diff --git a/Makefile b/Makefile index c083a61906..d97613b3e4 100644 --- a/Makefile +++ b/Makefile @@ -667,24 +667,36 @@ $(VALID_TARGETS): $(MAKE) -j binary hex TARGET=$@ && \ echo "Building $@ succeeded." -## clean : clean up all temporary / machine-generated files + + +CLEAN_TARGETS = $(addprefix clean_,$(VALID_TARGETS) ) +TARGETS_CLEAN = $(addsuffix _clean,$(VALID_TARGETS) ) + +## clean : clean up temporary / machine-generated files clean: + echo "Cleaning $(TARGET)" rm -f $(CLEAN_ARTIFACTS) rm -rf $(OBJECT_DIR)/$(TARGET) + echo "Cleaning $(TARGET) succeeded." -## clean_test : clean up all temporary / machine-generated files (tests) +## clean_test : clean up temporary / machine-generated files (tests) clean_test: cd src/test && $(MAKE) clean || true -## clean_all_targets : clean all valid target platforms -clean_all: - for clean_target in $(VALID_TARGETS); do \ - echo "" && \ - echo "Cleaning $$clean_target" && \ - $(MAKE) -j TARGET=$$clean_target clean || \ - break; \ - echo "Cleaning $$clean_target succeeded."; \ - done +## clean_ : clean up one specific target +$(CLEAN_TARGETS) : + $(MAKE) -j TARGET=$(subst clean_,,$@) clean + +## _clean : clean up one specific target (alias for above) +$(TARGETS_CLEAN) : + $(MAKE) -j TARGET=$(subst _clean,,$@) clean + +## clean_all : clean all valid targets +clean_all:$(CLEAN_TARGETS) + +## all_clean : clean all valid targets (alias for above) +all_clean:$(TARGETS_CLEAN) + flash_$(TARGET): $(TARGET_HEX) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon diff --git a/README.md b/README.md index 0239f59611..0253334eff 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,6 @@ # Betaflight -![Betaflight](https://dl.dropboxusercontent.com/u/31537757/betaflight%20logo.jpg) +![Betaflight](https://camo.githubusercontent.com/8178215d6cb90842dc95c9d437b1bdf09b2d57a7/687474703a2f2f7374617469632e726367726f7570732e6e65742f666f72756d732f6174746163686d656e74732f362f312f302f332f372f362f61393038383930302d3232382d62665f6c6f676f2e6a7067) Clean-code version of baseflight flight-controller - flight controllers are used to fly multi-rotor craft and fixed wing craft. diff --git a/fake_travis_build.sh b/fake_travis_build.sh index 5bae319ada..1a2c9af909 100755 --- a/fake_travis_build.sh +++ b/fake_travis_build.sh @@ -20,7 +20,10 @@ targets=("PUBLISHMETA=True" \ "TARGET=ALIENFLIGHTF3" \ "TARGET=DOGE" \ "TARGET=SINGULARITY" \ - "TARGET=SIRINFPV") + "TARGET=SIRINFPV" \ + "TARGET=X_RACERSPI") + + #fake a travis build environment export TRAVIS_BUILD_NUMBER=$(date +%s) @@ -30,9 +33,9 @@ export TRAVIS_REPO_SLUG=${TRAVIS_REPO_SLUG:=$USER/simulated} for target in "${targets[@]}" do unset RUNTESTS PUBLISHMETA TARGET - echo - echo - echo "BUILDING '$target'" + echo + echo + echo "BUILDING '$target'" eval "export $target" make -f Makefile clean ./.travis.sh diff --git a/lib/main/CMSIS/CM4/CoreSupport/arm_common_tables.h b/lib/main/CMSIS/CM4/CoreSupport/arm_common_tables.h index 76aadca490..039cc3d66b 100644 --- a/lib/main/CMSIS/CM4/CoreSupport/arm_common_tables.h +++ b/lib/main/CMSIS/CM4/CoreSupport/arm_common_tables.h @@ -1,8 +1,8 @@ /* ---------------------------------------------------------------------- * Copyright (C) 2010-2014 ARM Limited. All rights reserved. * -* $Date: 31. July 2014 -* $Revision: V1.4.4 +* $Date: 19. March 2015 +* $Revision: V.1.4.5 * * Project: CMSIS DSP Library * Title: arm_common_tables.h diff --git a/lib/main/CMSIS/CM4/CoreSupport/arm_const_structs.h b/lib/main/CMSIS/CM4/CoreSupport/arm_const_structs.h index 217f1d50e2..726d06eb69 100644 --- a/lib/main/CMSIS/CM4/CoreSupport/arm_const_structs.h +++ b/lib/main/CMSIS/CM4/CoreSupport/arm_const_structs.h @@ -1,8 +1,8 @@ /* ---------------------------------------------------------------------- * Copyright (C) 2010-2014 ARM Limited. All rights reserved. * -* $Date: 31. July 2014 -* $Revision: V1.4.4 +* $Date: 19. March 2015 +* $Revision: V.1.4.5 * * Project: CMSIS DSP Library * Title: arm_const_structs.h diff --git a/lib/main/CMSIS/CM4/CoreSupport/arm_math.h b/lib/main/CMSIS/CM4/CoreSupport/arm_math.h index f06a0713eb..e4b2f62e80 100644 --- a/lib/main/CMSIS/CM4/CoreSupport/arm_math.h +++ b/lib/main/CMSIS/CM4/CoreSupport/arm_math.h @@ -1,8 +1,8 @@ /* ---------------------------------------------------------------------- -* Copyright (C) 2010-2014 ARM Limited. All rights reserved. +* Copyright (C) 2010-2015 ARM Limited. All rights reserved. * -* $Date: 12. March 2014 -* $Revision: V1.4.4 +* $Date: 19. March 2015 +* $Revision: V.1.4.5 * * Project: CMSIS DSP Library * Title: arm_math.h @@ -66,19 +66,25 @@ * ------------ * * The library installer contains prebuilt versions of the libraries in the Lib folder. + * - arm_cortexM7lfdp_math.lib (Little endian and Double Precision Floating Point Unit on Cortex-M7) + * - arm_cortexM7bfdp_math.lib (Big endian and Double Precision Floating Point Unit on Cortex-M7) + * - arm_cortexM7lfsp_math.lib (Little endian and Single Precision Floating Point Unit on Cortex-M7) + * - arm_cortexM7bfsp_math.lib (Big endian and Single Precision Floating Point Unit on Cortex-M7) + * - arm_cortexM7l_math.lib (Little endian on Cortex-M7) + * - arm_cortexM7b_math.lib (Big endian on Cortex-M7) * - arm_cortexM4lf_math.lib (Little endian and Floating Point Unit on Cortex-M4) * - arm_cortexM4bf_math.lib (Big endian and Floating Point Unit on Cortex-M4) * - arm_cortexM4l_math.lib (Little endian on Cortex-M4) * - arm_cortexM4b_math.lib (Big endian on Cortex-M4) * - arm_cortexM3l_math.lib (Little endian on Cortex-M3) * - arm_cortexM3b_math.lib (Big endian on Cortex-M3) - * - arm_cortexM0l_math.lib (Little endian on Cortex-M0) - * - arm_cortexM0b_math.lib (Big endian on Cortex-M3) + * - arm_cortexM0l_math.lib (Little endian on Cortex-M0 / CortexM0+) + * - arm_cortexM0b_math.lib (Big endian on Cortex-M0 / CortexM0+) * * The library functions are declared in the public file arm_math.h which is placed in the Include folder. * Simply include this file and link the appropriate library in the application and begin calling the library functions. The Library supports single - * public header file arm_math.h for Cortex-M4/M3/M0 with little endian and big endian. Same header file will be used for floating point unit(FPU) variants. - * Define the appropriate pre processor MACRO ARM_MATH_CM4 or ARM_MATH_CM3 or + * public header file arm_math.h for Cortex-M7/M4/M3/M0/M0+ with little endian and big endian. Same header file will be used for floating point unit(FPU) variants. + * Define the appropriate pre processor MACRO ARM_MATH_CM7 or ARM_MATH_CM4 or ARM_MATH_CM3 or * ARM_MATH_CM0 or ARM_MATH_CM0PLUS depending on the target processor in the application. * * Examples @@ -89,17 +95,17 @@ * Toolchain Support * ------------ * - * The library has been developed and tested with MDK-ARM version 4.60. + * The library has been developed and tested with MDK-ARM version 5.14.0.0 * The library is being tested in GCC and IAR toolchains and updates on this activity will be made available shortly. * * Building the Library * ------------ * * The library installer contains a project file to re build libraries on MDK-ARM Tool chain in the CMSIS\\DSP_Lib\\Source\\ARM folder. - * - arm_cortexM_math.uvproj + * - arm_cortexM_math.uvprojx * * - * The libraries can be built by opening the arm_cortexM_math.uvproj project in MDK-ARM, selecting a specific target, and defining the optional pre processor MACROs detailed above. + * The libraries can be built by opening the arm_cortexM_math.uvprojx project in MDK-ARM, selecting a specific target, and defining the optional pre processor MACROs detailed above. * * Pre-processor Macros * ------------ @@ -125,7 +131,8 @@ * - ARM_MATH_CMx: * * Define macro ARM_MATH_CM4 for building the library on Cortex-M4 target, ARM_MATH_CM3 for building library on Cortex-M3 target - * and ARM_MATH_CM0 for building library on cortex-M0 target, ARM_MATH_CM0PLUS for building library on cortex-M0+ target. + * and ARM_MATH_CM0 for building library on Cortex-M0 target, ARM_MATH_CM0PLUS for building library on Cortex-M0+ target, and + * ARM_MATH_CM7 for building the library on cortex-M7. * * - __FPU_PRESENT: * @@ -151,7 +158,7 @@ * Copyright Notice * ------------ * - * Copyright (C) 2010-2014 ARM Limited. All rights reserved. + * Copyright (C) 2010-2015 ARM Limited. All rights reserved. */ @@ -400,19 +407,22 @@ extern "C" * @brief definition to read/write two 16 bit values. */ #if defined __CC_ARM -#define __SIMD32_TYPE int32_t __packed -#define CMSIS_UNUSED __attribute__((unused)) + #define __SIMD32_TYPE int32_t __packed + #define CMSIS_UNUSED __attribute__((unused)) #elif defined __ICCARM__ -#define CMSIS_UNUSED -#define __SIMD32_TYPE int32_t __packed + #define __SIMD32_TYPE int32_t __packed + #define CMSIS_UNUSED #elif defined __GNUC__ -#define __SIMD32_TYPE int32_t -#define CMSIS_UNUSED __attribute__((unused)) + #define __SIMD32_TYPE int32_t + #define CMSIS_UNUSED __attribute__((unused)) #elif defined __CSMC__ /* Cosmic */ -#define CMSIS_UNUSED -#define __SIMD32_TYPE int32_t + #define __SIMD32_TYPE int32_t + #define CMSIS_UNUSED +#elif defined __TASKING__ + #define __SIMD32_TYPE __unaligned int32_t + #define CMSIS_UNUSED #else -#error Unknown compiler + #error Unknown compiler #endif #define __SIMD32(addr) (*(__SIMD32_TYPE **) & (addr)) @@ -506,11 +516,12 @@ extern "C" } -#if defined (ARM_MATH_CM0_FAMILY) && defined ( __CC_ARM ) -#define __CLZ __clz -#endif +//#if defined (ARM_MATH_CM0_FAMILY) && defined ( __CC_ARM ) +//#define __CLZ __clz +//#endif -#if defined (ARM_MATH_CM0_FAMILY) && ((defined (__ICCARM__)) ||(defined (__GNUC__)) || defined (__TASKING__) ) +//note: function can be removed when all toolchain support __CLZ for Cortex-M0 +#if defined (ARM_MATH_CM0_FAMILY) && ((defined (__ICCARM__)) ) static __INLINE uint32_t __CLZ( q31_t data); @@ -6090,7 +6101,7 @@ void arm_rfft_fast_f32( float32_t in, float32_t * pOut) { - if(in > 0) + if(in >= 0.0f) { // #if __FPU_USED @@ -7522,6 +7533,13 @@ void arm_rfft_fast_f32( #define IAR_ONLY_LOW_OPTIMIZATION_ENTER #define IAR_ONLY_LOW_OPTIMIZATION_EXIT +#elif defined(__TASKING__) // TASKING + +#define LOW_OPTIMIZATION_ENTER +#define LOW_OPTIMIZATION_EXIT +#define IAR_ONLY_LOW_OPTIMIZATION_ENTER +#define IAR_ONLY_LOW_OPTIMIZATION_EXIT + #endif diff --git a/lib/main/CMSIS/CM4/CoreSupport/core_cm0.h b/lib/main/CMSIS/CM4/CoreSupport/core_cm0.h index 5186cb4838..cf2b5d66ba 100644 --- a/lib/main/CMSIS/CM4/CoreSupport/core_cm0.h +++ b/lib/main/CMSIS/CM4/CoreSupport/core_cm0.h @@ -1,13 +1,13 @@ /**************************************************************************//** * @file core_cm0.h * @brief CMSIS Cortex-M0 Core Peripheral Access Layer Header File - * @version V4.00 - * @date 22. August 2014 + * @version V4.10 + * @date 18. March 2015 * * @note * ******************************************************************************/ -/* Copyright (c) 2009 - 2014 ARM LIMITED +/* Copyright (c) 2009 - 2015 ARM LIMITED All rights reserved. Redistribution and use in source and binary forms, with or without @@ -225,14 +225,7 @@ typedef union { struct { -#if (__CORTEX_M != 0x04) - uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */ -#else - 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 */ -#endif - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t _reserved0:28; /*!< bit: 0..27 Reserved */ uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ uint32_t C:1; /*!< bit: 29 Carry condition code flag */ uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ @@ -241,6 +234,19 @@ typedef union uint32_t w; /*!< Type used for word access */ } APSR_Type; +/* APSR Register Definitions */ +#define APSR_N_Pos 31 /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30 /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29 /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28 /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + /** \brief Union type to access the Interrupt Program Status Register (IPSR). */ @@ -254,6 +260,10 @@ typedef union uint32_t w; /*!< Type used for word access */ } IPSR_Type; +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0 /*!< 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). */ @@ -262,16 +272,9 @@ typedef union struct { uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ -#if (__CORTEX_M != 0x04) uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ -#else - uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ -#endif uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ - uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t _reserved1:3; /*!< bit: 25..27 Reserved */ uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ uint32_t C:1; /*!< bit: 29 Carry condition code flag */ uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ @@ -280,6 +283,25 @@ typedef union uint32_t w; /*!< Type used for word access */ } xPSR_Type; +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31 /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30 /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29 /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28 /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_T_Pos 24 /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_ISR_Pos 0 /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + /** \brief Union type to access the Control Registers (CONTROL). */ @@ -287,14 +309,17 @@ typedef union { struct { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ + uint32_t _reserved0:1; /*!< bit: 0 Reserved */ 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 */ + uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ } b; /*!< Structure used for bit access */ uint32_t w; /*!< Type used for word access */ } CONTROL_Type; +/* CONTROL Register Definitions */ +#define CONTROL_SPSEL_Pos 1 /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + /*@} end of group CMSIS_CORE */ @@ -358,7 +383,7 @@ typedef struct #define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ #define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */ +#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 31 /*!< SCB ICSR: NMIPENDSET Position */ @@ -386,7 +411,7 @@ typedef struct #define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ #define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ /* SCB Application Interrupt and Reset Control Register Definitions */ #define SCB_AIRCR_VECTKEY_Pos 16 /*!< SCB AIRCR: VECTKEY Position */ @@ -455,15 +480,15 @@ typedef struct #define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ #define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */ +#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ /* SysTick Reload Register Definitions */ #define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ /* SysTick Current Register Definitions */ #define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ /* SysTick Calibration Register Definitions */ #define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */ @@ -473,7 +498,7 @@ typedef struct #define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ #define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL << SysTick_CALIB_TENMS_Pos) /*!< SysTick CALIB: TENMS Mask */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ /*@} end of group CMSIS_SysTick */ @@ -530,9 +555,9 @@ typedef struct /* Interrupt Priorities are WORD accessible only under ARMv6M */ /* The following MACROS handle generation of the register offset and byte masks */ -#define _BIT_SHIFT(IRQn) ( (((uint32_t)(IRQn) ) & 0x03) * 8 ) -#define _SHP_IDX(IRQn) ( ((((uint32_t)(IRQn) & 0x0F)-8) >> 2) ) -#define _IP_IDX(IRQn) ( ((uint32_t)(IRQn) >> 2) ) +#define _BIT_SHIFT(IRQn) ( ((((uint32_t)(int32_t)(IRQn)) ) & 0x03UL) * 8UL) +#define _SHP_IDX(IRQn) ( (((((uint32_t)(int32_t)(IRQn)) & 0x0FUL)-8UL) >> 2UL) ) +#define _IP_IDX(IRQn) ( (((uint32_t)(int32_t)(IRQn)) >> 2UL) ) /** \brief Enable External Interrupt @@ -543,7 +568,7 @@ typedef struct */ __STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) { - NVIC->ISER[0] = (1 << ((uint32_t)(IRQn) & 0x1F)); + NVIC->ISER[0] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -555,7 +580,7 @@ __STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) { - NVIC->ICER[0] = (1 << ((uint32_t)(IRQn) & 0x1F)); + NVIC->ICER[0] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -571,7 +596,7 @@ __STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) */ __STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) { - return((uint32_t) ((NVIC->ISPR[0] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); + return((uint32_t)(((NVIC->ISPR[0] & (1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); } @@ -583,7 +608,7 @@ __STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) { - NVIC->ISPR[0] = (1 << ((uint32_t)(IRQn) & 0x1F)); + NVIC->ISPR[0] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -595,7 +620,7 @@ __STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) { - NVIC->ICPR[0] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */ + NVIC->ICPR[0] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -610,12 +635,14 @@ __STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) { - if(IRQn < 0) { - SCB->SHP[_SHP_IDX(IRQn)] = (SCB->SHP[_SHP_IDX(IRQn)] & ~(0xFF << _BIT_SHIFT(IRQn))) | - (((priority << (8 - __NVIC_PRIO_BITS)) & 0xFF) << _BIT_SHIFT(IRQn)); } + if((int32_t)(IRQn) < 0) { + SCB->SHP[_SHP_IDX(IRQn)] = ((uint32_t)(SCB->SHP[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | + (((priority << (8 - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); + } else { - NVIC->IP[_IP_IDX(IRQn)] = (NVIC->IP[_IP_IDX(IRQn)] & ~(0xFF << _BIT_SHIFT(IRQn))) | - (((priority << (8 - __NVIC_PRIO_BITS)) & 0xFF) << _BIT_SHIFT(IRQn)); } + NVIC->IP[_IP_IDX(IRQn)] = ((uint32_t)(NVIC->IP[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | + (((priority << (8 - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); + } } @@ -633,10 +660,12 @@ __STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) __STATIC_INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) { - if(IRQn < 0) { - return((uint32_t)(((SCB->SHP[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & 0xFF) >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M0 system interrupts */ + if((int32_t)(IRQn) < 0) { + return((uint32_t)(((SCB->SHP[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8 - __NVIC_PRIO_BITS))); + } else { - return((uint32_t)(((NVIC->IP[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & 0xFF) >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */ + return((uint32_t)(((NVIC->IP[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8 - __NVIC_PRIO_BITS))); + } } @@ -648,10 +677,10 @@ __STATIC_INLINE void NVIC_SystemReset(void) { __DSB(); /* Ensure all outstanding memory accesses included buffered write are completed before reset */ - SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) | + SCB->AIRCR = ((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | SCB_AIRCR_SYSRESETREQ_Msk); __DSB(); /* Ensure completion of memory access */ - while(1); /* wait until reset */ + while(1) { __NOP(); } /* wait until reset */ } /*@} end of CMSIS_Core_NVICFunctions */ @@ -684,15 +713,15 @@ __STATIC_INLINE void NVIC_SystemReset(void) */ __STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) { - if ((ticks - 1) > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) { return (1UL); } /* Reload value impossible */ - SysTick->LOAD = ticks - 1; /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0; /* Load the SysTick Counter Value */ + 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 (0); /* Function successful */ + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ } #endif diff --git a/lib/main/CMSIS/CM4/CoreSupport/core_cm0plus.h b/lib/main/CMSIS/CM4/CoreSupport/core_cm0plus.h index 17e43984fc..123cb400a2 100644 --- a/lib/main/CMSIS/CM4/CoreSupport/core_cm0plus.h +++ b/lib/main/CMSIS/CM4/CoreSupport/core_cm0plus.h @@ -1,13 +1,13 @@ /**************************************************************************//** * @file core_cm0plus.h * @brief CMSIS Cortex-M0+ Core Peripheral Access Layer Header File - * @version V4.00 - * @date 22. August 2014 + * @version V4.10 + * @date 18. March 2015 * * @note * ******************************************************************************/ -/* Copyright (c) 2009 - 2014 ARM LIMITED +/* Copyright (c) 2009 - 2015 ARM LIMITED All rights reserved. Redistribution and use in source and binary forms, with or without @@ -236,14 +236,7 @@ typedef union { struct { -#if (__CORTEX_M != 0x04) - uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */ -#else - 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 */ -#endif - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t _reserved0:28; /*!< bit: 0..27 Reserved */ uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ uint32_t C:1; /*!< bit: 29 Carry condition code flag */ uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ @@ -252,6 +245,19 @@ typedef union uint32_t w; /*!< Type used for word access */ } APSR_Type; +/* APSR Register Definitions */ +#define APSR_N_Pos 31 /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30 /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29 /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28 /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + /** \brief Union type to access the Interrupt Program Status Register (IPSR). */ @@ -265,6 +271,10 @@ typedef union uint32_t w; /*!< Type used for word access */ } IPSR_Type; +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0 /*!< 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). */ @@ -273,16 +283,9 @@ typedef union struct { uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ -#if (__CORTEX_M != 0x04) uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ -#else - uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ -#endif uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ - uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t _reserved1:3; /*!< bit: 25..27 Reserved */ uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ uint32_t C:1; /*!< bit: 29 Carry condition code flag */ uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ @@ -291,6 +294,25 @@ typedef union uint32_t w; /*!< Type used for word access */ } xPSR_Type; +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31 /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30 /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29 /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28 /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_T_Pos 24 /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_ISR_Pos 0 /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + /** \brief Union type to access the Control Registers (CONTROL). */ @@ -300,12 +322,18 @@ typedef union { 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 */ + uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ } b; /*!< Structure used for bit access */ uint32_t w; /*!< Type used for word access */ } CONTROL_Type; +/* CONTROL Register Definitions */ +#define CONTROL_SPSEL_Pos 1 /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + +#define CONTROL_nPRIV_Pos 0 /*!< CONTROL: nPRIV Position */ +#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ + /*@} end of group CMSIS_CORE */ @@ -373,7 +401,7 @@ typedef struct #define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ #define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */ +#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 31 /*!< SCB ICSR: NMIPENDSET Position */ @@ -401,7 +429,7 @@ typedef struct #define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ #define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ #if (__VTOR_PRESENT == 1) /* SCB Interrupt Control State Register Definitions */ @@ -476,15 +504,15 @@ typedef struct #define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ #define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */ +#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ /* SysTick Reload Register Definitions */ #define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ /* SysTick Current Register Definitions */ #define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ /* SysTick Calibration Register Definitions */ #define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */ @@ -494,7 +522,7 @@ typedef struct #define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ #define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL << SysTick_CALIB_TENMS_Pos) /*!< SysTick CALIB: TENMS Mask */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ /*@} end of group CMSIS_SysTick */ @@ -524,7 +552,7 @@ typedef struct #define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ #define MPU_TYPE_SEPARATE_Pos 0 /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL << MPU_TYPE_SEPARATE_Pos) /*!< MPU TYPE: SEPARATE Mask */ +#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ /* MPU Control Register */ #define MPU_CTRL_PRIVDEFENA_Pos 2 /*!< MPU CTRL: PRIVDEFENA Position */ @@ -534,11 +562,11 @@ typedef struct #define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ #define MPU_CTRL_ENABLE_Pos 0 /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL << MPU_CTRL_ENABLE_Pos) /*!< MPU CTRL: ENABLE Mask */ +#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ /* MPU Region Number Register */ #define MPU_RNR_REGION_Pos 0 /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL << MPU_RNR_REGION_Pos) /*!< MPU RNR: REGION Mask */ +#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ /* MPU Region Base Address Register */ #define MPU_RBAR_ADDR_Pos 8 /*!< MPU RBAR: ADDR Position */ @@ -548,7 +576,7 @@ typedef struct #define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ #define MPU_RBAR_REGION_Pos 0 /*!< MPU RBAR: REGION Position */ -#define MPU_RBAR_REGION_Msk (0xFUL << MPU_RBAR_REGION_Pos) /*!< MPU RBAR: REGION Mask */ +#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ /* MPU Region Attribute and Size Register */ #define MPU_RASR_ATTRS_Pos 16 /*!< MPU RASR: MPU Region Attribute field Position */ @@ -579,7 +607,7 @@ typedef struct #define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ #define MPU_RASR_ENABLE_Pos 0 /*!< MPU RASR: Region enable bit Position */ -#define MPU_RASR_ENABLE_Msk (1UL << MPU_RASR_ENABLE_Pos) /*!< MPU RASR: Region enable bit Disable Mask */ +#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ /*@} end of group CMSIS_MPU */ #endif @@ -641,9 +669,9 @@ typedef struct /* Interrupt Priorities are WORD accessible only under ARMv6M */ /* The following MACROS handle generation of the register offset and byte masks */ -#define _BIT_SHIFT(IRQn) ( (((uint32_t)(IRQn) ) & 0x03) * 8 ) -#define _SHP_IDX(IRQn) ( ((((uint32_t)(IRQn) & 0x0F)-8) >> 2) ) -#define _IP_IDX(IRQn) ( ((uint32_t)(IRQn) >> 2) ) +#define _BIT_SHIFT(IRQn) ( ((((uint32_t)(int32_t)(IRQn)) ) & 0x03UL) * 8UL) +#define _SHP_IDX(IRQn) ( (((((uint32_t)(int32_t)(IRQn)) & 0x0FUL)-8UL) >> 2UL) ) +#define _IP_IDX(IRQn) ( (((uint32_t)(int32_t)(IRQn)) >> 2UL) ) /** \brief Enable External Interrupt @@ -654,7 +682,7 @@ typedef struct */ __STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) { - NVIC->ISER[0] = (1 << ((uint32_t)(IRQn) & 0x1F)); + NVIC->ISER[0] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -666,7 +694,7 @@ __STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) { - NVIC->ICER[0] = (1 << ((uint32_t)(IRQn) & 0x1F)); + NVIC->ICER[0] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -682,7 +710,7 @@ __STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) */ __STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) { - return((uint32_t) ((NVIC->ISPR[0] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); + return((uint32_t)(((NVIC->ISPR[0] & (1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); } @@ -694,7 +722,7 @@ __STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) { - NVIC->ISPR[0] = (1 << ((uint32_t)(IRQn) & 0x1F)); + NVIC->ISPR[0] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -706,7 +734,7 @@ __STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) { - NVIC->ICPR[0] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */ + NVIC->ICPR[0] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -721,12 +749,14 @@ __STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) { - if(IRQn < 0) { - SCB->SHP[_SHP_IDX(IRQn)] = (SCB->SHP[_SHP_IDX(IRQn)] & ~(0xFF << _BIT_SHIFT(IRQn))) | - (((priority << (8 - __NVIC_PRIO_BITS)) & 0xFF) << _BIT_SHIFT(IRQn)); } + if((int32_t)(IRQn) < 0) { + SCB->SHP[_SHP_IDX(IRQn)] = ((uint32_t)(SCB->SHP[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | + (((priority << (8 - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); + } else { - NVIC->IP[_IP_IDX(IRQn)] = (NVIC->IP[_IP_IDX(IRQn)] & ~(0xFF << _BIT_SHIFT(IRQn))) | - (((priority << (8 - __NVIC_PRIO_BITS)) & 0xFF) << _BIT_SHIFT(IRQn)); } + NVIC->IP[_IP_IDX(IRQn)] = ((uint32_t)(NVIC->IP[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | + (((priority << (8 - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); + } } @@ -744,10 +774,12 @@ __STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) __STATIC_INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) { - if(IRQn < 0) { - return((uint32_t)(((SCB->SHP[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & 0xFF) >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M0 system interrupts */ + if((int32_t)(IRQn) < 0) { + return((uint32_t)(((SCB->SHP[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8 - __NVIC_PRIO_BITS))); + } else { - return((uint32_t)(((NVIC->IP[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & 0xFF) >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */ + return((uint32_t)(((NVIC->IP[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8 - __NVIC_PRIO_BITS))); + } } @@ -759,10 +791,10 @@ __STATIC_INLINE void NVIC_SystemReset(void) { __DSB(); /* Ensure all outstanding memory accesses included buffered write are completed before reset */ - SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) | + SCB->AIRCR = ((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | SCB_AIRCR_SYSRESETREQ_Msk); __DSB(); /* Ensure completion of memory access */ - while(1); /* wait until reset */ + while(1) { __NOP(); } /* wait until reset */ } /*@} end of CMSIS_Core_NVICFunctions */ @@ -795,15 +827,15 @@ __STATIC_INLINE void NVIC_SystemReset(void) */ __STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) { - if ((ticks - 1) > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) {return (1UL);} /* Reload value impossible */ - SysTick->LOAD = ticks - 1; /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0; /* Load the SysTick Counter Value */ + 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 (0); /* Function successful */ + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ } #endif diff --git a/lib/main/CMSIS/CM4/CoreSupport/core_cm3.h b/lib/main/CMSIS/CM4/CoreSupport/core_cm3.h index e1357c6735..092ee23da9 100644 --- a/lib/main/CMSIS/CM4/CoreSupport/core_cm3.h +++ b/lib/main/CMSIS/CM4/CoreSupport/core_cm3.h @@ -1,13 +1,13 @@ /**************************************************************************//** * @file core_cm3.h * @brief CMSIS Cortex-M3 Core Peripheral Access Layer Header File - * @version V4.00 - * @date 22. August 2014 + * @version V4.10 + * @date 18. March 2015 * * @note * ******************************************************************************/ -/* Copyright (c) 2009 - 2014 ARM LIMITED +/* Copyright (c) 2009 - 2015 ARM LIMITED All rights reserved. Redistribution and use in source and binary forms, with or without @@ -232,13 +232,7 @@ typedef union { struct { -#if (__CORTEX_M != 0x04) uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */ -#else - 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 */ -#endif 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 */ @@ -248,6 +242,22 @@ typedef union uint32_t w; /*!< Type used for word access */ } APSR_Type; +/* APSR Register Definitions */ +#define APSR_N_Pos 31 /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30 /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29 /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28 /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + +#define APSR_Q_Pos 27 /*!< APSR: Q Position */ +#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ + /** \brief Union type to access the Interrupt Program Status Register (IPSR). */ @@ -261,6 +271,10 @@ typedef union uint32_t w; /*!< Type used for word access */ } IPSR_Type; +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0 /*!< 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). */ @@ -269,13 +283,7 @@ typedef union struct { uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ -#if (__CORTEX_M != 0x04) uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ -#else - uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ -#endif uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */ uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ @@ -287,6 +295,31 @@ typedef union uint32_t w; /*!< Type used for word access */ } xPSR_Type; +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31 /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30 /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29 /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28 /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_Q_Pos 27 /*!< xPSR: Q Position */ +#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ + +#define xPSR_IT_Pos 25 /*!< xPSR: IT Position */ +#define xPSR_IT_Msk (3UL << xPSR_IT_Pos) /*!< xPSR: IT Mask */ + +#define xPSR_T_Pos 24 /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_ISR_Pos 0 /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + /** \brief Union type to access the Control Registers (CONTROL). */ @@ -296,12 +329,18 @@ typedef union { 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 */ + uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ } b; /*!< Structure used for bit access */ uint32_t w; /*!< Type used for word access */ } CONTROL_Type; +/* CONTROL Register Definitions */ +#define CONTROL_SPSEL_Pos 1 /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + +#define CONTROL_nPRIV_Pos 0 /*!< CONTROL: nPRIV Position */ +#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ + /*@} end of group CMSIS_CORE */ @@ -332,7 +371,7 @@ typedef struct /* Software Triggered Interrupt Register Definitions */ #define NVIC_STIR_INTID_Pos 0 /*!< STIR: INTLINESNUM Position */ -#define NVIC_STIR_INTID_Msk (0x1FFUL << NVIC_STIR_INTID_Pos) /*!< STIR: INTLINESNUM Mask */ +#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ /*@} end of group CMSIS_NVIC */ @@ -384,7 +423,7 @@ typedef struct #define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ #define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */ +#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 31 /*!< SCB ICSR: NMIPENDSET Position */ @@ -415,7 +454,7 @@ typedef struct #define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ #define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ /* SCB Vector Table Offset Register Definitions */ #if (__CM3_REV < 0x0201) /* core r2p1 */ @@ -449,7 +488,7 @@ typedef struct #define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ #define SCB_AIRCR_VECTRESET_Pos 0 /*!< SCB AIRCR: VECTRESET Position */ -#define SCB_AIRCR_VECTRESET_Msk (1UL << SCB_AIRCR_VECTRESET_Pos) /*!< SCB AIRCR: VECTRESET Mask */ +#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ /* SCB System Control Register Definitions */ #define SCB_SCR_SEVONPEND_Pos 4 /*!< SCB SCR: SEVONPEND Position */ @@ -478,7 +517,7 @@ typedef struct #define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ #define SCB_CCR_NONBASETHRDENA_Pos 0 /*!< SCB CCR: NONBASETHRDENA Position */ -#define SCB_CCR_NONBASETHRDENA_Msk (1UL << SCB_CCR_NONBASETHRDENA_Pos) /*!< SCB CCR: NONBASETHRDENA Mask */ +#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 18 /*!< SCB SHCSR: USGFAULTENA Position */ @@ -521,7 +560,7 @@ typedef struct #define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ #define SCB_SHCSR_MEMFAULTACT_Pos 0 /*!< SCB SHCSR: MEMFAULTACT Position */ -#define SCB_SHCSR_MEMFAULTACT_Msk (1UL << SCB_SHCSR_MEMFAULTACT_Pos) /*!< SCB SHCSR: MEMFAULTACT Mask */ +#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ /* SCB Configurable Fault Status Registers Definitions */ #define SCB_CFSR_USGFAULTSR_Pos 16 /*!< SCB CFSR: Usage Fault Status Register Position */ @@ -531,7 +570,7 @@ typedef struct #define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ #define SCB_CFSR_MEMFAULTSR_Pos 0 /*!< 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 */ +#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ /* SCB Hard Fault Status Registers Definitions */ #define SCB_HFSR_DEBUGEVT_Pos 31 /*!< SCB HFSR: DEBUGEVT Position */ @@ -557,7 +596,7 @@ typedef struct #define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ #define SCB_DFSR_HALTED_Pos 0 /*!< SCB DFSR: HALTED Position */ -#define SCB_DFSR_HALTED_Msk (1UL << SCB_DFSR_HALTED_Pos) /*!< SCB DFSR: HALTED Mask */ +#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ /*@} end of group CMSIS_SCB */ @@ -583,7 +622,7 @@ typedef struct /* Interrupt Controller Type Register Definitions */ #define SCnSCB_ICTR_INTLINESNUM_Pos 0 /*!< ICTR: INTLINESNUM Position */ -#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL << SCnSCB_ICTR_INTLINESNUM_Pos) /*!< ICTR: INTLINESNUM Mask */ +#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ /* Auxiliary Control Register Definitions */ @@ -594,7 +633,7 @@ typedef struct #define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */ #define SCnSCB_ACTLR_DISMCYCINT_Pos 0 /*!< ACTLR: DISMCYCINT Position */ -#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL << SCnSCB_ACTLR_DISMCYCINT_Pos) /*!< ACTLR: DISMCYCINT Mask */ +#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ /*@} end of group CMSIS_SCnotSCB */ @@ -626,15 +665,15 @@ typedef struct #define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ #define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */ +#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ /* SysTick Reload Register Definitions */ #define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ /* SysTick Current Register Definitions */ #define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ /* SysTick Calibration Register Definitions */ #define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */ @@ -644,7 +683,7 @@ typedef struct #define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ #define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL << SysTick_CALIB_TENMS_Pos) /*!< SysTick CALIB: TENMS Mask */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ /*@} end of group CMSIS_SysTick */ @@ -695,7 +734,7 @@ typedef struct /* ITM Trace Privilege Register Definitions */ #define ITM_TPR_PRIVMASK_Pos 0 /*!< ITM TPR: PRIVMASK Position */ -#define ITM_TPR_PRIVMASK_Msk (0xFUL << ITM_TPR_PRIVMASK_Pos) /*!< ITM TPR: PRIVMASK Mask */ +#define ITM_TPR_PRIVMASK_Msk (0xFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ /* ITM Trace Control Register Definitions */ #define ITM_TCR_BUSY_Pos 23 /*!< ITM TCR: BUSY Position */ @@ -723,19 +762,19 @@ typedef struct #define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ #define ITM_TCR_ITMENA_Pos 0 /*!< ITM TCR: ITM Enable bit Position */ -#define ITM_TCR_ITMENA_Msk (1UL << ITM_TCR_ITMENA_Pos) /*!< ITM TCR: ITM Enable bit Mask */ +#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ /* ITM Integration Write Register Definitions */ #define ITM_IWR_ATVALIDM_Pos 0 /*!< ITM IWR: ATVALIDM Position */ -#define ITM_IWR_ATVALIDM_Msk (1UL << ITM_IWR_ATVALIDM_Pos) /*!< ITM IWR: ATVALIDM Mask */ +#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */ /* ITM Integration Read Register Definitions */ #define ITM_IRR_ATREADYM_Pos 0 /*!< ITM IRR: ATREADYM Position */ -#define ITM_IRR_ATREADYM_Msk (1UL << ITM_IRR_ATREADYM_Pos) /*!< ITM IRR: ATREADYM Mask */ +#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */ /* ITM Integration Mode Control Register Definitions */ #define ITM_IMCR_INTEGRATION_Pos 0 /*!< ITM IMCR: INTEGRATION Position */ -#define ITM_IMCR_INTEGRATION_Msk (1UL << ITM_IMCR_INTEGRATION_Pos) /*!< ITM IMCR: INTEGRATION Mask */ +#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */ /* ITM Lock Status Register Definitions */ #define ITM_LSR_ByteAcc_Pos 2 /*!< ITM LSR: ByteAcc Position */ @@ -745,7 +784,7 @@ typedef struct #define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ #define ITM_LSR_Present_Pos 0 /*!< ITM LSR: Present Position */ -#define ITM_LSR_Present_Msk (1UL << ITM_LSR_Present_Pos) /*!< ITM LSR: Present Mask */ +#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ /*@}*/ /* end of group CMSIS_ITM */ @@ -838,31 +877,31 @@ typedef struct #define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ #define DWT_CTRL_CYCCNTENA_Pos 0 /*!< DWT CTRL: CYCCNTENA Position */ -#define DWT_CTRL_CYCCNTENA_Msk (0x1UL << DWT_CTRL_CYCCNTENA_Pos) /*!< DWT CTRL: CYCCNTENA Mask */ +#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ /* DWT CPI Count Register Definitions */ #define DWT_CPICNT_CPICNT_Pos 0 /*!< DWT CPICNT: CPICNT Position */ -#define DWT_CPICNT_CPICNT_Msk (0xFFUL << DWT_CPICNT_CPICNT_Pos) /*!< DWT CPICNT: CPICNT Mask */ +#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 0 /*!< DWT EXCCNT: EXCCNT Position */ -#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL << DWT_EXCCNT_EXCCNT_Pos) /*!< DWT EXCCNT: EXCCNT Mask */ +#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ /* DWT Sleep Count Register Definitions */ #define DWT_SLEEPCNT_SLEEPCNT_Pos 0 /*!< DWT SLEEPCNT: SLEEPCNT Position */ -#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL << DWT_SLEEPCNT_SLEEPCNT_Pos) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ +#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ /* DWT LSU Count Register Definitions */ #define DWT_LSUCNT_LSUCNT_Pos 0 /*!< DWT LSUCNT: LSUCNT Position */ -#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL << DWT_LSUCNT_LSUCNT_Pos) /*!< DWT LSUCNT: LSUCNT Mask */ +#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 0 /*!< DWT FOLDCNT: FOLDCNT Position */ -#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL << DWT_FOLDCNT_FOLDCNT_Pos) /*!< DWT FOLDCNT: FOLDCNT Mask */ +#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ /* DWT Comparator Mask Register Definitions */ #define DWT_MASK_MASK_Pos 0 /*!< DWT MASK: MASK Position */ -#define DWT_MASK_MASK_Msk (0x1FUL << DWT_MASK_MASK_Pos) /*!< DWT MASK: MASK Mask */ +#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ /* DWT Comparator Function Register Definitions */ #define DWT_FUNCTION_MATCHED_Pos 24 /*!< DWT FUNCTION: MATCHED Position */ @@ -890,7 +929,7 @@ typedef struct #define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ #define DWT_FUNCTION_FUNCTION_Pos 0 /*!< DWT FUNCTION: FUNCTION Position */ -#define DWT_FUNCTION_FUNCTION_Msk (0xFUL << DWT_FUNCTION_FUNCTION_Pos) /*!< DWT FUNCTION: FUNCTION Mask */ +#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ /*@}*/ /* end of group CMSIS_DWT */ @@ -933,11 +972,11 @@ typedef struct /* TPI Asynchronous Clock Prescaler Register Definitions */ #define TPI_ACPR_PRESCALER_Pos 0 /*!< TPI ACPR: PRESCALER Position */ -#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL << TPI_ACPR_PRESCALER_Pos) /*!< TPI ACPR: PRESCALER Mask */ +#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 0 /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL << TPI_SPPR_TXMODE_Pos) /*!< TPI SPPR: TXMODE Mask */ +#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 3 /*!< TPI FFSR: FtNonStop Position */ @@ -950,7 +989,7 @@ typedef struct #define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ #define TPI_FFSR_FlInProg_Pos 0 /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL << TPI_FFSR_FlInProg_Pos) /*!< TPI FFSR: FlInProg Mask */ +#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 8 /*!< TPI FFCR: TrigIn Position */ @@ -961,7 +1000,7 @@ typedef struct /* TPI TRIGGER Register Definitions */ #define TPI_TRIGGER_TRIGGER_Pos 0 /*!< TPI TRIGGER: TRIGGER Position */ -#define TPI_TRIGGER_TRIGGER_Msk (0x1UL << TPI_TRIGGER_TRIGGER_Pos) /*!< TPI TRIGGER: TRIGGER Mask */ +#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 29 /*!< TPI FIFO0: ITM_ATVALID Position */ @@ -983,11 +1022,11 @@ typedef struct #define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ #define TPI_FIFO0_ETM0_Pos 0 /*!< TPI FIFO0: ETM0 Position */ -#define TPI_FIFO0_ETM0_Msk (0xFFUL << TPI_FIFO0_ETM0_Pos) /*!< TPI FIFO0: ETM0 Mask */ +#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ /* TPI ITATBCTR2 Register Definitions */ #define TPI_ITATBCTR2_ATREADY_Pos 0 /*!< TPI ITATBCTR2: ATREADY Position */ -#define TPI_ITATBCTR2_ATREADY_Msk (0x1UL << TPI_ITATBCTR2_ATREADY_Pos) /*!< TPI ITATBCTR2: ATREADY Mask */ +#define TPI_ITATBCTR2_ATREADY_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY_Pos*/) /*!< TPI ITATBCTR2: ATREADY Mask */ /* TPI Integration ITM Data Register Definitions (FIFO1) */ #define TPI_FIFO1_ITM_ATVALID_Pos 29 /*!< TPI FIFO1: ITM_ATVALID Position */ @@ -1009,15 +1048,15 @@ typedef struct #define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ #define TPI_FIFO1_ITM0_Pos 0 /*!< TPI FIFO1: ITM0 Position */ -#define TPI_FIFO1_ITM0_Msk (0xFFUL << TPI_FIFO1_ITM0_Pos) /*!< TPI FIFO1: ITM0 Mask */ +#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ /* TPI ITATBCTR0 Register Definitions */ #define TPI_ITATBCTR0_ATREADY_Pos 0 /*!< TPI ITATBCTR0: ATREADY Position */ -#define TPI_ITATBCTR0_ATREADY_Msk (0x1UL << TPI_ITATBCTR0_ATREADY_Pos) /*!< TPI ITATBCTR0: ATREADY Mask */ +#define TPI_ITATBCTR0_ATREADY_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY_Pos*/) /*!< TPI ITATBCTR0: ATREADY Mask */ /* TPI Integration Mode Control Register Definitions */ #define TPI_ITCTRL_Mode_Pos 0 /*!< TPI ITCTRL: Mode Position */ -#define TPI_ITCTRL_Mode_Msk (0x1UL << TPI_ITCTRL_Mode_Pos) /*!< TPI ITCTRL: Mode Mask */ +#define TPI_ITCTRL_Mode_Msk (0x1UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ /* TPI DEVID Register Definitions */ #define TPI_DEVID_NRZVALID_Pos 11 /*!< TPI DEVID: NRZVALID Position */ @@ -1036,15 +1075,15 @@ typedef struct #define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ #define TPI_DEVID_NrTraceInput_Pos 0 /*!< TPI DEVID: NrTraceInput Position */ -#define TPI_DEVID_NrTraceInput_Msk (0x1FUL << TPI_DEVID_NrTraceInput_Pos) /*!< TPI DEVID: NrTraceInput Mask */ +#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ /* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 0 /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL << TPI_DEVTYPE_SubType_Pos) /*!< TPI DEVTYPE: SubType Mask */ - #define TPI_DEVTYPE_MajorType_Pos 4 /*!< TPI DEVTYPE: MajorType Position */ #define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ +#define TPI_DEVTYPE_SubType_Pos 0 /*!< TPI DEVTYPE: SubType Position */ +#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ + /*@}*/ /* end of group CMSIS_TPI */ @@ -1080,7 +1119,7 @@ typedef struct #define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ #define MPU_TYPE_SEPARATE_Pos 0 /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL << MPU_TYPE_SEPARATE_Pos) /*!< MPU TYPE: SEPARATE Mask */ +#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ /* MPU Control Register */ #define MPU_CTRL_PRIVDEFENA_Pos 2 /*!< MPU CTRL: PRIVDEFENA Position */ @@ -1090,11 +1129,11 @@ typedef struct #define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ #define MPU_CTRL_ENABLE_Pos 0 /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL << MPU_CTRL_ENABLE_Pos) /*!< MPU CTRL: ENABLE Mask */ +#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ /* MPU Region Number Register */ #define MPU_RNR_REGION_Pos 0 /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL << MPU_RNR_REGION_Pos) /*!< MPU RNR: REGION Mask */ +#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ /* MPU Region Base Address Register */ #define MPU_RBAR_ADDR_Pos 5 /*!< MPU RBAR: ADDR Position */ @@ -1104,7 +1143,7 @@ typedef struct #define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ #define MPU_RBAR_REGION_Pos 0 /*!< MPU RBAR: REGION Position */ -#define MPU_RBAR_REGION_Msk (0xFUL << MPU_RBAR_REGION_Pos) /*!< MPU RBAR: REGION Mask */ +#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ /* MPU Region Attribute and Size Register */ #define MPU_RASR_ATTRS_Pos 16 /*!< MPU RASR: MPU Region Attribute field Position */ @@ -1135,7 +1174,7 @@ typedef struct #define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ #define MPU_RASR_ENABLE_Pos 0 /*!< MPU RASR: Region enable bit Position */ -#define MPU_RASR_ENABLE_Msk (1UL << MPU_RASR_ENABLE_Pos) /*!< MPU RASR: Region enable bit Disable Mask */ +#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ /*@} end of group CMSIS_MPU */ #endif @@ -1192,14 +1231,14 @@ typedef struct #define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ #define CoreDebug_DHCSR_C_DEBUGEN_Pos 0 /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL << CoreDebug_DHCSR_C_DEBUGEN_Pos) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ +#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ /* Debug Core Register Selector Register */ #define CoreDebug_DCRSR_REGWnR_Pos 16 /*!< CoreDebug DCRSR: REGWnR Position */ #define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ #define CoreDebug_DCRSR_REGSEL_Pos 0 /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL << CoreDebug_DCRSR_REGSEL_Pos) /*!< CoreDebug DCRSR: REGSEL Mask */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ /* Debug Exception and Monitor Control Register */ #define CoreDebug_DEMCR_TRCENA_Pos 24 /*!< CoreDebug DEMCR: TRCENA Position */ @@ -1239,7 +1278,7 @@ typedef struct #define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ #define CoreDebug_DEMCR_VC_CORERESET_Pos 0 /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL << CoreDebug_DEMCR_VC_CORERESET_Pos) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ +#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ /*@} end of group CMSIS_CoreDebug */ @@ -1311,13 +1350,13 @@ typedef struct __STATIC_INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); /* only values 0..7 are used */ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << 8)); /* Insert write key and priorty group */ + 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 << 8) ); /* Insert write key and priorty group */ SCB->AIRCR = reg_value; } @@ -1330,7 +1369,7 @@ __STATIC_INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) */ __STATIC_INLINE uint32_t NVIC_GetPriorityGrouping(void) { - return ((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos); /* read priority grouping field */ + return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); } @@ -1342,7 +1381,7 @@ __STATIC_INLINE uint32_t NVIC_GetPriorityGrouping(void) */ __STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) { - NVIC->ISER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* enable interrupt */ + NVIC->ISER[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -1354,7 +1393,7 @@ __STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) { - NVIC->ICER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* disable interrupt */ + NVIC->ICER[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -1370,7 +1409,7 @@ __STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) */ __STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) { - return((uint32_t) ((NVIC->ISPR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if pending else 0 */ + return((uint32_t)(((NVIC->ISPR[(((uint32_t)(int32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); } @@ -1382,7 +1421,7 @@ __STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) { - NVIC->ISPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* set interrupt pending */ + NVIC->ISPR[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -1394,7 +1433,7 @@ __STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) { - NVIC->ICPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */ + NVIC->ICPR[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -1409,7 +1448,7 @@ __STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) */ __STATIC_INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn) { - return((uint32_t)((NVIC->IABR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if active else 0 */ + return((uint32_t)(((NVIC->IABR[(((uint32_t)(int32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); } @@ -1424,10 +1463,12 @@ __STATIC_INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) { - if(IRQn < 0) { - SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for Cortex-M System Interrupts */ + if((int32_t)IRQn < 0) { + SCB->SHP[(((uint32_t)(int32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8 - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } else { - NVIC->IP[(uint32_t)(IRQn)] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for device specific Interrupts */ + NVIC->IP[((uint32_t)(int32_t)IRQn)] = (uint8_t)((priority << (8 - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } } @@ -1445,10 +1486,12 @@ __STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) __STATIC_INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) { - if(IRQn < 0) { - return((uint32_t)(SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M system interrupts */ + if((int32_t)IRQn < 0) { + return(((uint32_t)SCB->SHP[(((uint32_t)(int32_t)IRQn) & 0xFUL)-4UL] >> (8 - __NVIC_PRIO_BITS))); + } else { - return((uint32_t)(NVIC->IP[(uint32_t)(IRQn)] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */ + return(((uint32_t)NVIC->IP[((uint32_t)(int32_t)IRQn)] >> (8 - __NVIC_PRIO_BITS))); + } } @@ -1466,16 +1509,16 @@ __STATIC_INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) */ __STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) { - uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ uint32_t PreemptPriorityBits; uint32_t SubPriorityBits; - PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; - SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + 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 & ((1 << (PreemptPriorityBits)) - 1)) << SubPriorityBits) | - ((SubPriority & ((1 << (SubPriorityBits )) - 1))) + ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | + ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) ); } @@ -1494,15 +1537,15 @@ __STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t P */ __STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority) { - uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ uint32_t PreemptPriorityBits; uint32_t SubPriorityBits; - PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; - SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + 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) & ((1 << (PreemptPriorityBits)) - 1); - *pSubPriority = (Priority ) & ((1 << (SubPriorityBits )) - 1); + *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); + *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); } @@ -1512,13 +1555,13 @@ __STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGr */ __STATIC_INLINE void NVIC_SystemReset(void) { - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) | - (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | - SCB_AIRCR_SYSRESETREQ_Msk); /* Keep priority group unchanged */ - __DSB(); /* Ensure completion of memory access */ - while(1); /* wait until reset */ + __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 */ + while(1) { __NOP(); } /* wait until reset */ } /*@} end of CMSIS_Core_NVICFunctions */ @@ -1551,15 +1594,15 @@ __STATIC_INLINE void NVIC_SystemReset(void) */ __STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) { - if ((ticks - 1) > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) { return (1UL); } /* Reload value impossible */ - SysTick->LOAD = ticks - 1; /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0; /* Load the SysTick Counter Value */ + 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 (0); /* Function successful */ + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ } #endif @@ -1591,11 +1634,11 @@ extern volatile int32_t ITM_RxBuffer; /*!< External variable */ __STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) { - if ((ITM->TCR & ITM_TCR_ITMENA_Msk) && /* ITM enabled */ - (ITM->TER & (1UL << 0) ) ) /* ITM Port #0 enabled */ + if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ + ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ { - while (ITM->PORT[0].u32 == 0); - ITM->PORT[0].u8 = (uint8_t) ch; + while (ITM->PORT[0].u32 == 0UL) { __NOP(); } + ITM->PORT[0].u8 = (uint8_t)ch; } return (ch); } diff --git a/lib/main/CMSIS/CM4/CoreSupport/core_cm4.h b/lib/main/CMSIS/CM4/CoreSupport/core_cm4.h index 9890abeefe..9749c27d24 100644 --- a/lib/main/CMSIS/CM4/CoreSupport/core_cm4.h +++ b/lib/main/CMSIS/CM4/CoreSupport/core_cm4.h @@ -1,13 +1,13 @@ /**************************************************************************//** * @file core_cm4.h * @brief CMSIS Cortex-M4 Core Peripheral Access Layer Header File - * @version V4.00 - * @date 22. August 2014 + * @version V4.10 + * @date 18. March 2015 * * @note * ******************************************************************************/ -/* Copyright (c) 2009 - 2014 ARM LIMITED +/* Copyright (c) 2009 - 2015 ARM LIMITED All rights reserved. Redistribution and use in source and binary forms, with or without @@ -279,13 +279,9 @@ typedef union { struct { -#if (__CORTEX_M != 0x04) - uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */ -#else 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 */ -#endif 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 */ @@ -295,6 +291,25 @@ typedef union uint32_t w; /*!< Type used for word access */ } APSR_Type; +/* APSR Register Definitions */ +#define APSR_N_Pos 31 /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30 /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29 /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28 /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + +#define APSR_Q_Pos 27 /*!< APSR: Q Position */ +#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ + +#define APSR_GE_Pos 16 /*!< 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). */ @@ -308,6 +323,10 @@ typedef union uint32_t w; /*!< Type used for word access */ } IPSR_Type; +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0 /*!< 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). */ @@ -316,13 +335,9 @@ typedef union struct { uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ -#if (__CORTEX_M != 0x04) - uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ -#else uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */ uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ -#endif uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */ uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ @@ -334,6 +349,34 @@ typedef union uint32_t w; /*!< Type used for word access */ } xPSR_Type; +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31 /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30 /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29 /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28 /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_Q_Pos 27 /*!< xPSR: Q Position */ +#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ + +#define xPSR_IT_Pos 25 /*!< xPSR: IT Position */ +#define xPSR_IT_Msk (3UL << xPSR_IT_Pos) /*!< xPSR: IT Mask */ + +#define xPSR_T_Pos 24 /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_GE_Pos 16 /*!< xPSR: GE Position */ +#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE Mask */ + +#define xPSR_ISR_Pos 0 /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + /** \brief Union type to access the Control Registers (CONTROL). */ @@ -349,6 +392,16 @@ typedef union uint32_t w; /*!< Type used for word access */ } CONTROL_Type; +/* CONTROL Register Definitions */ +#define CONTROL_FPCA_Pos 2 /*!< CONTROL: FPCA Position */ +#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */ + +#define CONTROL_SPSEL_Pos 1 /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + +#define CONTROL_nPRIV_Pos 0 /*!< CONTROL: nPRIV Position */ +#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ + /*@} end of group CMSIS_CORE */ @@ -379,7 +432,7 @@ typedef struct /* Software Triggered Interrupt Register Definitions */ #define NVIC_STIR_INTID_Pos 0 /*!< STIR: INTLINESNUM Position */ -#define NVIC_STIR_INTID_Msk (0x1FFUL << NVIC_STIR_INTID_Pos) /*!< STIR: INTLINESNUM Mask */ +#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ /*@} end of group CMSIS_NVIC */ @@ -431,7 +484,7 @@ typedef struct #define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ #define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */ +#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 31 /*!< SCB ICSR: NMIPENDSET Position */ @@ -462,7 +515,7 @@ typedef struct #define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ #define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */ +#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 7 /*!< SCB VTOR: TBLOFF Position */ @@ -488,7 +541,7 @@ typedef struct #define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ #define SCB_AIRCR_VECTRESET_Pos 0 /*!< SCB AIRCR: VECTRESET Position */ -#define SCB_AIRCR_VECTRESET_Msk (1UL << SCB_AIRCR_VECTRESET_Pos) /*!< SCB AIRCR: VECTRESET Mask */ +#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ /* SCB System Control Register Definitions */ #define SCB_SCR_SEVONPEND_Pos 4 /*!< SCB SCR: SEVONPEND Position */ @@ -517,7 +570,7 @@ typedef struct #define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ #define SCB_CCR_NONBASETHRDENA_Pos 0 /*!< SCB CCR: NONBASETHRDENA Position */ -#define SCB_CCR_NONBASETHRDENA_Msk (1UL << SCB_CCR_NONBASETHRDENA_Pos) /*!< SCB CCR: NONBASETHRDENA Mask */ +#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 18 /*!< SCB SHCSR: USGFAULTENA Position */ @@ -560,7 +613,7 @@ typedef struct #define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ #define SCB_SHCSR_MEMFAULTACT_Pos 0 /*!< SCB SHCSR: MEMFAULTACT Position */ -#define SCB_SHCSR_MEMFAULTACT_Msk (1UL << SCB_SHCSR_MEMFAULTACT_Pos) /*!< SCB SHCSR: MEMFAULTACT Mask */ +#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ /* SCB Configurable Fault Status Registers Definitions */ #define SCB_CFSR_USGFAULTSR_Pos 16 /*!< SCB CFSR: Usage Fault Status Register Position */ @@ -570,7 +623,7 @@ typedef struct #define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ #define SCB_CFSR_MEMFAULTSR_Pos 0 /*!< 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 */ +#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ /* SCB Hard Fault Status Registers Definitions */ #define SCB_HFSR_DEBUGEVT_Pos 31 /*!< SCB HFSR: DEBUGEVT Position */ @@ -596,7 +649,7 @@ typedef struct #define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ #define SCB_DFSR_HALTED_Pos 0 /*!< SCB DFSR: HALTED Position */ -#define SCB_DFSR_HALTED_Msk (1UL << SCB_DFSR_HALTED_Pos) /*!< SCB DFSR: HALTED Mask */ +#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ /*@} end of group CMSIS_SCB */ @@ -618,7 +671,7 @@ typedef struct /* Interrupt Controller Type Register Definitions */ #define SCnSCB_ICTR_INTLINESNUM_Pos 0 /*!< ICTR: INTLINESNUM Position */ -#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL << SCnSCB_ICTR_INTLINESNUM_Pos) /*!< ICTR: INTLINESNUM Mask */ +#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ /* Auxiliary Control Register Definitions */ #define SCnSCB_ACTLR_DISOOFP_Pos 9 /*!< ACTLR: DISOOFP Position */ @@ -634,7 +687,7 @@ typedef struct #define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */ #define SCnSCB_ACTLR_DISMCYCINT_Pos 0 /*!< ACTLR: DISMCYCINT Position */ -#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL << SCnSCB_ACTLR_DISMCYCINT_Pos) /*!< ACTLR: DISMCYCINT Mask */ +#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ /*@} end of group CMSIS_SCnotSCB */ @@ -666,15 +719,15 @@ typedef struct #define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ #define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */ +#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ /* SysTick Reload Register Definitions */ #define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ /* SysTick Current Register Definitions */ #define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ /* SysTick Calibration Register Definitions */ #define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */ @@ -684,7 +737,7 @@ typedef struct #define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ #define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL << SysTick_CALIB_TENMS_Pos) /*!< SysTick CALIB: TENMS Mask */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ /*@} end of group CMSIS_SysTick */ @@ -735,7 +788,7 @@ typedef struct /* ITM Trace Privilege Register Definitions */ #define ITM_TPR_PRIVMASK_Pos 0 /*!< ITM TPR: PRIVMASK Position */ -#define ITM_TPR_PRIVMASK_Msk (0xFUL << ITM_TPR_PRIVMASK_Pos) /*!< ITM TPR: PRIVMASK Mask */ +#define ITM_TPR_PRIVMASK_Msk (0xFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ /* ITM Trace Control Register Definitions */ #define ITM_TCR_BUSY_Pos 23 /*!< ITM TCR: BUSY Position */ @@ -763,19 +816,19 @@ typedef struct #define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ #define ITM_TCR_ITMENA_Pos 0 /*!< ITM TCR: ITM Enable bit Position */ -#define ITM_TCR_ITMENA_Msk (1UL << ITM_TCR_ITMENA_Pos) /*!< ITM TCR: ITM Enable bit Mask */ +#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ /* ITM Integration Write Register Definitions */ #define ITM_IWR_ATVALIDM_Pos 0 /*!< ITM IWR: ATVALIDM Position */ -#define ITM_IWR_ATVALIDM_Msk (1UL << ITM_IWR_ATVALIDM_Pos) /*!< ITM IWR: ATVALIDM Mask */ +#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */ /* ITM Integration Read Register Definitions */ #define ITM_IRR_ATREADYM_Pos 0 /*!< ITM IRR: ATREADYM Position */ -#define ITM_IRR_ATREADYM_Msk (1UL << ITM_IRR_ATREADYM_Pos) /*!< ITM IRR: ATREADYM Mask */ +#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */ /* ITM Integration Mode Control Register Definitions */ #define ITM_IMCR_INTEGRATION_Pos 0 /*!< ITM IMCR: INTEGRATION Position */ -#define ITM_IMCR_INTEGRATION_Msk (1UL << ITM_IMCR_INTEGRATION_Pos) /*!< ITM IMCR: INTEGRATION Mask */ +#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */ /* ITM Lock Status Register Definitions */ #define ITM_LSR_ByteAcc_Pos 2 /*!< ITM LSR: ByteAcc Position */ @@ -785,7 +838,7 @@ typedef struct #define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ #define ITM_LSR_Present_Pos 0 /*!< ITM LSR: Present Position */ -#define ITM_LSR_Present_Msk (1UL << ITM_LSR_Present_Pos) /*!< ITM LSR: Present Mask */ +#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ /*@}*/ /* end of group CMSIS_ITM */ @@ -878,31 +931,31 @@ typedef struct #define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ #define DWT_CTRL_CYCCNTENA_Pos 0 /*!< DWT CTRL: CYCCNTENA Position */ -#define DWT_CTRL_CYCCNTENA_Msk (0x1UL << DWT_CTRL_CYCCNTENA_Pos) /*!< DWT CTRL: CYCCNTENA Mask */ +#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ /* DWT CPI Count Register Definitions */ #define DWT_CPICNT_CPICNT_Pos 0 /*!< DWT CPICNT: CPICNT Position */ -#define DWT_CPICNT_CPICNT_Msk (0xFFUL << DWT_CPICNT_CPICNT_Pos) /*!< DWT CPICNT: CPICNT Mask */ +#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 0 /*!< DWT EXCCNT: EXCCNT Position */ -#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL << DWT_EXCCNT_EXCCNT_Pos) /*!< DWT EXCCNT: EXCCNT Mask */ +#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ /* DWT Sleep Count Register Definitions */ #define DWT_SLEEPCNT_SLEEPCNT_Pos 0 /*!< DWT SLEEPCNT: SLEEPCNT Position */ -#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL << DWT_SLEEPCNT_SLEEPCNT_Pos) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ +#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ /* DWT LSU Count Register Definitions */ #define DWT_LSUCNT_LSUCNT_Pos 0 /*!< DWT LSUCNT: LSUCNT Position */ -#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL << DWT_LSUCNT_LSUCNT_Pos) /*!< DWT LSUCNT: LSUCNT Mask */ +#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 0 /*!< DWT FOLDCNT: FOLDCNT Position */ -#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL << DWT_FOLDCNT_FOLDCNT_Pos) /*!< DWT FOLDCNT: FOLDCNT Mask */ +#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ /* DWT Comparator Mask Register Definitions */ #define DWT_MASK_MASK_Pos 0 /*!< DWT MASK: MASK Position */ -#define DWT_MASK_MASK_Msk (0x1FUL << DWT_MASK_MASK_Pos) /*!< DWT MASK: MASK Mask */ +#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ /* DWT Comparator Function Register Definitions */ #define DWT_FUNCTION_MATCHED_Pos 24 /*!< DWT FUNCTION: MATCHED Position */ @@ -930,7 +983,7 @@ typedef struct #define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ #define DWT_FUNCTION_FUNCTION_Pos 0 /*!< DWT FUNCTION: FUNCTION Position */ -#define DWT_FUNCTION_FUNCTION_Msk (0xFUL << DWT_FUNCTION_FUNCTION_Pos) /*!< DWT FUNCTION: FUNCTION Mask */ +#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ /*@}*/ /* end of group CMSIS_DWT */ @@ -973,11 +1026,11 @@ typedef struct /* TPI Asynchronous Clock Prescaler Register Definitions */ #define TPI_ACPR_PRESCALER_Pos 0 /*!< TPI ACPR: PRESCALER Position */ -#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL << TPI_ACPR_PRESCALER_Pos) /*!< TPI ACPR: PRESCALER Mask */ +#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 0 /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL << TPI_SPPR_TXMODE_Pos) /*!< TPI SPPR: TXMODE Mask */ +#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 3 /*!< TPI FFSR: FtNonStop Position */ @@ -990,7 +1043,7 @@ typedef struct #define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ #define TPI_FFSR_FlInProg_Pos 0 /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL << TPI_FFSR_FlInProg_Pos) /*!< TPI FFSR: FlInProg Mask */ +#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 8 /*!< TPI FFCR: TrigIn Position */ @@ -1001,7 +1054,7 @@ typedef struct /* TPI TRIGGER Register Definitions */ #define TPI_TRIGGER_TRIGGER_Pos 0 /*!< TPI TRIGGER: TRIGGER Position */ -#define TPI_TRIGGER_TRIGGER_Msk (0x1UL << TPI_TRIGGER_TRIGGER_Pos) /*!< TPI TRIGGER: TRIGGER Mask */ +#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 29 /*!< TPI FIFO0: ITM_ATVALID Position */ @@ -1023,11 +1076,11 @@ typedef struct #define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ #define TPI_FIFO0_ETM0_Pos 0 /*!< TPI FIFO0: ETM0 Position */ -#define TPI_FIFO0_ETM0_Msk (0xFFUL << TPI_FIFO0_ETM0_Pos) /*!< TPI FIFO0: ETM0 Mask */ +#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ /* TPI ITATBCTR2 Register Definitions */ #define TPI_ITATBCTR2_ATREADY_Pos 0 /*!< TPI ITATBCTR2: ATREADY Position */ -#define TPI_ITATBCTR2_ATREADY_Msk (0x1UL << TPI_ITATBCTR2_ATREADY_Pos) /*!< TPI ITATBCTR2: ATREADY Mask */ +#define TPI_ITATBCTR2_ATREADY_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY_Pos*/) /*!< TPI ITATBCTR2: ATREADY Mask */ /* TPI Integration ITM Data Register Definitions (FIFO1) */ #define TPI_FIFO1_ITM_ATVALID_Pos 29 /*!< TPI FIFO1: ITM_ATVALID Position */ @@ -1049,15 +1102,15 @@ typedef struct #define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ #define TPI_FIFO1_ITM0_Pos 0 /*!< TPI FIFO1: ITM0 Position */ -#define TPI_FIFO1_ITM0_Msk (0xFFUL << TPI_FIFO1_ITM0_Pos) /*!< TPI FIFO1: ITM0 Mask */ +#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ /* TPI ITATBCTR0 Register Definitions */ #define TPI_ITATBCTR0_ATREADY_Pos 0 /*!< TPI ITATBCTR0: ATREADY Position */ -#define TPI_ITATBCTR0_ATREADY_Msk (0x1UL << TPI_ITATBCTR0_ATREADY_Pos) /*!< TPI ITATBCTR0: ATREADY Mask */ +#define TPI_ITATBCTR0_ATREADY_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY_Pos*/) /*!< TPI ITATBCTR0: ATREADY Mask */ /* TPI Integration Mode Control Register Definitions */ #define TPI_ITCTRL_Mode_Pos 0 /*!< TPI ITCTRL: Mode Position */ -#define TPI_ITCTRL_Mode_Msk (0x1UL << TPI_ITCTRL_Mode_Pos) /*!< TPI ITCTRL: Mode Mask */ +#define TPI_ITCTRL_Mode_Msk (0x1UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ /* TPI DEVID Register Definitions */ #define TPI_DEVID_NRZVALID_Pos 11 /*!< TPI DEVID: NRZVALID Position */ @@ -1076,15 +1129,15 @@ typedef struct #define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ #define TPI_DEVID_NrTraceInput_Pos 0 /*!< TPI DEVID: NrTraceInput Position */ -#define TPI_DEVID_NrTraceInput_Msk (0x1FUL << TPI_DEVID_NrTraceInput_Pos) /*!< TPI DEVID: NrTraceInput Mask */ +#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ /* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 0 /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL << TPI_DEVTYPE_SubType_Pos) /*!< TPI DEVTYPE: SubType Mask */ - #define TPI_DEVTYPE_MajorType_Pos 4 /*!< TPI DEVTYPE: MajorType Position */ #define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ +#define TPI_DEVTYPE_SubType_Pos 0 /*!< TPI DEVTYPE: SubType Position */ +#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ + /*@}*/ /* end of group CMSIS_TPI */ @@ -1120,7 +1173,7 @@ typedef struct #define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ #define MPU_TYPE_SEPARATE_Pos 0 /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL << MPU_TYPE_SEPARATE_Pos) /*!< MPU TYPE: SEPARATE Mask */ +#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ /* MPU Control Register */ #define MPU_CTRL_PRIVDEFENA_Pos 2 /*!< MPU CTRL: PRIVDEFENA Position */ @@ -1130,11 +1183,11 @@ typedef struct #define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ #define MPU_CTRL_ENABLE_Pos 0 /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL << MPU_CTRL_ENABLE_Pos) /*!< MPU CTRL: ENABLE Mask */ +#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ /* MPU Region Number Register */ #define MPU_RNR_REGION_Pos 0 /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL << MPU_RNR_REGION_Pos) /*!< MPU RNR: REGION Mask */ +#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ /* MPU Region Base Address Register */ #define MPU_RBAR_ADDR_Pos 5 /*!< MPU RBAR: ADDR Position */ @@ -1144,7 +1197,7 @@ typedef struct #define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ #define MPU_RBAR_REGION_Pos 0 /*!< MPU RBAR: REGION Position */ -#define MPU_RBAR_REGION_Msk (0xFUL << MPU_RBAR_REGION_Pos) /*!< MPU RBAR: REGION Mask */ +#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ /* MPU Region Attribute and Size Register */ #define MPU_RASR_ATTRS_Pos 16 /*!< MPU RASR: MPU Region Attribute field Position */ @@ -1175,7 +1228,7 @@ typedef struct #define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ #define MPU_RASR_ENABLE_Pos 0 /*!< MPU RASR: Region enable bit Position */ -#define MPU_RASR_ENABLE_Msk (1UL << MPU_RASR_ENABLE_Pos) /*!< MPU RASR: Region enable bit Disable Mask */ +#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ /*@} end of group CMSIS_MPU */ #endif @@ -1226,7 +1279,7 @@ typedef struct #define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ #define FPU_FPCCR_LSPACT_Pos 0 /*!< FPCCR: Lazy state preservation active bit Position */ -#define FPU_FPCCR_LSPACT_Msk (1UL << FPU_FPCCR_LSPACT_Pos) /*!< FPCCR: Lazy state preservation active bit Mask */ +#define FPU_FPCCR_LSPACT_Msk (1UL /*<< FPU_FPCCR_LSPACT_Pos*/) /*!< FPCCR: Lazy state preservation active bit Mask */ /* Floating-Point Context Address Register */ #define FPU_FPCAR_ADDRESS_Pos 3 /*!< FPCAR: ADDRESS bit Position */ @@ -1268,7 +1321,7 @@ typedef struct #define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ #define FPU_MVFR0_A_SIMD_registers_Pos 0 /*!< 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 */ +#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 */ #define FPU_MVFR1_FP_fused_MAC_Pos 28 /*!< MVFR1: FP fused MAC bits Position */ @@ -1281,7 +1334,7 @@ typedef struct #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 0 /*!< MVFR1: FtZ mode bits Position */ -#define FPU_MVFR1_FtZ_mode_Msk (0xFUL << FPU_MVFR1_FtZ_mode_Pos) /*!< MVFR1: FtZ mode bits Mask */ +#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */ /*@} end of group CMSIS_FPU */ #endif @@ -1338,14 +1391,14 @@ typedef struct #define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ #define CoreDebug_DHCSR_C_DEBUGEN_Pos 0 /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL << CoreDebug_DHCSR_C_DEBUGEN_Pos) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ +#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ /* Debug Core Register Selector Register */ #define CoreDebug_DCRSR_REGWnR_Pos 16 /*!< CoreDebug DCRSR: REGWnR Position */ #define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ #define CoreDebug_DCRSR_REGSEL_Pos 0 /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL << CoreDebug_DCRSR_REGSEL_Pos) /*!< CoreDebug DCRSR: REGSEL Mask */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ /* Debug Exception and Monitor Control Register */ #define CoreDebug_DEMCR_TRCENA_Pos 24 /*!< CoreDebug DEMCR: TRCENA Position */ @@ -1385,7 +1438,7 @@ typedef struct #define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ #define CoreDebug_DEMCR_VC_CORERESET_Pos 0 /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL << CoreDebug_DEMCR_VC_CORERESET_Pos) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ +#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ /*@} end of group CMSIS_CoreDebug */ @@ -1462,13 +1515,13 @@ typedef struct __STATIC_INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); /* only values 0..7 are used */ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << 8)); /* Insert write key and priorty group */ + 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 << 8) ); /* Insert write key and priorty group */ SCB->AIRCR = reg_value; } @@ -1481,7 +1534,7 @@ __STATIC_INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) */ __STATIC_INLINE uint32_t NVIC_GetPriorityGrouping(void) { - return ((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos); /* read priority grouping field */ + return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); } @@ -1493,8 +1546,7 @@ __STATIC_INLINE uint32_t NVIC_GetPriorityGrouping(void) */ __STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) { -/* NVIC->ISER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); enable interrupt */ - NVIC->ISER[(uint32_t)((int32_t)IRQn) >> 5] = (uint32_t)(1 << ((uint32_t)((int32_t)IRQn) & (uint32_t)0x1F)); /* enable interrupt */ + NVIC->ISER[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -1506,7 +1558,7 @@ __STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) { - NVIC->ICER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* disable interrupt */ + NVIC->ICER[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -1522,7 +1574,7 @@ __STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) */ __STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) { - return((uint32_t) ((NVIC->ISPR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if pending else 0 */ + return((uint32_t)(((NVIC->ISPR[(((uint32_t)(int32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); } @@ -1534,7 +1586,7 @@ __STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) { - NVIC->ISPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* set interrupt pending */ + NVIC->ISPR[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -1546,7 +1598,7 @@ __STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) { - NVIC->ICPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */ + NVIC->ICPR[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -1561,7 +1613,7 @@ __STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) */ __STATIC_INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn) { - return((uint32_t)((NVIC->IABR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if active else 0 */ + return((uint32_t)(((NVIC->IABR[(((uint32_t)(int32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); } @@ -1576,10 +1628,12 @@ __STATIC_INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) { - if(IRQn < 0) { - SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for Cortex-M System Interrupts */ + if((int32_t)IRQn < 0) { + SCB->SHP[(((uint32_t)(int32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8 - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } else { - NVIC->IP[(uint32_t)(IRQn)] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for device specific Interrupts */ + NVIC->IP[((uint32_t)(int32_t)IRQn)] = (uint8_t)((priority << (8 - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } } @@ -1597,10 +1651,12 @@ __STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) __STATIC_INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) { - if(IRQn < 0) { - return((uint32_t)(SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M system interrupts */ + if((int32_t)IRQn < 0) { + return(((uint32_t)SCB->SHP[(((uint32_t)(int32_t)IRQn) & 0xFUL)-4UL] >> (8 - __NVIC_PRIO_BITS))); + } else { - return((uint32_t)(NVIC->IP[(uint32_t)(IRQn)] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */ + return(((uint32_t)NVIC->IP[((uint32_t)(int32_t)IRQn)] >> (8 - __NVIC_PRIO_BITS))); + } } @@ -1618,16 +1674,16 @@ __STATIC_INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) */ __STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) { - uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ uint32_t PreemptPriorityBits; uint32_t SubPriorityBits; - PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; - SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + 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 & ((1 << (PreemptPriorityBits)) - 1)) << SubPriorityBits) | - ((SubPriority & ((1 << (SubPriorityBits )) - 1))) + ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | + ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) ); } @@ -1646,46 +1702,31 @@ __STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t P */ __STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority) { - uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ uint32_t PreemptPriorityBits; uint32_t SubPriorityBits; - PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; - SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + 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) & ((1 << (PreemptPriorityBits)) - 1); - *pSubPriority = (Priority ) & ((1 << (SubPriorityBits )) - 1); + *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); + *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); } -/** \brief System Reset - - The function initiates a system reset request to reset the MCU. - */ -__STATIC_INLINE void NVIC_CoreReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) | - (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | - CoreDebug_DEMCR_VC_CORERESET_Msk); /* Keep priority group unchanged */ - __DSB(); /* Ensure completion of memory access */ - while(1); /* wait until reset */ -} - /** \brief System Reset The function initiates a system reset request to reset the MCU. */ __STATIC_INLINE void NVIC_SystemReset(void) { - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) | - (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | - SCB_AIRCR_SYSRESETREQ_Msk); /* Keep priority group unchanged */ - __DSB(); /* Ensure completion of memory access */ - while(1); /* wait until reset */ + __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 */ + while(1) { __NOP(); } /* wait until reset */ } /*@} end of CMSIS_Core_NVICFunctions */ @@ -1718,15 +1759,15 @@ __STATIC_INLINE void NVIC_SystemReset(void) */ __STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) { - if ((ticks - 1) > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) { return (1UL); } /* Reload value impossible */ - SysTick->LOAD = ticks - 1; /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0; /* Load the SysTick Counter Value */ + 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 (0); /* Function successful */ + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ } #endif @@ -1758,11 +1799,11 @@ extern volatile int32_t ITM_RxBuffer; /*!< External variable */ __STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) { - if ((ITM->TCR & ITM_TCR_ITMENA_Msk) && /* ITM enabled */ - (ITM->TER & (1UL << 0) ) ) /* ITM Port #0 enabled */ + if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ + ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ { - while (ITM->PORT[0].u32 == 0); - ITM->PORT[0].u8 = (uint8_t) ch; + while (ITM->PORT[0].u32 == 0UL) { __NOP(); } + ITM->PORT[0].u8 = (uint8_t)ch; } return (ch); } diff --git a/lib/main/CMSIS/CM4/CoreSupport/core_cm7.h b/lib/main/CMSIS/CM4/CoreSupport/core_cm7.h index 242540f8b1..842e323f67 100644 --- a/lib/main/CMSIS/CM4/CoreSupport/core_cm7.h +++ b/lib/main/CMSIS/CM4/CoreSupport/core_cm7.h @@ -1,13 +1,13 @@ /**************************************************************************//** * @file core_cm7.h * @brief CMSIS Cortex-M7 Core Peripheral Access Layer Header File - * @version V4.00 - * @date 01. September 2014 + * @version V4.10 + * @date 18. March 2015 * * @note * ******************************************************************************/ -/* Copyright (c) 2009 - 2014 ARM LIMITED +/* Copyright (c) 2009 - 2015 ARM LIMITED All rights reserved. Redistribution and use in source and binary forms, with or without @@ -294,13 +294,9 @@ typedef union { struct { -#if (__CORTEX_M != 0x07) - uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */ -#else 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 */ -#endif 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 */ @@ -310,6 +306,25 @@ typedef union uint32_t w; /*!< Type used for word access */ } APSR_Type; +/* APSR Register Definitions */ +#define APSR_N_Pos 31 /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30 /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29 /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28 /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + +#define APSR_Q_Pos 27 /*!< APSR: Q Position */ +#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ + +#define APSR_GE_Pos 16 /*!< 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). */ @@ -323,6 +338,10 @@ typedef union uint32_t w; /*!< Type used for word access */ } IPSR_Type; +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0 /*!< 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). */ @@ -331,13 +350,9 @@ typedef union struct { uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ -#if (__CORTEX_M != 0x07) - uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ -#else uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */ uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ -#endif uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */ uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ @@ -349,6 +364,34 @@ typedef union uint32_t w; /*!< Type used for word access */ } xPSR_Type; +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31 /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30 /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29 /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28 /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_Q_Pos 27 /*!< xPSR: Q Position */ +#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ + +#define xPSR_IT_Pos 25 /*!< xPSR: IT Position */ +#define xPSR_IT_Msk (3UL << xPSR_IT_Pos) /*!< xPSR: IT Mask */ + +#define xPSR_T_Pos 24 /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_GE_Pos 16 /*!< xPSR: GE Position */ +#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE Mask */ + +#define xPSR_ISR_Pos 0 /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + /** \brief Union type to access the Control Registers (CONTROL). */ @@ -364,6 +407,16 @@ typedef union uint32_t w; /*!< Type used for word access */ } CONTROL_Type; +/* CONTROL Register Definitions */ +#define CONTROL_FPCA_Pos 2 /*!< CONTROL: FPCA Position */ +#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */ + +#define CONTROL_SPSEL_Pos 1 /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + +#define CONTROL_nPRIV_Pos 0 /*!< CONTROL: nPRIV Position */ +#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ + /*@} end of group CMSIS_CORE */ @@ -394,7 +447,7 @@ typedef struct /* Software Triggered Interrupt Register Definitions */ #define NVIC_STIR_INTID_Pos 0 /*!< STIR: INTLINESNUM Position */ -#define NVIC_STIR_INTID_Msk (0x1FFUL << NVIC_STIR_INTID_Pos) /*!< STIR: INTLINESNUM Mask */ +#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ /*@} end of group CMSIS_NVIC */ @@ -444,7 +497,7 @@ typedef struct __O uint32_t ICIALLU; /*!< Offset: 0x250 ( /W) I-Cache Invalidate All to PoU */ uint32_t RESERVED6[1]; __O uint32_t ICIMVAU; /*!< Offset: 0x258 ( /W) I-Cache Invalidate by MVA to PoU */ - __O uint32_t DCIMVAU; /*!< Offset: 0x25C ( /W) D-Cache Invalidate by MVA to PoC */ + __O uint32_t DCIMVAC; /*!< Offset: 0x25C ( /W) D-Cache Invalidate by MVA to PoC */ __O uint32_t DCISW; /*!< Offset: 0x260 ( /W) D-Cache Invalidate by Set-way */ __O uint32_t DCCMVAU; /*!< Offset: 0x264 ( /W) D-Cache Clean by MVA to PoU */ __O uint32_t DCCMVAC; /*!< Offset: 0x268 ( /W) D-Cache Clean by MVA to PoC */ @@ -475,7 +528,7 @@ typedef struct #define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ #define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */ +#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 31 /*!< SCB ICSR: NMIPENDSET Position */ @@ -506,7 +559,7 @@ typedef struct #define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ #define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */ +#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 7 /*!< SCB VTOR: TBLOFF Position */ @@ -532,7 +585,7 @@ typedef struct #define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ #define SCB_AIRCR_VECTRESET_Pos 0 /*!< SCB AIRCR: VECTRESET Position */ -#define SCB_AIRCR_VECTRESET_Msk (1UL << SCB_AIRCR_VECTRESET_Pos) /*!< SCB AIRCR: VECTRESET Mask */ +#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ /* SCB System Control Register Definitions */ #define SCB_SCR_SEVONPEND_Pos 4 /*!< SCB SCR: SEVONPEND Position */ @@ -570,7 +623,7 @@ typedef struct #define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ #define SCB_CCR_NONBASETHRDENA_Pos 0 /*!< SCB CCR: NONBASETHRDENA Position */ -#define SCB_CCR_NONBASETHRDENA_Msk (1UL << SCB_CCR_NONBASETHRDENA_Pos) /*!< SCB CCR: NONBASETHRDENA Mask */ +#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 18 /*!< SCB SHCSR: USGFAULTENA Position */ @@ -613,7 +666,7 @@ typedef struct #define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ #define SCB_SHCSR_MEMFAULTACT_Pos 0 /*!< SCB SHCSR: MEMFAULTACT Position */ -#define SCB_SHCSR_MEMFAULTACT_Msk (1UL << SCB_SHCSR_MEMFAULTACT_Pos) /*!< SCB SHCSR: MEMFAULTACT Mask */ +#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ /* SCB Configurable Fault Status Registers Definitions */ #define SCB_CFSR_USGFAULTSR_Pos 16 /*!< SCB CFSR: Usage Fault Status Register Position */ @@ -623,7 +676,7 @@ typedef struct #define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ #define SCB_CFSR_MEMFAULTSR_Pos 0 /*!< 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 */ +#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ /* SCB Hard Fault Status Registers Definitions */ #define SCB_HFSR_DEBUGEVT_Pos 31 /*!< SCB HFSR: DEBUGEVT Position */ @@ -649,7 +702,7 @@ typedef struct #define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ #define SCB_DFSR_HALTED_Pos 0 /*!< SCB DFSR: HALTED Position */ -#define SCB_DFSR_HALTED_Msk (1UL << SCB_DFSR_HALTED_Pos) /*!< SCB DFSR: HALTED Mask */ +#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ /* Cache Level ID register */ #define SCB_CLIDR_LOUU_Pos 27 /*!< SCB CLIDR: LoUU Position */ @@ -672,7 +725,7 @@ typedef struct #define SCB_CTR_DMINLINE_Msk (0xFUL << SCB_CTR_DMINLINE_Pos) /*!< SCB CTR: DminLine Mask */ #define SCB_CTR_IMINLINE_Pos 0 /*!< SCB CTR: ImInLine Position */ -#define SCB_CTR_IMINLINE_Msk (0xFUL << SCB_CTR_IMINLINE_Pos) /*!< SCB CTR: ImInLine Mask */ +#define SCB_CTR_IMINLINE_Msk (0xFUL /*<< SCB_CTR_IMINLINE_Pos*/) /*!< SCB CTR: ImInLine Mask */ /* Cache Size ID Register */ #define SCB_CCSIDR_WT_Pos 31 /*!< SCB CCSIDR: WT Position */ @@ -694,31 +747,31 @@ typedef struct #define SCB_CCSIDR_ASSOCIATIVITY_Msk (0x3FFUL << SCB_CCSIDR_ASSOCIATIVITY_Pos) /*!< SCB CCSIDR: Associativity Mask */ #define SCB_CCSIDR_LINESIZE_Pos 0 /*!< SCB CCSIDR: LineSize Position */ -#define SCB_CCSIDR_LINESIZE_Msk (7UL << SCB_CCSIDR_LINESIZE_Pos) /*!< SCB CCSIDR: LineSize Mask */ +#define SCB_CCSIDR_LINESIZE_Msk (7UL /*<< SCB_CCSIDR_LINESIZE_Pos*/) /*!< SCB CCSIDR: LineSize Mask */ /* Cache Size Selection Register */ -#define SCB_CSSELR_LEVEL_Pos 0 /*!< SCB CSSELR: Level Position */ -#define SCB_CSSELR_LEVEL_Msk (1UL << SCB_CSSELR_LEVEL_Pos) /*!< SCB CSSELR: Level Mask */ +#define SCB_CSSELR_LEVEL_Pos 1 /*!< SCB CSSELR: Level Position */ +#define SCB_CSSELR_LEVEL_Msk (7UL << SCB_CSSELR_LEVEL_Pos) /*!< SCB CSSELR: Level Mask */ #define SCB_CSSELR_IND_Pos 0 /*!< SCB CSSELR: InD Position */ -#define SCB_CSSELR_IND_Msk (1UL << SCB_CSSELR_IND_Pos) /*!< SCB CSSELR: InD Mask */ +#define SCB_CSSELR_IND_Msk (1UL /*<< SCB_CSSELR_IND_Pos*/) /*!< SCB CSSELR: InD Mask */ /* SCB Software Triggered Interrupt Register */ #define SCB_STIR_INTID_Pos 0 /*!< SCB STIR: INTID Position */ -#define SCB_STIR_INTID_Msk (0x1FFUL << SCB_STIR_INTID_Pos) /*!< SCB STIR: INTID Mask */ +#define SCB_STIR_INTID_Msk (0x1FFUL /*<< SCB_STIR_INTID_Pos*/) /*!< SCB STIR: INTID Mask */ /* Instruction Tightly-Coupled Memory Control Register*/ #define SCB_ITCMCR_SZ_Pos 3 /*!< SCB ITCMCR: SZ Position */ #define SCB_ITCMCR_SZ_Msk (0xFUL << SCB_ITCMCR_SZ_Pos) /*!< SCB ITCMCR: SZ Mask */ #define SCB_ITCMCR_RETEN_Pos 2 /*!< SCB ITCMCR: RETEN Position */ -#define SCB_ITCMCR_RETEN_Msk (1FFUL << SCB_ITCMCR_RETEN_Pos) /*!< SCB ITCMCR: RETEN Mask */ +#define SCB_ITCMCR_RETEN_Msk (1UL << SCB_ITCMCR_RETEN_Pos) /*!< SCB ITCMCR: RETEN Mask */ #define SCB_ITCMCR_RMW_Pos 1 /*!< SCB ITCMCR: RMW Position */ -#define SCB_ITCMCR_RMW_Msk (1FFUL << SCB_ITCMCR_RMW_Pos) /*!< SCB ITCMCR: RMW Mask */ +#define SCB_ITCMCR_RMW_Msk (1UL << SCB_ITCMCR_RMW_Pos) /*!< SCB ITCMCR: RMW Mask */ #define SCB_ITCMCR_EN_Pos 0 /*!< SCB ITCMCR: EN Position */ -#define SCB_ITCMCR_EN_Msk (1FFUL << SCB_ITCMCR_EN_Pos) /*!< SCB ITCMCR: EN Mask */ +#define SCB_ITCMCR_EN_Msk (1UL /*<< SCB_ITCMCR_EN_Pos*/) /*!< SCB ITCMCR: EN Mask */ /* Data Tightly-Coupled Memory Control Registers */ #define SCB_DTCMCR_SZ_Pos 3 /*!< SCB DTCMCR: SZ Position */ @@ -731,14 +784,14 @@ typedef struct #define SCB_DTCMCR_RMW_Msk (1UL << SCB_DTCMCR_RMW_Pos) /*!< SCB DTCMCR: RMW Mask */ #define SCB_DTCMCR_EN_Pos 0 /*!< SCB DTCMCR: EN Position */ -#define SCB_DTCMCR_EN_Msk (1UL << SCB_DTCMCR_EN_Pos) /*!< SCB DTCMCR: EN Mask */ +#define SCB_DTCMCR_EN_Msk (1UL /*<< SCB_DTCMCR_EN_Pos*/) /*!< SCB DTCMCR: EN Mask */ /* AHBP Control Register */ #define SCB_AHBPCR_SZ_Pos 1 /*!< SCB AHBPCR: SZ Position */ #define SCB_AHBPCR_SZ_Msk (7UL << SCB_AHBPCR_SZ_Pos) /*!< SCB AHBPCR: SZ Mask */ #define SCB_AHBPCR_EN_Pos 0 /*!< SCB AHBPCR: EN Position */ -#define SCB_AHBPCR_EN_Msk (1UL << SCB_AHBPCR_EN_Pos) /*!< SCB AHBPCR: EN Mask */ +#define SCB_AHBPCR_EN_Msk (1UL /*<< SCB_AHBPCR_EN_Pos*/) /*!< SCB AHBPCR: EN Mask */ /* L1 Cache Control Register */ #define SCB_CACR_FORCEWT_Pos 2 /*!< SCB CACR: FORCEWT Position */ @@ -748,7 +801,7 @@ typedef struct #define SCB_CACR_ECCEN_Msk (1UL << SCB_CACR_ECCEN_Pos) /*!< SCB CACR: ECCEN Mask */ #define SCB_CACR_SIWT_Pos 0 /*!< SCB CACR: SIWT Position */ -#define SCB_CACR_SIWT_Msk (1UL << SCB_CACR_SIWT_Pos) /*!< SCB CACR: SIWT Mask */ +#define SCB_CACR_SIWT_Msk (1UL /*<< SCB_CACR_SIWT_Pos*/) /*!< SCB CACR: SIWT Mask */ /* AHBS control register */ #define SCB_AHBSCR_INITCOUNT_Pos 11 /*!< SCB AHBSCR: INITCOUNT Position */ @@ -758,7 +811,7 @@ typedef struct #define SCB_AHBSCR_TPRI_Msk (0x1FFUL << SCB_AHBPCR_TPRI_Pos) /*!< SCB AHBSCR: TPRI Mask */ #define SCB_AHBSCR_CTL_Pos 0 /*!< SCB AHBSCR: CTL Position*/ -#define SCB_AHBSCR_CTL_Msk (3UL << SCB_AHBPCR_CTL_Pos) /*!< SCB AHBSCR: CTL Mask */ +#define SCB_AHBSCR_CTL_Msk (3UL /*<< SCB_AHBPCR_CTL_Pos*/) /*!< SCB AHBSCR: CTL Mask */ /* Auxiliary Bus Fault Status Register */ #define SCB_ABFSR_AXIMTYPE_Pos 8 /*!< SCB ABFSR: AXIMTYPE Position*/ @@ -777,7 +830,7 @@ typedef struct #define SCB_ABFSR_DTCM_Msk (1UL << SCB_ABFSR_DTCM_Pos) /*!< SCB ABFSR: DTCM Mask */ #define SCB_ABFSR_ITCM_Pos 0 /*!< SCB ABFSR: ITCM Position*/ -#define SCB_ABFSR_ITCM_Msk (1UL << SCB_ABFSR_ITCM_Pos) /*!< SCB ABFSR: ITCM Mask */ +#define SCB_ABFSR_ITCM_Msk (1UL /*<< SCB_ABFSR_ITCM_Pos*/) /*!< SCB ABFSR: ITCM Mask */ /*@} end of group CMSIS_SCB */ @@ -799,7 +852,7 @@ typedef struct /* Interrupt Controller Type Register Definitions */ #define SCnSCB_ICTR_INTLINESNUM_Pos 0 /*!< ICTR: INTLINESNUM Position */ -#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL << SCnSCB_ICTR_INTLINESNUM_Pos) /*!< ICTR: INTLINESNUM Mask */ +#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ /* Auxiliary Control Register Definitions */ #define SCnSCB_ACTLR_DISITMATBFLUSH_Pos 12 /*!< ACTLR: DISITMATBFLUSH Position */ @@ -815,7 +868,7 @@ typedef struct #define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ #define SCnSCB_ACTLR_DISMCYCINT_Pos 0 /*!< ACTLR: DISMCYCINT Position */ -#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL << SCnSCB_ACTLR_DISMCYCINT_Pos) /*!< ACTLR: DISMCYCINT Mask */ +#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ /*@} end of group CMSIS_SCnotSCB */ @@ -847,15 +900,15 @@ typedef struct #define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ #define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */ +#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ /* SysTick Reload Register Definitions */ #define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ /* SysTick Current Register Definitions */ #define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ /* SysTick Calibration Register Definitions */ #define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */ @@ -865,7 +918,7 @@ typedef struct #define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ #define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL << SysTick_CALIB_TENMS_Pos) /*!< SysTick CALIB: TENMS Mask */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ /*@} end of group CMSIS_SysTick */ @@ -916,7 +969,7 @@ typedef struct /* ITM Trace Privilege Register Definitions */ #define ITM_TPR_PRIVMASK_Pos 0 /*!< ITM TPR: PRIVMASK Position */ -#define ITM_TPR_PRIVMASK_Msk (0xFUL << ITM_TPR_PRIVMASK_Pos) /*!< ITM TPR: PRIVMASK Mask */ +#define ITM_TPR_PRIVMASK_Msk (0xFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ /* ITM Trace Control Register Definitions */ #define ITM_TCR_BUSY_Pos 23 /*!< ITM TCR: BUSY Position */ @@ -944,19 +997,19 @@ typedef struct #define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ #define ITM_TCR_ITMENA_Pos 0 /*!< ITM TCR: ITM Enable bit Position */ -#define ITM_TCR_ITMENA_Msk (1UL << ITM_TCR_ITMENA_Pos) /*!< ITM TCR: ITM Enable bit Mask */ +#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ /* ITM Integration Write Register Definitions */ #define ITM_IWR_ATVALIDM_Pos 0 /*!< ITM IWR: ATVALIDM Position */ -#define ITM_IWR_ATVALIDM_Msk (1UL << ITM_IWR_ATVALIDM_Pos) /*!< ITM IWR: ATVALIDM Mask */ +#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */ /* ITM Integration Read Register Definitions */ #define ITM_IRR_ATREADYM_Pos 0 /*!< ITM IRR: ATREADYM Position */ -#define ITM_IRR_ATREADYM_Msk (1UL << ITM_IRR_ATREADYM_Pos) /*!< ITM IRR: ATREADYM Mask */ +#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */ /* ITM Integration Mode Control Register Definitions */ #define ITM_IMCR_INTEGRATION_Pos 0 /*!< ITM IMCR: INTEGRATION Position */ -#define ITM_IMCR_INTEGRATION_Msk (1UL << ITM_IMCR_INTEGRATION_Pos) /*!< ITM IMCR: INTEGRATION Mask */ +#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */ /* ITM Lock Status Register Definitions */ #define ITM_LSR_ByteAcc_Pos 2 /*!< ITM LSR: ByteAcc Position */ @@ -966,7 +1019,7 @@ typedef struct #define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ #define ITM_LSR_Present_Pos 0 /*!< ITM LSR: Present Position */ -#define ITM_LSR_Present_Msk (1UL << ITM_LSR_Present_Pos) /*!< ITM LSR: Present Mask */ +#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ /*@}*/ /* end of group CMSIS_ITM */ @@ -1062,31 +1115,31 @@ typedef struct #define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ #define DWT_CTRL_CYCCNTENA_Pos 0 /*!< DWT CTRL: CYCCNTENA Position */ -#define DWT_CTRL_CYCCNTENA_Msk (0x1UL << DWT_CTRL_CYCCNTENA_Pos) /*!< DWT CTRL: CYCCNTENA Mask */ +#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ /* DWT CPI Count Register Definitions */ #define DWT_CPICNT_CPICNT_Pos 0 /*!< DWT CPICNT: CPICNT Position */ -#define DWT_CPICNT_CPICNT_Msk (0xFFUL << DWT_CPICNT_CPICNT_Pos) /*!< DWT CPICNT: CPICNT Mask */ +#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 0 /*!< DWT EXCCNT: EXCCNT Position */ -#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL << DWT_EXCCNT_EXCCNT_Pos) /*!< DWT EXCCNT: EXCCNT Mask */ +#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ /* DWT Sleep Count Register Definitions */ #define DWT_SLEEPCNT_SLEEPCNT_Pos 0 /*!< DWT SLEEPCNT: SLEEPCNT Position */ -#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL << DWT_SLEEPCNT_SLEEPCNT_Pos) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ +#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ /* DWT LSU Count Register Definitions */ #define DWT_LSUCNT_LSUCNT_Pos 0 /*!< DWT LSUCNT: LSUCNT Position */ -#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL << DWT_LSUCNT_LSUCNT_Pos) /*!< DWT LSUCNT: LSUCNT Mask */ +#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 0 /*!< DWT FOLDCNT: FOLDCNT Position */ -#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL << DWT_FOLDCNT_FOLDCNT_Pos) /*!< DWT FOLDCNT: FOLDCNT Mask */ +#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ /* DWT Comparator Mask Register Definitions */ #define DWT_MASK_MASK_Pos 0 /*!< DWT MASK: MASK Position */ -#define DWT_MASK_MASK_Msk (0x1FUL << DWT_MASK_MASK_Pos) /*!< DWT MASK: MASK Mask */ +#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ /* DWT Comparator Function Register Definitions */ #define DWT_FUNCTION_MATCHED_Pos 24 /*!< DWT FUNCTION: MATCHED Position */ @@ -1114,7 +1167,7 @@ typedef struct #define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ #define DWT_FUNCTION_FUNCTION_Pos 0 /*!< DWT FUNCTION: FUNCTION Position */ -#define DWT_FUNCTION_FUNCTION_Msk (0xFUL << DWT_FUNCTION_FUNCTION_Pos) /*!< DWT FUNCTION: FUNCTION Mask */ +#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ /*@}*/ /* end of group CMSIS_DWT */ @@ -1157,11 +1210,11 @@ typedef struct /* TPI Asynchronous Clock Prescaler Register Definitions */ #define TPI_ACPR_PRESCALER_Pos 0 /*!< TPI ACPR: PRESCALER Position */ -#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL << TPI_ACPR_PRESCALER_Pos) /*!< TPI ACPR: PRESCALER Mask */ +#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 0 /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL << TPI_SPPR_TXMODE_Pos) /*!< TPI SPPR: TXMODE Mask */ +#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 3 /*!< TPI FFSR: FtNonStop Position */ @@ -1174,7 +1227,7 @@ typedef struct #define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ #define TPI_FFSR_FlInProg_Pos 0 /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL << TPI_FFSR_FlInProg_Pos) /*!< TPI FFSR: FlInProg Mask */ +#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 8 /*!< TPI FFCR: TrigIn Position */ @@ -1185,7 +1238,7 @@ typedef struct /* TPI TRIGGER Register Definitions */ #define TPI_TRIGGER_TRIGGER_Pos 0 /*!< TPI TRIGGER: TRIGGER Position */ -#define TPI_TRIGGER_TRIGGER_Msk (0x1UL << TPI_TRIGGER_TRIGGER_Pos) /*!< TPI TRIGGER: TRIGGER Mask */ +#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 29 /*!< TPI FIFO0: ITM_ATVALID Position */ @@ -1207,11 +1260,11 @@ typedef struct #define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ #define TPI_FIFO0_ETM0_Pos 0 /*!< TPI FIFO0: ETM0 Position */ -#define TPI_FIFO0_ETM0_Msk (0xFFUL << TPI_FIFO0_ETM0_Pos) /*!< TPI FIFO0: ETM0 Mask */ +#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ /* TPI ITATBCTR2 Register Definitions */ #define TPI_ITATBCTR2_ATREADY_Pos 0 /*!< TPI ITATBCTR2: ATREADY Position */ -#define TPI_ITATBCTR2_ATREADY_Msk (0x1UL << TPI_ITATBCTR2_ATREADY_Pos) /*!< TPI ITATBCTR2: ATREADY Mask */ +#define TPI_ITATBCTR2_ATREADY_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY_Pos*/) /*!< TPI ITATBCTR2: ATREADY Mask */ /* TPI Integration ITM Data Register Definitions (FIFO1) */ #define TPI_FIFO1_ITM_ATVALID_Pos 29 /*!< TPI FIFO1: ITM_ATVALID Position */ @@ -1233,15 +1286,15 @@ typedef struct #define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ #define TPI_FIFO1_ITM0_Pos 0 /*!< TPI FIFO1: ITM0 Position */ -#define TPI_FIFO1_ITM0_Msk (0xFFUL << TPI_FIFO1_ITM0_Pos) /*!< TPI FIFO1: ITM0 Mask */ +#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ /* TPI ITATBCTR0 Register Definitions */ #define TPI_ITATBCTR0_ATREADY_Pos 0 /*!< TPI ITATBCTR0: ATREADY Position */ -#define TPI_ITATBCTR0_ATREADY_Msk (0x1UL << TPI_ITATBCTR0_ATREADY_Pos) /*!< TPI ITATBCTR0: ATREADY Mask */ +#define TPI_ITATBCTR0_ATREADY_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY_Pos*/) /*!< TPI ITATBCTR0: ATREADY Mask */ /* TPI Integration Mode Control Register Definitions */ #define TPI_ITCTRL_Mode_Pos 0 /*!< TPI ITCTRL: Mode Position */ -#define TPI_ITCTRL_Mode_Msk (0x1UL << TPI_ITCTRL_Mode_Pos) /*!< TPI ITCTRL: Mode Mask */ +#define TPI_ITCTRL_Mode_Msk (0x1UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ /* TPI DEVID Register Definitions */ #define TPI_DEVID_NRZVALID_Pos 11 /*!< TPI DEVID: NRZVALID Position */ @@ -1260,15 +1313,15 @@ typedef struct #define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ #define TPI_DEVID_NrTraceInput_Pos 0 /*!< TPI DEVID: NrTraceInput Position */ -#define TPI_DEVID_NrTraceInput_Msk (0x1FUL << TPI_DEVID_NrTraceInput_Pos) /*!< TPI DEVID: NrTraceInput Mask */ +#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ /* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 0 /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL << TPI_DEVTYPE_SubType_Pos) /*!< TPI DEVTYPE: SubType Mask */ - #define TPI_DEVTYPE_MajorType_Pos 4 /*!< TPI DEVTYPE: MajorType Position */ #define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ +#define TPI_DEVTYPE_SubType_Pos 0 /*!< TPI DEVTYPE: SubType Position */ +#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ + /*@}*/ /* end of group CMSIS_TPI */ @@ -1304,7 +1357,7 @@ typedef struct #define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ #define MPU_TYPE_SEPARATE_Pos 0 /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL << MPU_TYPE_SEPARATE_Pos) /*!< MPU TYPE: SEPARATE Mask */ +#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ /* MPU Control Register */ #define MPU_CTRL_PRIVDEFENA_Pos 2 /*!< MPU CTRL: PRIVDEFENA Position */ @@ -1314,11 +1367,11 @@ typedef struct #define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ #define MPU_CTRL_ENABLE_Pos 0 /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL << MPU_CTRL_ENABLE_Pos) /*!< MPU CTRL: ENABLE Mask */ +#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ /* MPU Region Number Register */ #define MPU_RNR_REGION_Pos 0 /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL << MPU_RNR_REGION_Pos) /*!< MPU RNR: REGION Mask */ +#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ /* MPU Region Base Address Register */ #define MPU_RBAR_ADDR_Pos 5 /*!< MPU RBAR: ADDR Position */ @@ -1328,7 +1381,7 @@ typedef struct #define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ #define MPU_RBAR_REGION_Pos 0 /*!< MPU RBAR: REGION Position */ -#define MPU_RBAR_REGION_Msk (0xFUL << MPU_RBAR_REGION_Pos) /*!< MPU RBAR: REGION Mask */ +#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ /* MPU Region Attribute and Size Register */ #define MPU_RASR_ATTRS_Pos 16 /*!< MPU RASR: MPU Region Attribute field Position */ @@ -1359,7 +1412,7 @@ typedef struct #define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ #define MPU_RASR_ENABLE_Pos 0 /*!< MPU RASR: Region enable bit Position */ -#define MPU_RASR_ENABLE_Msk (1UL << MPU_RASR_ENABLE_Pos) /*!< MPU RASR: Region enable bit Disable Mask */ +#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ /*@} end of group CMSIS_MPU */ #endif @@ -1411,7 +1464,7 @@ typedef struct #define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ #define FPU_FPCCR_LSPACT_Pos 0 /*!< FPCCR: Lazy state preservation active bit Position */ -#define FPU_FPCCR_LSPACT_Msk (1UL << FPU_FPCCR_LSPACT_Pos) /*!< FPCCR: Lazy state preservation active bit Mask */ +#define FPU_FPCCR_LSPACT_Msk (1UL /*<< FPU_FPCCR_LSPACT_Pos*/) /*!< FPCCR: Lazy state preservation active bit Mask */ /* Floating-Point Context Address Register */ #define FPU_FPCAR_ADDRESS_Pos 3 /*!< FPCAR: ADDRESS bit Position */ @@ -1453,7 +1506,7 @@ typedef struct #define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ #define FPU_MVFR0_A_SIMD_registers_Pos 0 /*!< 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 */ +#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 */ #define FPU_MVFR1_FP_fused_MAC_Pos 28 /*!< MVFR1: FP fused MAC bits Position */ @@ -1466,7 +1519,7 @@ typedef struct #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 0 /*!< MVFR1: FtZ mode bits Position */ -#define FPU_MVFR1_FtZ_mode_Msk (0xFUL << FPU_MVFR1_FtZ_mode_Pos) /*!< MVFR1: FtZ mode bits Mask */ +#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */ /* Media and FP Feature Register 2 */ @@ -1525,14 +1578,14 @@ typedef struct #define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ #define CoreDebug_DHCSR_C_DEBUGEN_Pos 0 /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL << CoreDebug_DHCSR_C_DEBUGEN_Pos) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ +#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ /* Debug Core Register Selector Register */ #define CoreDebug_DCRSR_REGWnR_Pos 16 /*!< CoreDebug DCRSR: REGWnR Position */ #define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ #define CoreDebug_DCRSR_REGSEL_Pos 0 /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL << CoreDebug_DCRSR_REGSEL_Pos) /*!< CoreDebug DCRSR: REGSEL Mask */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ /* Debug Exception and Monitor Control Register */ #define CoreDebug_DEMCR_TRCENA_Pos 24 /*!< CoreDebug DEMCR: TRCENA Position */ @@ -1572,7 +1625,7 @@ typedef struct #define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ #define CoreDebug_DEMCR_VC_CORERESET_Pos 0 /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL << CoreDebug_DEMCR_VC_CORERESET_Pos) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ +#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ /*@} end of group CMSIS_CoreDebug */ @@ -1649,13 +1702,13 @@ typedef struct __STATIC_INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); /* only values 0..7 are used */ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << 8)); /* Insert write key and priorty group */ + 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 << 8) ); /* Insert write key and priorty group */ SCB->AIRCR = reg_value; } @@ -1668,7 +1721,7 @@ __STATIC_INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) */ __STATIC_INLINE uint32_t NVIC_GetPriorityGrouping(void) { - return ((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos); /* read priority grouping field */ + return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); } @@ -1680,8 +1733,7 @@ __STATIC_INLINE uint32_t NVIC_GetPriorityGrouping(void) */ __STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) { -/* NVIC->ISER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); enable interrupt */ - NVIC->ISER[(uint32_t)((int32_t)IRQn) >> 5] = (uint32_t)(1 << ((uint32_t)((int32_t)IRQn) & (uint32_t)0x1F)); /* enable interrupt */ + NVIC->ISER[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -1693,7 +1745,7 @@ __STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) { - NVIC->ICER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* disable interrupt */ + NVIC->ICER[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -1709,7 +1761,7 @@ __STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) */ __STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) { - return((uint32_t) ((NVIC->ISPR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if pending else 0 */ + return((uint32_t)(((NVIC->ISPR[(((uint32_t)(int32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); } @@ -1721,7 +1773,7 @@ __STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) { - NVIC->ISPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* set interrupt pending */ + NVIC->ISPR[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -1733,7 +1785,7 @@ __STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) { - NVIC->ICPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */ + NVIC->ICPR[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -1748,7 +1800,7 @@ __STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) */ __STATIC_INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn) { - return((uint32_t)((NVIC->IABR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if active else 0 */ + return((uint32_t)(((NVIC->IABR[(((uint32_t)(int32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); } @@ -1763,10 +1815,12 @@ __STATIC_INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) { - if(IRQn < 0) { - SCB->SHPR[((uint32_t)(IRQn) & 0xF)-4] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for Cortex-M System Interrupts */ + if((int32_t)IRQn < 0) { + SCB->SHPR[(((uint32_t)(int32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8 - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } else { - NVIC->IP[(uint32_t)(IRQn)] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for device specific Interrupts */ + NVIC->IP[((uint32_t)(int32_t)IRQn)] = (uint8_t)((priority << (8 - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } } @@ -1784,10 +1838,12 @@ __STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) __STATIC_INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) { - if(IRQn < 0) { - return((uint32_t)(SCB->SHPR[((uint32_t)(IRQn) & 0xF)-4] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M system interrupts */ + if((int32_t)IRQn < 0) { + return(((uint32_t)SCB->SHPR[(((uint32_t)(int32_t)IRQn) & 0xFUL)-4UL] >> (8 - __NVIC_PRIO_BITS))); + } else { - return((uint32_t)(NVIC->IP[(uint32_t)(IRQn)] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */ + return(((uint32_t)NVIC->IP[((uint32_t)(int32_t)IRQn)] >> (8 - __NVIC_PRIO_BITS))); + } } @@ -1805,16 +1861,16 @@ __STATIC_INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) */ __STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) { - uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ uint32_t PreemptPriorityBits; uint32_t SubPriorityBits; - PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; - SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + 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 & ((1 << (PreemptPriorityBits)) - 1)) << SubPriorityBits) | - ((SubPriority & ((1 << (SubPriorityBits )) - 1))) + ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | + ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) ); } @@ -1833,15 +1889,15 @@ __STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t P */ __STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority) { - uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ uint32_t PreemptPriorityBits; uint32_t SubPriorityBits; - PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; - SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + 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) & ((1 << (PreemptPriorityBits)) - 1); - *pSubPriority = (Priority ) & ((1 << (SubPriorityBits )) - 1); + *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); + *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); } @@ -1851,18 +1907,52 @@ __STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGr */ __STATIC_INLINE void NVIC_SystemReset(void) { - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) | - (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | - SCB_AIRCR_SYSRESETREQ_Msk); /* Keep priority group unchanged */ - __DSB(); /* Ensure completion of memory access */ - while(1); /* wait until reset */ + __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 */ + while(1) { __NOP(); } /* wait until reset */ } /*@} end of CMSIS_Core_NVICFunctions */ +/* ########################## FPU functions #################################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_FpuFunctions FPU Functions + \brief Function that provides FPU type. + @{ + */ + +/** + \fn uint32_t SCB_GetFPUType(void) + \brief get FPU type + \returns + - \b 0: No FPU + - \b 1: Single precision FPU + - \b 2: Double + Single precision FPU + */ +__STATIC_INLINE uint32_t SCB_GetFPUType(void) +{ + uint32_t mvfr0; + + mvfr0 = SCB->MVFR0; + if ((mvfr0 & 0x00000FF0UL) == 0x220UL) { + return 2UL; // Double + Single precision FPU + } else if ((mvfr0 & 0x00000FF0UL) == 0x020UL) { + return 1UL; // Single precision FPU + } else { + return 0UL; // No FPU + } +} + + +/*@} end of CMSIS_Core_FpuFunctions */ + + + /* ########################## Cache functions #################################### */ /** \ingroup CMSIS_Core_FunctionInterface \defgroup CMSIS_Core_CacheFunctions Cache Functions @@ -1873,20 +1963,20 @@ __STATIC_INLINE void NVIC_SystemReset(void) /* Cache Size ID Register Macros */ #define CCSIDR_WAYS(x) (((x) & SCB_CCSIDR_ASSOCIATIVITY_Msk) >> SCB_CCSIDR_ASSOCIATIVITY_Pos) #define CCSIDR_SETS(x) (((x) & SCB_CCSIDR_NUMSETS_Msk ) >> SCB_CCSIDR_NUMSETS_Pos ) -#define CCSIDR_LSSHIFT(x) (((x) & SCB_CCSIDR_LINESIZE_Msk ) >> SCB_CCSIDR_LINESIZE_Pos ) +#define CCSIDR_LSSHIFT(x) (((x) & SCB_CCSIDR_LINESIZE_Msk ) /*>> SCB_CCSIDR_LINESIZE_Pos*/ ) /** \brief Enable I-Cache The function turns on I-Cache */ -__STATIC_INLINE void SCB_EnableICache(void) +__STATIC_INLINE void SCB_EnableICache (void) { #if (__ICACHE_PRESENT == 1) __DSB(); __ISB(); - SCB->ICIALLU = 0; // invalidate I-Cache - SCB->CCR |= SCB_CCR_IC_Msk; // enable I-Cache + SCB->ICIALLU = 0UL; // invalidate I-Cache + SCB->CCR |= (uint32_t)SCB_CCR_IC_Msk; // enable I-Cache __DSB(); __ISB(); #endif @@ -1897,13 +1987,13 @@ __STATIC_INLINE void SCB_EnableICache(void) The function turns off I-Cache */ -__STATIC_INLINE void SCB_DisableICache(void) +__STATIC_INLINE void SCB_DisableICache (void) { #if (__ICACHE_PRESENT == 1) __DSB(); __ISB(); - SCB->CCR &= ~SCB_CCR_IC_Msk; // disable I-Cache - SCB->ICIALLU = 0; // invalidate I-Cache + SCB->CCR &= ~(uint32_t)SCB_CCR_IC_Msk; // disable I-Cache + SCB->ICIALLU = 0UL; // invalidate I-Cache __DSB(); __ISB(); #endif @@ -1914,12 +2004,12 @@ __STATIC_INLINE void SCB_DisableICache(void) The function invalidates I-Cache */ -__STATIC_INLINE void SCB_InvalidateICache(void) +__STATIC_INLINE void SCB_InvalidateICache (void) { #if (__ICACHE_PRESENT == 1) __DSB(); __ISB(); - SCB->ICIALLU = 0; + SCB->ICIALLU = 0UL; __DSB(); __ISB(); #endif @@ -1930,22 +2020,23 @@ __STATIC_INLINE void SCB_InvalidateICache(void) The function turns on D-Cache */ -__STATIC_INLINE void SCB_EnableDCache(void) +__STATIC_INLINE void SCB_EnableDCache (void) { #if (__DCACHE_PRESENT == 1) uint32_t ccsidr, sshift, wshift, sw; uint32_t sets, ways; + SCB->CSSELR = (0UL << 1) | 0UL; // Level 1 data cache ccsidr = SCB->CCSIDR; - sets = CCSIDR_SETS(ccsidr); - sshift = CCSIDR_LSSHIFT(ccsidr) + 4; - ways = CCSIDR_WAYS(ccsidr); - wshift = __CLZ(ways) & 0x1f; + sets = (uint32_t)(CCSIDR_SETS(ccsidr)); + sshift = (uint32_t)(CCSIDR_LSSHIFT(ccsidr) + 4UL); + ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); + wshift = (uint32_t)((uint32_t)__CLZ(ways) & 0x1FUL); __DSB(); - do { // invalidate D-Cache - int32_t tmpways = ways; + do { // invalidate D-Cache + uint32_t tmpways = ways; do { sw = ((tmpways << wshift) | (sets << sshift)); SCB->DCISW = sw; @@ -1953,7 +2044,7 @@ __STATIC_INLINE void SCB_EnableDCache(void) } while(sets--); __DSB(); - SCB->CCR |= SCB_CCR_DC_Msk; // enable D-Cache + SCB->CCR |= (uint32_t)SCB_CCR_DC_Msk; // enable D-Cache __DSB(); __ISB(); @@ -1965,24 +2056,25 @@ __STATIC_INLINE void SCB_EnableDCache(void) The function turns off D-Cache */ -__STATIC_INLINE void SCB_DisableDCache(void) +__STATIC_INLINE void SCB_DisableDCache (void) { #if (__DCACHE_PRESENT == 1) uint32_t ccsidr, sshift, wshift, sw; uint32_t sets, ways; + SCB->CSSELR = (0UL << 1) | 0UL; // Level 1 data cache ccsidr = SCB->CCSIDR; - sets = CCSIDR_SETS(ccsidr); - sshift = CCSIDR_LSSHIFT(ccsidr) + 4; - ways = CCSIDR_WAYS(ccsidr); - wshift = __CLZ(ways) & 0x1f; + sets = (uint32_t)(CCSIDR_SETS(ccsidr)); + sshift = (uint32_t)(CCSIDR_LSSHIFT(ccsidr) + 4UL); + ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); + wshift = (uint32_t)((uint32_t)__CLZ(ways) & 0x1FUL); __DSB(); - SCB->CCR &= ~SCB_CCR_DC_Msk; // disable D-Cache + SCB->CCR &= ~(uint32_t)SCB_CCR_DC_Msk; // disable D-Cache do { // clean & invalidate D-Cache - int32_t tmpways = ways; + uint32_t tmpways = ways; do { sw = ((tmpways << wshift) | (sets << sshift)); SCB->DCCISW = sw; @@ -1992,7 +2084,7 @@ __STATIC_INLINE void SCB_DisableDCache(void) __DSB(); __ISB(); - #endif + #endif } @@ -2000,22 +2092,23 @@ __STATIC_INLINE void SCB_DisableDCache(void) The function invalidates D-Cache */ -__STATIC_INLINE void SCB_InvalidateDCache(void) +__STATIC_INLINE void SCB_InvalidateDCache (void) { #if (__DCACHE_PRESENT == 1) uint32_t ccsidr, sshift, wshift, sw; uint32_t sets, ways; + SCB->CSSELR = (0UL << 1) | 0UL; // Level 1 data cache ccsidr = SCB->CCSIDR; - sets = CCSIDR_SETS(ccsidr); - sshift = CCSIDR_LSSHIFT(ccsidr) + 4; - ways = CCSIDR_WAYS(ccsidr); - wshift = __CLZ(ways) & 0x1f; + sets = (uint32_t)(CCSIDR_SETS(ccsidr)); + sshift = (uint32_t)(CCSIDR_LSSHIFT(ccsidr) + 4UL); + ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); + wshift = (uint32_t)((uint32_t)__CLZ(ways) & 0x1FUL); __DSB(); do { // invalidate D-Cache - int32_t tmpways = ways; + uint32_t tmpways = ways; do { sw = ((tmpways << wshift) | (sets << sshift)); SCB->DCISW = sw; @@ -2024,7 +2117,7 @@ __STATIC_INLINE void SCB_InvalidateDCache(void) __DSB(); __ISB(); - #endif + #endif } @@ -2032,22 +2125,23 @@ __STATIC_INLINE void SCB_InvalidateDCache(void) The function cleans D-Cache */ -__STATIC_INLINE void SCB_CleanDCache(void) +__STATIC_INLINE void SCB_CleanDCache (void) { #if (__DCACHE_PRESENT == 1) uint32_t ccsidr, sshift, wshift, sw; uint32_t sets, ways; + SCB->CSSELR = (0UL << 1) | 0UL; // Level 1 data cache ccsidr = SCB->CCSIDR; - sets = CCSIDR_SETS(ccsidr); - sshift = CCSIDR_LSSHIFT(ccsidr) + 4; - ways = CCSIDR_WAYS(ccsidr); - wshift = __CLZ(ways) & 0x1f; + sets = (uint32_t)(CCSIDR_SETS(ccsidr)); + sshift = (uint32_t)(CCSIDR_LSSHIFT(ccsidr) + 4UL); + ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); + wshift = (uint32_t)((uint32_t)__CLZ(ways) & 0x1FUL); __DSB(); do { // clean D-Cache - int32_t tmpways = ways; + uint32_t tmpways = ways; do { sw = ((tmpways << wshift) | (sets << sshift)); SCB->DCCSW = sw; @@ -2056,7 +2150,7 @@ __STATIC_INLINE void SCB_CleanDCache(void) __DSB(); __ISB(); - #endif + #endif } @@ -2064,22 +2158,23 @@ __STATIC_INLINE void SCB_CleanDCache(void) The function cleans and Invalidates D-Cache */ -__STATIC_INLINE void SCB_CleanInvalidateDCache(void) +__STATIC_INLINE void SCB_CleanInvalidateDCache (void) { #if (__DCACHE_PRESENT == 1) uint32_t ccsidr, sshift, wshift, sw; uint32_t sets, ways; + SCB->CSSELR = (0UL << 1) | 0UL; // Level 1 data cache ccsidr = SCB->CCSIDR; - sets = CCSIDR_SETS(ccsidr); - sshift = CCSIDR_LSSHIFT(ccsidr) + 4; - ways = CCSIDR_WAYS(ccsidr); - wshift = __CLZ(ways) & 0x1f; + sets = (uint32_t)(CCSIDR_SETS(ccsidr)); + sshift = (uint32_t)(CCSIDR_LSSHIFT(ccsidr) + 4UL); + ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); + wshift = (uint32_t)((uint32_t)__CLZ(ways) & 0x1FUL); __DSB(); do { // clean & invalidate D-Cache - int32_t tmpways = ways; + uint32_t tmpways = ways; do { sw = ((tmpways << wshift) | (sets << sshift)); SCB->DCCISW = sw; @@ -2088,7 +2183,88 @@ __STATIC_INLINE void SCB_CleanInvalidateDCache(void) __DSB(); __ISB(); - #endif + #endif +} + + +/** + \fn void SCB_InvalidateDCache_by_Addr(volatile uint32_t *addr, int32_t dsize) + \brief D-Cache Invalidate by address + \param[in] addr address (aligned to 32-byte boundary) + \param[in] dsize size of memory block (in number of bytes) +*/ +__STATIC_INLINE void SCB_InvalidateDCache_by_Addr (uint32_t *addr, int32_t dsize) +{ + #if (__DCACHE_PRESENT == 1) + int32_t op_size = dsize; + uint32_t op_addr = (uint32_t)addr; + uint32_t linesize = 32UL; // in Cortex-M7 size of cache line is fixed to 8 words (32 bytes) + + __DSB(); + + while (op_size > 0) { + SCB->DCIMVAC = op_addr; + op_addr += linesize; + op_size -= (int32_t)linesize; + } + + __DSB(); + __ISB(); + #endif +} + + +/** + \fn void SCB_CleanDCache_by_Addr(volatile uint32_t *addr, int32_t dsize) + \brief D-Cache Clean by address + \param[in] addr address (aligned to 32-byte boundary) + \param[in] dsize size of memory block (in number of bytes) +*/ +__STATIC_INLINE void SCB_CleanDCache_by_Addr (uint32_t *addr, int32_t dsize) +{ + #if (__DCACHE_PRESENT == 1) + int32_t op_size = dsize; + uint32_t op_addr = (uint32_t) addr; + uint32_t linesize = 32UL; // in Cortex-M7 size of cache line is fixed to 8 words (32 bytes) + + __DSB(); + + while (op_size > 0) { + SCB->DCCMVAC = op_addr; + op_addr += linesize; + op_size -= (int32_t)linesize; + } + + __DSB(); + __ISB(); + #endif +} + + +/** + \fn void SCB_CleanInvalidateDCache_by_Addr(volatile uint32_t *addr, int32_t dsize) + \brief D-Cache Clean and Invalidate by address + \param[in] addr address (aligned to 32-byte boundary) + \param[in] dsize size of memory block (in number of bytes) +*/ +__STATIC_INLINE void SCB_CleanInvalidateDCache_by_Addr (uint32_t *addr, int32_t dsize) +{ + #if (__DCACHE_PRESENT == 1) + int32_t op_size = dsize; + uint32_t op_addr = (uint32_t) addr; + uint32_t linesize = 32UL; // in Cortex-M7 size of cache line is fixed to 8 words (32 bytes) + + __DSB(); + + while (op_size > 0) { + SCB->DCCIMVAC = op_addr; + op_addr += linesize; + op_size -= (int32_t)linesize; + } + + __DSB(); + __ISB(); + #endif } @@ -2122,15 +2298,15 @@ __STATIC_INLINE void SCB_CleanInvalidateDCache(void) */ __STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) { - if ((ticks - 1) > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) { return (1UL); } /* Reload value impossible */ - SysTick->LOAD = ticks - 1; /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0; /* Load the SysTick Counter Value */ + 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 (0); /* Function successful */ + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ } #endif @@ -2162,11 +2338,11 @@ extern volatile int32_t ITM_RxBuffer; /*!< External variable */ __STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) { - if ((ITM->TCR & ITM_TCR_ITMENA_Msk) && /* ITM enabled */ - (ITM->TER & (1UL << 0) ) ) /* ITM Port #0 enabled */ + if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ + ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ { - while (ITM->PORT[0].u32 == 0); - ITM->PORT[0].u8 = (uint8_t) ch; + while (ITM->PORT[0].u32 == 0UL) { __NOP(); } + ITM->PORT[0].u8 = (uint8_t)ch; } return (ch); } diff --git a/lib/main/CMSIS/CM4/CoreSupport/core_cmFunc.h b/lib/main/CMSIS/CM4/CoreSupport/core_cmFunc.h index 01089f1333..b6ad0a4c5f 100644 --- a/lib/main/CMSIS/CM4/CoreSupport/core_cmFunc.h +++ b/lib/main/CMSIS/CM4/CoreSupport/core_cmFunc.h @@ -1,13 +1,13 @@ /**************************************************************************//** * @file core_cmFunc.h * @brief CMSIS Cortex-M Core Function Access Header File - * @version V4.00 - * @date 28. August 2014 + * @version V4.10 + * @date 18. March 2015 * * @note * ******************************************************************************/ -/* Copyright (c) 2009 - 2014 ARM LIMITED +/* Copyright (c) 2009 - 2015 ARM LIMITED All rights reserved. Redistribution and use in source and binary forms, with or without @@ -242,6 +242,20 @@ __STATIC_INLINE void __set_BASEPRI(uint32_t basePri) } +/** \brief Set Base Priority with condition + + This function 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 & 0xff); +} + + /** \brief Get Fault Mask This function returns the current value of the Fault Mask register. @@ -518,7 +532,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_BASEPRI(void) { uint32_t result; - __ASM volatile ("MRS %0, basepri_max" : "=r" (result) ); + __ASM volatile ("MRS %0, basepri" : "=r" (result) ); return(result); } @@ -535,6 +549,19 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE void __set_BASEPRI(uint32_t v } +/** \brief Set Base Priority with condition + + This function assigns the given value to the Base Priority register only if BASEPRI masking is disabled, + or the new value increases the BASEPRI priority level. + + \param [in] basePri Base Priority value to set + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_BASEPRI_MAX(uint32_t value) +{ + __ASM volatile ("MSR basepri_max, %0" : : "r" (value) : "memory"); +} + + /** \brief Get Fault Mask This function returns the current value of the Fault Mask register. diff --git a/lib/main/CMSIS/CM4/CoreSupport/core_cmInstr.h b/lib/main/CMSIS/CM4/CoreSupport/core_cmInstr.h index d14110b2ab..fca425c51d 100644 --- a/lib/main/CMSIS/CM4/CoreSupport/core_cmInstr.h +++ b/lib/main/CMSIS/CM4/CoreSupport/core_cmInstr.h @@ -1,8 +1,8 @@ /**************************************************************************//** * @file core_cmInstr.h * @brief CMSIS Cortex-M Core Instruction Access Header File - * @version V4.00 - * @date 28. August 2014 + * @version V4.10 + * @date 18. March 2015 * * @note * @@ -89,24 +89,33 @@ so that all instructions following the ISB are fetched from cache or memory, after the instruction has been completed. */ -#define __ISB() __isb(0xF) - +#define __ISB() do {\ + __schedule_barrier();\ + __isb(0xF);\ + __schedule_barrier();\ + } while (0) /** \brief Data Synchronization Barrier This function acts as a special kind of Data Memory Barrier. It completes when all explicit memory accesses before this instruction complete. */ -#define __DSB() __dsb(0xF) - +#define __DSB() do {\ + __schedule_barrier();\ + __dsb(0xF);\ + __schedule_barrier();\ + } while (0) /** \brief Data Memory Barrier This function ensures the apparent order of the explicit memory operations before and after the instruction, without ensuring their completion. */ -#define __DMB() __dmb(0xF) - +#define __DMB() do {\ + __schedule_barrier();\ + __dmb(0xF);\ + __schedule_barrier();\ + } while (0) /** \brief Reverse byte order (32 bit) @@ -171,8 +180,6 @@ __attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int32_t __REVSH(in #define __BKPT(value) __breakpoint(value) -#if (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) - /** \brief Reverse bit order of value This function reverses the bit order of the given value. @@ -180,8 +187,38 @@ __attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int32_t __REVSH(in \param [in] value Value to reverse \return Reversed value */ -#define __RBIT __rbit +#if (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) + #define __RBIT __rbit +#else +__attribute__((always_inline)) __STATIC_INLINE uint32_t __RBIT(uint32_t value) +{ + uint32_t result; + int32_t s = 4 /*sizeof(v)*/ * 8 - 1; // extra shift needed at end + result = value; // r will be reversed bits of v; first get LSB of v + for (value >>= 1; value; value >>= 1) + { + result <<= 1; + result |= value & 1; + s--; + } + result <<= s; // shift when v's highest bits are zero + return(result); +} +#endif + + +/** \brief Count leading zeros + + This function 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 (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) /** \brief LDR Exclusive (8 bit) @@ -279,19 +316,10 @@ __attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int32_t __REVSH(in #define __USAT __usat -/** \brief Count leading zeros - - This function 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 - - /** \brief Rotate Right with Extend (32 bit) - This function moves each bit of a bitstring right by one bit. The carry input is shifted in at the left end of the bitstring. + This function 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 @@ -385,7 +413,7 @@ __attribute__((section(".rrx_text"))) __STATIC_INLINE __ASM uint32_t __RRX(uint3 No Operation does nothing. This instruction can be used for code alignment purposes. */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __NOP(void) +__attribute__((always_inline)) __STATIC_INLINE void __NOP(void) { __ASM volatile ("nop"); } @@ -396,7 +424,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE void __NOP(void) Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __WFI(void) +__attribute__((always_inline)) __STATIC_INLINE void __WFI(void) { __ASM volatile ("wfi"); } @@ -407,7 +435,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE void __WFI(void) 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. */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __WFE(void) +__attribute__((always_inline)) __STATIC_INLINE void __WFE(void) { __ASM volatile ("wfe"); } @@ -417,7 +445,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE void __WFE(void) Send Event is a hint instruction. It causes an event to be signaled to the CPU. */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __SEV(void) +__attribute__((always_inline)) __STATIC_INLINE void __SEV(void) { __ASM volatile ("sev"); } @@ -429,9 +457,9 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE void __SEV(void) so that all instructions following the ISB are fetched from cache or memory, after the instruction has been completed. */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __ISB(void) +__attribute__((always_inline)) __STATIC_INLINE void __ISB(void) { - __ASM volatile ("isb"); + __ASM volatile ("isb 0xF":::"memory"); } @@ -440,9 +468,9 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE void __ISB(void) This function acts as a special kind of Data Memory Barrier. It completes when all explicit memory accesses before this instruction complete. */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __DSB(void) +__attribute__((always_inline)) __STATIC_INLINE void __DSB(void) { - __ASM volatile ("dsb"); + __ASM volatile ("dsb 0xF":::"memory"); } @@ -451,9 +479,9 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE void __DSB(void) This function ensures the apparent order of the explicit memory operations before and after the instruction, without ensuring their completion. */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __DMB(void) +__attribute__((always_inline)) __STATIC_INLINE void __DMB(void) { - __ASM volatile ("dmb"); + __ASM volatile ("dmb 0xF":::"memory"); } @@ -464,7 +492,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE void __DMB(void) \param [in] value Value to reverse \return Reversed value */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV(uint32_t value) +__attribute__((always_inline)) __STATIC_INLINE uint32_t __REV(uint32_t value) { #if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 5) return __builtin_bswap32(value); @@ -484,7 +512,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV(uint32_t value \param [in] value Value to reverse \return Reversed value */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV16(uint32_t value) +__attribute__((always_inline)) __STATIC_INLINE uint32_t __REV16(uint32_t value) { uint32_t result; @@ -500,7 +528,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV16(uint32_t val \param [in] value Value to reverse \return Reversed value */ -__attribute__( ( always_inline ) ) __STATIC_INLINE int32_t __REVSH(int32_t value) +__attribute__((always_inline)) __STATIC_INLINE int32_t __REVSH(int32_t value) { #if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) return (short)__builtin_bswap16(value); @@ -521,9 +549,9 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE int32_t __REVSH(int32_t value \param [in] value Number of Bits to rotate \return Rotated value */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __ROR(uint32_t op1, uint32_t op2) +__attribute__((always_inline)) __STATIC_INLINE uint32_t __ROR(uint32_t op1, uint32_t op2) { - return (op1 >> op2) | (op1 << (32 - op2)); + return (op1 >> op2) | (op1 << (32 - op2)); } @@ -538,8 +566,6 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __ROR(uint32_t op1, #define __BKPT(value) __ASM volatile ("bkpt "#value) -#if (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) - /** \brief Reverse bit order of value This function reverses the bit order of the given value. @@ -547,15 +573,40 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __ROR(uint32_t op1, \param [in] value Value to reverse \return Reversed value */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __RBIT(uint32_t value) +__attribute__((always_inline)) __STATIC_INLINE uint32_t __RBIT(uint32_t value) { uint32_t result; +#if (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); - return(result); +#else + int32_t s = 4 /*sizeof(v)*/ * 8 - 1; // extra shift needed at end + + result = value; // r will be reversed bits of v; first get LSB of v + for (value >>= 1; value; value >>= 1) + { + result <<= 1; + result |= value & 1; + s--; + } + result <<= s; // shift when v's highest bits are zero +#endif + return(result); } +/** \brief Count leading zeros + + This function counts the number of leading zeros of a data value. + + \param [in] value Value to count the leading zeros + \return number of leading zeros in value + */ +#define __CLZ __builtin_clz + + +#if (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) + /** \brief LDR Exclusive (8 bit) This function executes a exclusive LDR instruction for 8 bit value. @@ -563,7 +614,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __RBIT(uint32_t valu \param [in] ptr Pointer to data \return value of type uint8_t at (*ptr) */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __LDREXB(volatile uint8_t *addr) +__attribute__((always_inline)) __STATIC_INLINE uint8_t __LDREXB(volatile uint8_t *addr) { uint32_t result; @@ -586,7 +637,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __LDREXB(volatile uin \param [in] ptr Pointer to data \return value of type uint16_t at (*ptr) */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint16_t __LDREXH(volatile uint16_t *addr) +__attribute__((always_inline)) __STATIC_INLINE uint16_t __LDREXH(volatile uint16_t *addr) { uint32_t result; @@ -609,7 +660,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint16_t __LDREXH(volatile ui \param [in] ptr Pointer to data \return value of type uint32_t at (*ptr) */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __LDREXW(volatile uint32_t *addr) +__attribute__((always_inline)) __STATIC_INLINE uint32_t __LDREXW(volatile uint32_t *addr) { uint32_t result; @@ -627,7 +678,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __LDREXW(volatile ui \return 0 Function succeeded \return 1 Function failed */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr) +__attribute__((always_inline)) __STATIC_INLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr) { uint32_t result; @@ -645,7 +696,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXB(uint8_t val \return 0 Function succeeded \return 1 Function failed */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr) +__attribute__((always_inline)) __STATIC_INLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr) { uint32_t result; @@ -663,7 +714,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXH(uint16_t va \return 0 Function succeeded \return 1 Function failed */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr) +__attribute__((always_inline)) __STATIC_INLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr) { uint32_t result; @@ -677,7 +728,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXW(uint32_t va This function removes the exclusive lock which is created by LDREX. */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __CLREX(void) +__attribute__((always_inline)) __STATIC_INLINE void __CLREX(void) { __ASM volatile ("clrex" ::: "memory"); } @@ -715,30 +766,15 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE void __CLREX(void) }) -/** \brief Count leading zeros - - This function 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 - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __CLZ(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("clz %0, %1" : "=r" (result) : "r" (value) ); - return ((uint8_t) result); /* Add explicit type cast here */ -} - - /** \brief Rotate Right with Extend (32 bit) - This function moves each bit of a bitstring right by one bit. The carry input is shifted in at the left end of the bitstring. + This function moves each bit of a bitstring right by one bit. + The carry input is shifted in at the left end of the bitstring. \param [in] value Value to rotate \return Rotated value */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __RRX(uint32_t value) +__attribute__((always_inline)) __STATIC_INLINE uint32_t __RRX(uint32_t value) { uint32_t result; @@ -754,7 +790,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __RRX(uint32_t value \param [in] ptr Pointer to data \return value of type uint8_t at (*ptr) */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __LDRBT(volatile uint8_t *addr) +__attribute__((always_inline)) __STATIC_INLINE uint8_t __LDRBT(volatile uint8_t *addr) { uint32_t result; @@ -777,7 +813,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __LDRBT(volatile uint \param [in] ptr Pointer to data \return value of type uint16_t at (*ptr) */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint16_t __LDRHT(volatile uint16_t *addr) +__attribute__((always_inline)) __STATIC_INLINE uint16_t __LDRHT(volatile uint16_t *addr) { uint32_t result; @@ -800,7 +836,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint16_t __LDRHT(volatile uin \param [in] ptr Pointer to data \return value of type uint32_t at (*ptr) */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __LDRT(volatile uint32_t *addr) +__attribute__((always_inline)) __STATIC_INLINE uint32_t __LDRT(volatile uint32_t *addr) { uint32_t result; @@ -816,7 +852,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __LDRT(volatile uint \param [in] value Value to store \param [in] ptr Pointer to location */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __STRBT(uint8_t value, volatile uint8_t *addr) +__attribute__((always_inline)) __STATIC_INLINE void __STRBT(uint8_t value, volatile uint8_t *addr) { __ASM volatile ("strbt %1, %0" : "=Q" (*addr) : "r" ((uint32_t)value) ); } @@ -829,7 +865,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE void __STRBT(uint8_t value, v \param [in] value Value to store \param [in] ptr Pointer to location */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __STRHT(uint16_t value, volatile uint16_t *addr) +__attribute__((always_inline)) __STATIC_INLINE void __STRHT(uint16_t value, volatile uint16_t *addr) { __ASM volatile ("strht %1, %0" : "=Q" (*addr) : "r" ((uint32_t)value) ); } @@ -842,7 +878,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE void __STRHT(uint16_t value, \param [in] value Value to store \param [in] ptr Pointer to location */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __STRT(uint32_t value, volatile uint32_t *addr) +__attribute__((always_inline)) __STATIC_INLINE void __STRT(uint32_t value, volatile uint32_t *addr) { __ASM volatile ("strt %1, %0" : "=Q" (*addr) : "r" (value) ); } diff --git a/lib/main/CMSIS/CM4/CoreSupport/core_cmSimd.h b/lib/main/CMSIS/CM4/CoreSupport/core_cmSimd.h index ee58eee56d..7b8e37fff6 100644 --- a/lib/main/CMSIS/CM4/CoreSupport/core_cmSimd.h +++ b/lib/main/CMSIS/CM4/CoreSupport/core_cmSimd.h @@ -1,8 +1,8 @@ /**************************************************************************//** * @file core_cmSimd.h * @brief CMSIS Cortex-M SIMD Header File - * @version V4.00 - * @date 22. August 2014 + * @version V4.10 + * @date 18. March 2015 * * @note * diff --git a/lib/main/CMSIS/CM4/CoreSupport/core_sc000.h b/lib/main/CMSIS/CM4/CoreSupport/core_sc000.h index 5d0219c89f..44cb027473 100644 --- a/lib/main/CMSIS/CM4/CoreSupport/core_sc000.h +++ b/lib/main/CMSIS/CM4/CoreSupport/core_sc000.h @@ -1,13 +1,13 @@ /**************************************************************************//** * @file core_sc000.h * @brief CMSIS SC000 Core Peripheral Access Layer Header File - * @version V4.00 - * @date 22. August 2014 + * @version V4.10 + * @date 18. March 2015 * * @note * ******************************************************************************/ -/* Copyright (c) 2009 - 2014 ARM LIMITED +/* Copyright (c) 2009 - 2015 ARM LIMITED All rights reserved. Redistribution and use in source and binary forms, with or without @@ -231,14 +231,7 @@ typedef union { struct { -#if (__CORTEX_M != 0x04) - uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */ -#else - 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 */ -#endif - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t _reserved0:28; /*!< bit: 0..27 Reserved */ uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ uint32_t C:1; /*!< bit: 29 Carry condition code flag */ uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ @@ -247,6 +240,19 @@ typedef union uint32_t w; /*!< Type used for word access */ } APSR_Type; +/* APSR Register Definitions */ +#define APSR_N_Pos 31 /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30 /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29 /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28 /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + /** \brief Union type to access the Interrupt Program Status Register (IPSR). */ @@ -260,6 +266,10 @@ typedef union uint32_t w; /*!< Type used for word access */ } IPSR_Type; +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0 /*!< 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). */ @@ -268,16 +278,9 @@ typedef union struct { uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ -#if (__CORTEX_M != 0x04) uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ -#else - uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ -#endif uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ - uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t _reserved1:3; /*!< bit: 25..27 Reserved */ uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ uint32_t C:1; /*!< bit: 29 Carry condition code flag */ uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ @@ -286,6 +289,25 @@ typedef union uint32_t w; /*!< Type used for word access */ } xPSR_Type; +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31 /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30 /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29 /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28 /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_T_Pos 24 /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_ISR_Pos 0 /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + /** \brief Union type to access the Control Registers (CONTROL). */ @@ -293,14 +315,17 @@ typedef union { struct { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ + uint32_t _reserved0:1; /*!< bit: 0 Reserved */ 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 */ + uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ } b; /*!< Structure used for bit access */ uint32_t w; /*!< Type used for word access */ } CONTROL_Type; +/* CONTROL Register Definitions */ +#define CONTROL_SPSEL_Pos 1 /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + /*@} end of group CMSIS_CORE */ @@ -349,7 +374,7 @@ typedef struct __IO uint32_t SHP[2]; /*!< Offset: 0x01C (R/W) System Handlers Priority Registers. [0] is RESERVED */ __IO uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ uint32_t RESERVED1[154]; - __IO uint32_t SFCR; /*!< Offset: 0x290 (R/W) Security Features Register */ + __IO uint32_t SFCR; /*!< Offset: 0x290 (R/W) Security Features Control Register */ } SCB_Type; /* SCB CPUID Register Definitions */ @@ -366,7 +391,7 @@ typedef struct #define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ #define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */ +#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 31 /*!< SCB ICSR: NMIPENDSET Position */ @@ -394,7 +419,7 @@ typedef struct #define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ #define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ /* SCB Interrupt Control State Register Definitions */ #define SCB_VTOR_TBLOFF_Pos 7 /*!< SCB VTOR: TBLOFF Position */ @@ -437,13 +462,6 @@ typedef struct #define SCB_SHCSR_SVCALLPENDED_Pos 15 /*!< SCB SHCSR: SVCALLPENDED Position */ #define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ -/* SCB Security Features Register Definitions */ -#define SCB_SFCR_UNIBRTIMING_Pos 0 /*!< SCB SFCR: UNIBRTIMING Position */ -#define SCB_SFCR_UNIBRTIMING_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SFCR: UNIBRTIMING Mask */ - -#define SCB_SFCR_SECKEY_Pos 16 /*!< SCB SFCR: SECKEY Position */ -#define SCB_SFCR_SECKEY_Msk (0xFFFFUL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SFCR: SECKEY Mask */ - /*@} end of group CMSIS_SCB */ @@ -463,7 +481,7 @@ typedef struct /* Auxiliary Control Register Definitions */ #define SCnSCB_ACTLR_DISMCYCINT_Pos 0 /*!< ACTLR: DISMCYCINT Position */ -#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL << SCnSCB_ACTLR_DISMCYCINT_Pos) /*!< ACTLR: DISMCYCINT Mask */ +#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ /*@} end of group CMSIS_SCnotSCB */ @@ -495,15 +513,15 @@ typedef struct #define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ #define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */ +#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ /* SysTick Reload Register Definitions */ #define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ /* SysTick Current Register Definitions */ #define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ /* SysTick Calibration Register Definitions */ #define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */ @@ -513,7 +531,7 @@ typedef struct #define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ #define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL << SysTick_CALIB_TENMS_Pos) /*!< SysTick CALIB: TENMS Mask */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ /*@} end of group CMSIS_SysTick */ @@ -543,7 +561,7 @@ typedef struct #define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ #define MPU_TYPE_SEPARATE_Pos 0 /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL << MPU_TYPE_SEPARATE_Pos) /*!< MPU TYPE: SEPARATE Mask */ +#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ /* MPU Control Register */ #define MPU_CTRL_PRIVDEFENA_Pos 2 /*!< MPU CTRL: PRIVDEFENA Position */ @@ -553,11 +571,11 @@ typedef struct #define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ #define MPU_CTRL_ENABLE_Pos 0 /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL << MPU_CTRL_ENABLE_Pos) /*!< MPU CTRL: ENABLE Mask */ +#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ /* MPU Region Number Register */ #define MPU_RNR_REGION_Pos 0 /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL << MPU_RNR_REGION_Pos) /*!< MPU RNR: REGION Mask */ +#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ /* MPU Region Base Address Register */ #define MPU_RBAR_ADDR_Pos 8 /*!< MPU RBAR: ADDR Position */ @@ -567,7 +585,7 @@ typedef struct #define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ #define MPU_RBAR_REGION_Pos 0 /*!< MPU RBAR: REGION Position */ -#define MPU_RBAR_REGION_Msk (0xFUL << MPU_RBAR_REGION_Pos) /*!< MPU RBAR: REGION Mask */ +#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ /* MPU Region Attribute and Size Register */ #define MPU_RASR_ATTRS_Pos 16 /*!< MPU RASR: MPU Region Attribute field Position */ @@ -598,7 +616,7 @@ typedef struct #define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ #define MPU_RASR_ENABLE_Pos 0 /*!< MPU RASR: Region enable bit Position */ -#define MPU_RASR_ENABLE_Msk (1UL << MPU_RASR_ENABLE_Pos) /*!< MPU RASR: Region enable bit Disable Mask */ +#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ /*@} end of group CMSIS_MPU */ #endif @@ -661,9 +679,9 @@ typedef struct /* Interrupt Priorities are WORD accessible only under ARMv6M */ /* The following MACROS handle generation of the register offset and byte masks */ -#define _BIT_SHIFT(IRQn) ( (((uint32_t)(IRQn) ) & 0x03) * 8 ) -#define _SHP_IDX(IRQn) ( ((((uint32_t)(IRQn) & 0x0F)-8) >> 2) ) -#define _IP_IDX(IRQn) ( ((uint32_t)(IRQn) >> 2) ) +#define _BIT_SHIFT(IRQn) ( ((((uint32_t)(int32_t)(IRQn)) ) & 0x03UL) * 8UL) +#define _SHP_IDX(IRQn) ( (((((uint32_t)(int32_t)(IRQn)) & 0x0FUL)-8UL) >> 2UL) ) +#define _IP_IDX(IRQn) ( (((uint32_t)(int32_t)(IRQn)) >> 2UL) ) /** \brief Enable External Interrupt @@ -674,7 +692,7 @@ typedef struct */ __STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) { - NVIC->ISER[0] = (1 << ((uint32_t)(IRQn) & 0x1F)); + NVIC->ISER[0] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -686,7 +704,7 @@ __STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) { - NVIC->ICER[0] = (1 << ((uint32_t)(IRQn) & 0x1F)); + NVIC->ICER[0] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -702,7 +720,7 @@ __STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) */ __STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) { - return((uint32_t) ((NVIC->ISPR[0] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); + return((uint32_t)(((NVIC->ISPR[0] & (1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); } @@ -714,7 +732,7 @@ __STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) { - NVIC->ISPR[0] = (1 << ((uint32_t)(IRQn) & 0x1F)); + NVIC->ISPR[0] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -726,7 +744,7 @@ __STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) { - NVIC->ICPR[0] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */ + NVIC->ICPR[0] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -741,12 +759,14 @@ __STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) { - if(IRQn < 0) { - SCB->SHP[_SHP_IDX(IRQn)] = (SCB->SHP[_SHP_IDX(IRQn)] & ~(0xFF << _BIT_SHIFT(IRQn))) | - (((priority << (8 - __NVIC_PRIO_BITS)) & 0xFF) << _BIT_SHIFT(IRQn)); } + if((int32_t)(IRQn) < 0) { + SCB->SHP[_SHP_IDX(IRQn)] = ((uint32_t)(SCB->SHP[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | + (((priority << (8 - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); + } else { - NVIC->IP[_IP_IDX(IRQn)] = (NVIC->IP[_IP_IDX(IRQn)] & ~(0xFF << _BIT_SHIFT(IRQn))) | - (((priority << (8 - __NVIC_PRIO_BITS)) & 0xFF) << _BIT_SHIFT(IRQn)); } + NVIC->IP[_IP_IDX(IRQn)] = ((uint32_t)(NVIC->IP[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | + (((priority << (8 - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); + } } @@ -764,10 +784,12 @@ __STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) __STATIC_INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) { - if(IRQn < 0) { - return((uint32_t)(((SCB->SHP[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & 0xFF) >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M0 system interrupts */ + if((int32_t)(IRQn) < 0) { + return((uint32_t)(((SCB->SHP[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8 - __NVIC_PRIO_BITS))); + } else { - return((uint32_t)(((NVIC->IP[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & 0xFF) >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */ + return((uint32_t)(((NVIC->IP[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8 - __NVIC_PRIO_BITS))); + } } @@ -779,10 +801,10 @@ __STATIC_INLINE void NVIC_SystemReset(void) { __DSB(); /* Ensure all outstanding memory accesses included buffered write are completed before reset */ - SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) | + SCB->AIRCR = ((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | SCB_AIRCR_SYSRESETREQ_Msk); __DSB(); /* Ensure completion of memory access */ - while(1); /* wait until reset */ + while(1) { __NOP(); } /* wait until reset */ } /*@} end of CMSIS_Core_NVICFunctions */ @@ -815,15 +837,15 @@ __STATIC_INLINE void NVIC_SystemReset(void) */ __STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) { - if ((ticks - 1) > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) {return (1UL);} /* Reload value impossible */ - SysTick->LOAD = ticks - 1; /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0; /* Load the SysTick Counter Value */ + 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 (0); /* Function successful */ + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ } #endif diff --git a/lib/main/CMSIS/CM4/CoreSupport/core_sc300.h b/lib/main/CMSIS/CM4/CoreSupport/core_sc300.h index b6f6e8b5f2..7e40672a94 100644 --- a/lib/main/CMSIS/CM4/CoreSupport/core_sc300.h +++ b/lib/main/CMSIS/CM4/CoreSupport/core_sc300.h @@ -1,13 +1,13 @@ /**************************************************************************//** * @file core_sc300.h * @brief CMSIS SC300 Core Peripheral Access Layer Header File - * @version V4.00 - * @date 22. August 2014 + * @version V4.10 + * @date 18. March 2015 * * @note * ******************************************************************************/ -/* Copyright (c) 2009 - 2014 ARM LIMITED +/* Copyright (c) 2009 - 2015 ARM LIMITED All rights reserved. Redistribution and use in source and binary forms, with or without @@ -232,13 +232,7 @@ typedef union { struct { -#if (__CORTEX_M != 0x04) uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */ -#else - 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 */ -#endif 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 */ @@ -248,6 +242,22 @@ typedef union uint32_t w; /*!< Type used for word access */ } APSR_Type; +/* APSR Register Definitions */ +#define APSR_N_Pos 31 /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30 /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29 /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28 /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + +#define APSR_Q_Pos 27 /*!< APSR: Q Position */ +#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ + /** \brief Union type to access the Interrupt Program Status Register (IPSR). */ @@ -261,6 +271,10 @@ typedef union uint32_t w; /*!< Type used for word access */ } IPSR_Type; +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0 /*!< 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). */ @@ -269,13 +283,7 @@ typedef union struct { uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ -#if (__CORTEX_M != 0x04) uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ -#else - uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ -#endif uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */ uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ @@ -287,6 +295,31 @@ typedef union uint32_t w; /*!< Type used for word access */ } xPSR_Type; +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31 /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30 /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29 /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28 /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_Q_Pos 27 /*!< xPSR: Q Position */ +#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ + +#define xPSR_IT_Pos 25 /*!< xPSR: IT Position */ +#define xPSR_IT_Msk (3UL << xPSR_IT_Pos) /*!< xPSR: IT Mask */ + +#define xPSR_T_Pos 24 /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_ISR_Pos 0 /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + /** \brief Union type to access the Control Registers (CONTROL). */ @@ -296,12 +329,18 @@ typedef union { 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 */ + uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ } b; /*!< Structure used for bit access */ uint32_t w; /*!< Type used for word access */ } CONTROL_Type; +/* CONTROL Register Definitions */ +#define CONTROL_SPSEL_Pos 1 /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + +#define CONTROL_nPRIV_Pos 0 /*!< CONTROL: nPRIV Position */ +#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ + /*@} end of group CMSIS_CORE */ @@ -332,7 +371,7 @@ typedef struct /* Software Triggered Interrupt Register Definitions */ #define NVIC_STIR_INTID_Pos 0 /*!< STIR: INTLINESNUM Position */ -#define NVIC_STIR_INTID_Msk (0x1FFUL << NVIC_STIR_INTID_Pos) /*!< STIR: INTLINESNUM Mask */ +#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ /*@} end of group CMSIS_NVIC */ @@ -368,6 +407,8 @@ typedef struct __I uint32_t ISAR[5]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ uint32_t RESERVED0[5]; __IO uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ + uint32_t RESERVED1[129]; + __IO uint32_t SFCR; /*!< Offset: 0x290 (R/W) Security Features Control Register */ } SCB_Type; /* SCB CPUID Register Definitions */ @@ -384,7 +425,7 @@ typedef struct #define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ #define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */ +#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 31 /*!< SCB ICSR: NMIPENDSET Position */ @@ -415,7 +456,7 @@ typedef struct #define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ #define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ /* SCB Vector Table Offset Register Definitions */ #define SCB_VTOR_TBLBASE_Pos 29 /*!< SCB VTOR: TBLBASE Position */ @@ -444,7 +485,7 @@ typedef struct #define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ #define SCB_AIRCR_VECTRESET_Pos 0 /*!< SCB AIRCR: VECTRESET Position */ -#define SCB_AIRCR_VECTRESET_Msk (1UL << SCB_AIRCR_VECTRESET_Pos) /*!< SCB AIRCR: VECTRESET Mask */ +#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ /* SCB System Control Register Definitions */ #define SCB_SCR_SEVONPEND_Pos 4 /*!< SCB SCR: SEVONPEND Position */ @@ -473,7 +514,7 @@ typedef struct #define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ #define SCB_CCR_NONBASETHRDENA_Pos 0 /*!< SCB CCR: NONBASETHRDENA Position */ -#define SCB_CCR_NONBASETHRDENA_Msk (1UL << SCB_CCR_NONBASETHRDENA_Pos) /*!< SCB CCR: NONBASETHRDENA Mask */ +#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 18 /*!< SCB SHCSR: USGFAULTENA Position */ @@ -516,7 +557,7 @@ typedef struct #define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ #define SCB_SHCSR_MEMFAULTACT_Pos 0 /*!< SCB SHCSR: MEMFAULTACT Position */ -#define SCB_SHCSR_MEMFAULTACT_Msk (1UL << SCB_SHCSR_MEMFAULTACT_Pos) /*!< SCB SHCSR: MEMFAULTACT Mask */ +#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ /* SCB Configurable Fault Status Registers Definitions */ #define SCB_CFSR_USGFAULTSR_Pos 16 /*!< SCB CFSR: Usage Fault Status Register Position */ @@ -526,7 +567,7 @@ typedef struct #define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ #define SCB_CFSR_MEMFAULTSR_Pos 0 /*!< 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 */ +#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ /* SCB Hard Fault Status Registers Definitions */ #define SCB_HFSR_DEBUGEVT_Pos 31 /*!< SCB HFSR: DEBUGEVT Position */ @@ -552,7 +593,7 @@ typedef struct #define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ #define SCB_DFSR_HALTED_Pos 0 /*!< SCB DFSR: HALTED Position */ -#define SCB_DFSR_HALTED_Msk (1UL << SCB_DFSR_HALTED_Pos) /*!< SCB DFSR: HALTED Mask */ +#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ /*@} end of group CMSIS_SCB */ @@ -574,7 +615,7 @@ typedef struct /* Interrupt Controller Type Register Definitions */ #define SCnSCB_ICTR_INTLINESNUM_Pos 0 /*!< ICTR: INTLINESNUM Position */ -#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL << SCnSCB_ICTR_INTLINESNUM_Pos) /*!< ICTR: INTLINESNUM Mask */ +#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ /*@} end of group CMSIS_SCnotSCB */ @@ -606,15 +647,15 @@ typedef struct #define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ #define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */ +#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ /* SysTick Reload Register Definitions */ #define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ /* SysTick Current Register Definitions */ #define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ /* SysTick Calibration Register Definitions */ #define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */ @@ -624,7 +665,7 @@ typedef struct #define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ #define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL << SysTick_CALIB_TENMS_Pos) /*!< SysTick CALIB: TENMS Mask */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ /*@} end of group CMSIS_SysTick */ @@ -675,7 +716,7 @@ typedef struct /* ITM Trace Privilege Register Definitions */ #define ITM_TPR_PRIVMASK_Pos 0 /*!< ITM TPR: PRIVMASK Position */ -#define ITM_TPR_PRIVMASK_Msk (0xFUL << ITM_TPR_PRIVMASK_Pos) /*!< ITM TPR: PRIVMASK Mask */ +#define ITM_TPR_PRIVMASK_Msk (0xFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ /* ITM Trace Control Register Definitions */ #define ITM_TCR_BUSY_Pos 23 /*!< ITM TCR: BUSY Position */ @@ -703,19 +744,19 @@ typedef struct #define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ #define ITM_TCR_ITMENA_Pos 0 /*!< ITM TCR: ITM Enable bit Position */ -#define ITM_TCR_ITMENA_Msk (1UL << ITM_TCR_ITMENA_Pos) /*!< ITM TCR: ITM Enable bit Mask */ +#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ /* ITM Integration Write Register Definitions */ #define ITM_IWR_ATVALIDM_Pos 0 /*!< ITM IWR: ATVALIDM Position */ -#define ITM_IWR_ATVALIDM_Msk (1UL << ITM_IWR_ATVALIDM_Pos) /*!< ITM IWR: ATVALIDM Mask */ +#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */ /* ITM Integration Read Register Definitions */ #define ITM_IRR_ATREADYM_Pos 0 /*!< ITM IRR: ATREADYM Position */ -#define ITM_IRR_ATREADYM_Msk (1UL << ITM_IRR_ATREADYM_Pos) /*!< ITM IRR: ATREADYM Mask */ +#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */ /* ITM Integration Mode Control Register Definitions */ #define ITM_IMCR_INTEGRATION_Pos 0 /*!< ITM IMCR: INTEGRATION Position */ -#define ITM_IMCR_INTEGRATION_Msk (1UL << ITM_IMCR_INTEGRATION_Pos) /*!< ITM IMCR: INTEGRATION Mask */ +#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */ /* ITM Lock Status Register Definitions */ #define ITM_LSR_ByteAcc_Pos 2 /*!< ITM LSR: ByteAcc Position */ @@ -725,7 +766,7 @@ typedef struct #define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ #define ITM_LSR_Present_Pos 0 /*!< ITM LSR: Present Position */ -#define ITM_LSR_Present_Msk (1UL << ITM_LSR_Present_Pos) /*!< ITM LSR: Present Mask */ +#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ /*@}*/ /* end of group CMSIS_ITM */ @@ -818,31 +859,31 @@ typedef struct #define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ #define DWT_CTRL_CYCCNTENA_Pos 0 /*!< DWT CTRL: CYCCNTENA Position */ -#define DWT_CTRL_CYCCNTENA_Msk (0x1UL << DWT_CTRL_CYCCNTENA_Pos) /*!< DWT CTRL: CYCCNTENA Mask */ +#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ /* DWT CPI Count Register Definitions */ #define DWT_CPICNT_CPICNT_Pos 0 /*!< DWT CPICNT: CPICNT Position */ -#define DWT_CPICNT_CPICNT_Msk (0xFFUL << DWT_CPICNT_CPICNT_Pos) /*!< DWT CPICNT: CPICNT Mask */ +#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 0 /*!< DWT EXCCNT: EXCCNT Position */ -#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL << DWT_EXCCNT_EXCCNT_Pos) /*!< DWT EXCCNT: EXCCNT Mask */ +#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ /* DWT Sleep Count Register Definitions */ #define DWT_SLEEPCNT_SLEEPCNT_Pos 0 /*!< DWT SLEEPCNT: SLEEPCNT Position */ -#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL << DWT_SLEEPCNT_SLEEPCNT_Pos) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ +#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ /* DWT LSU Count Register Definitions */ #define DWT_LSUCNT_LSUCNT_Pos 0 /*!< DWT LSUCNT: LSUCNT Position */ -#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL << DWT_LSUCNT_LSUCNT_Pos) /*!< DWT LSUCNT: LSUCNT Mask */ +#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 0 /*!< DWT FOLDCNT: FOLDCNT Position */ -#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL << DWT_FOLDCNT_FOLDCNT_Pos) /*!< DWT FOLDCNT: FOLDCNT Mask */ +#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ /* DWT Comparator Mask Register Definitions */ #define DWT_MASK_MASK_Pos 0 /*!< DWT MASK: MASK Position */ -#define DWT_MASK_MASK_Msk (0x1FUL << DWT_MASK_MASK_Pos) /*!< DWT MASK: MASK Mask */ +#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ /* DWT Comparator Function Register Definitions */ #define DWT_FUNCTION_MATCHED_Pos 24 /*!< DWT FUNCTION: MATCHED Position */ @@ -870,7 +911,7 @@ typedef struct #define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ #define DWT_FUNCTION_FUNCTION_Pos 0 /*!< DWT FUNCTION: FUNCTION Position */ -#define DWT_FUNCTION_FUNCTION_Msk (0xFUL << DWT_FUNCTION_FUNCTION_Pos) /*!< DWT FUNCTION: FUNCTION Mask */ +#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ /*@}*/ /* end of group CMSIS_DWT */ @@ -913,11 +954,11 @@ typedef struct /* TPI Asynchronous Clock Prescaler Register Definitions */ #define TPI_ACPR_PRESCALER_Pos 0 /*!< TPI ACPR: PRESCALER Position */ -#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL << TPI_ACPR_PRESCALER_Pos) /*!< TPI ACPR: PRESCALER Mask */ +#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 0 /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL << TPI_SPPR_TXMODE_Pos) /*!< TPI SPPR: TXMODE Mask */ +#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 3 /*!< TPI FFSR: FtNonStop Position */ @@ -930,7 +971,7 @@ typedef struct #define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ #define TPI_FFSR_FlInProg_Pos 0 /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL << TPI_FFSR_FlInProg_Pos) /*!< TPI FFSR: FlInProg Mask */ +#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 8 /*!< TPI FFCR: TrigIn Position */ @@ -941,7 +982,7 @@ typedef struct /* TPI TRIGGER Register Definitions */ #define TPI_TRIGGER_TRIGGER_Pos 0 /*!< TPI TRIGGER: TRIGGER Position */ -#define TPI_TRIGGER_TRIGGER_Msk (0x1UL << TPI_TRIGGER_TRIGGER_Pos) /*!< TPI TRIGGER: TRIGGER Mask */ +#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 29 /*!< TPI FIFO0: ITM_ATVALID Position */ @@ -963,11 +1004,11 @@ typedef struct #define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ #define TPI_FIFO0_ETM0_Pos 0 /*!< TPI FIFO0: ETM0 Position */ -#define TPI_FIFO0_ETM0_Msk (0xFFUL << TPI_FIFO0_ETM0_Pos) /*!< TPI FIFO0: ETM0 Mask */ +#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ /* TPI ITATBCTR2 Register Definitions */ #define TPI_ITATBCTR2_ATREADY_Pos 0 /*!< TPI ITATBCTR2: ATREADY Position */ -#define TPI_ITATBCTR2_ATREADY_Msk (0x1UL << TPI_ITATBCTR2_ATREADY_Pos) /*!< TPI ITATBCTR2: ATREADY Mask */ +#define TPI_ITATBCTR2_ATREADY_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY_Pos*/) /*!< TPI ITATBCTR2: ATREADY Mask */ /* TPI Integration ITM Data Register Definitions (FIFO1) */ #define TPI_FIFO1_ITM_ATVALID_Pos 29 /*!< TPI FIFO1: ITM_ATVALID Position */ @@ -989,15 +1030,15 @@ typedef struct #define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ #define TPI_FIFO1_ITM0_Pos 0 /*!< TPI FIFO1: ITM0 Position */ -#define TPI_FIFO1_ITM0_Msk (0xFFUL << TPI_FIFO1_ITM0_Pos) /*!< TPI FIFO1: ITM0 Mask */ +#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ /* TPI ITATBCTR0 Register Definitions */ #define TPI_ITATBCTR0_ATREADY_Pos 0 /*!< TPI ITATBCTR0: ATREADY Position */ -#define TPI_ITATBCTR0_ATREADY_Msk (0x1UL << TPI_ITATBCTR0_ATREADY_Pos) /*!< TPI ITATBCTR0: ATREADY Mask */ +#define TPI_ITATBCTR0_ATREADY_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY_Pos*/) /*!< TPI ITATBCTR0: ATREADY Mask */ /* TPI Integration Mode Control Register Definitions */ #define TPI_ITCTRL_Mode_Pos 0 /*!< TPI ITCTRL: Mode Position */ -#define TPI_ITCTRL_Mode_Msk (0x1UL << TPI_ITCTRL_Mode_Pos) /*!< TPI ITCTRL: Mode Mask */ +#define TPI_ITCTRL_Mode_Msk (0x1UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ /* TPI DEVID Register Definitions */ #define TPI_DEVID_NRZVALID_Pos 11 /*!< TPI DEVID: NRZVALID Position */ @@ -1016,15 +1057,15 @@ typedef struct #define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ #define TPI_DEVID_NrTraceInput_Pos 0 /*!< TPI DEVID: NrTraceInput Position */ -#define TPI_DEVID_NrTraceInput_Msk (0x1FUL << TPI_DEVID_NrTraceInput_Pos) /*!< TPI DEVID: NrTraceInput Mask */ +#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ /* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 0 /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL << TPI_DEVTYPE_SubType_Pos) /*!< TPI DEVTYPE: SubType Mask */ - #define TPI_DEVTYPE_MajorType_Pos 4 /*!< TPI DEVTYPE: MajorType Position */ #define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ +#define TPI_DEVTYPE_SubType_Pos 0 /*!< TPI DEVTYPE: SubType Position */ +#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ + /*@}*/ /* end of group CMSIS_TPI */ @@ -1060,7 +1101,7 @@ typedef struct #define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ #define MPU_TYPE_SEPARATE_Pos 0 /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL << MPU_TYPE_SEPARATE_Pos) /*!< MPU TYPE: SEPARATE Mask */ +#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ /* MPU Control Register */ #define MPU_CTRL_PRIVDEFENA_Pos 2 /*!< MPU CTRL: PRIVDEFENA Position */ @@ -1070,11 +1111,11 @@ typedef struct #define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ #define MPU_CTRL_ENABLE_Pos 0 /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL << MPU_CTRL_ENABLE_Pos) /*!< MPU CTRL: ENABLE Mask */ +#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ /* MPU Region Number Register */ #define MPU_RNR_REGION_Pos 0 /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL << MPU_RNR_REGION_Pos) /*!< MPU RNR: REGION Mask */ +#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ /* MPU Region Base Address Register */ #define MPU_RBAR_ADDR_Pos 5 /*!< MPU RBAR: ADDR Position */ @@ -1084,7 +1125,7 @@ typedef struct #define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ #define MPU_RBAR_REGION_Pos 0 /*!< MPU RBAR: REGION Position */ -#define MPU_RBAR_REGION_Msk (0xFUL << MPU_RBAR_REGION_Pos) /*!< MPU RBAR: REGION Mask */ +#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ /* MPU Region Attribute and Size Register */ #define MPU_RASR_ATTRS_Pos 16 /*!< MPU RASR: MPU Region Attribute field Position */ @@ -1115,7 +1156,7 @@ typedef struct #define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ #define MPU_RASR_ENABLE_Pos 0 /*!< MPU RASR: Region enable bit Position */ -#define MPU_RASR_ENABLE_Msk (1UL << MPU_RASR_ENABLE_Pos) /*!< MPU RASR: Region enable bit Disable Mask */ +#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ /*@} end of group CMSIS_MPU */ #endif @@ -1172,14 +1213,14 @@ typedef struct #define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ #define CoreDebug_DHCSR_C_DEBUGEN_Pos 0 /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL << CoreDebug_DHCSR_C_DEBUGEN_Pos) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ +#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ /* Debug Core Register Selector Register */ #define CoreDebug_DCRSR_REGWnR_Pos 16 /*!< CoreDebug DCRSR: REGWnR Position */ #define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ #define CoreDebug_DCRSR_REGSEL_Pos 0 /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL << CoreDebug_DCRSR_REGSEL_Pos) /*!< CoreDebug DCRSR: REGSEL Mask */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ /* Debug Exception and Monitor Control Register */ #define CoreDebug_DEMCR_TRCENA_Pos 24 /*!< CoreDebug DEMCR: TRCENA Position */ @@ -1219,7 +1260,7 @@ typedef struct #define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ #define CoreDebug_DEMCR_VC_CORERESET_Pos 0 /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL << CoreDebug_DEMCR_VC_CORERESET_Pos) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ +#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ /*@} end of group CMSIS_CoreDebug */ @@ -1291,13 +1332,13 @@ typedef struct __STATIC_INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); /* only values 0..7 are used */ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << 8)); /* Insert write key and priorty group */ + 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 << 8) ); /* Insert write key and priorty group */ SCB->AIRCR = reg_value; } @@ -1310,7 +1351,7 @@ __STATIC_INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) */ __STATIC_INLINE uint32_t NVIC_GetPriorityGrouping(void) { - return ((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos); /* read priority grouping field */ + return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); } @@ -1322,7 +1363,7 @@ __STATIC_INLINE uint32_t NVIC_GetPriorityGrouping(void) */ __STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) { - NVIC->ISER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* enable interrupt */ + NVIC->ISER[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -1334,7 +1375,7 @@ __STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) { - NVIC->ICER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* disable interrupt */ + NVIC->ICER[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -1350,7 +1391,7 @@ __STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) */ __STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) { - return((uint32_t) ((NVIC->ISPR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if pending else 0 */ + return((uint32_t)(((NVIC->ISPR[(((uint32_t)(int32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); } @@ -1362,7 +1403,7 @@ __STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) { - NVIC->ISPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* set interrupt pending */ + NVIC->ISPR[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -1374,7 +1415,7 @@ __STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) { - NVIC->ICPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */ + NVIC->ICPR[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); } @@ -1389,7 +1430,7 @@ __STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) */ __STATIC_INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn) { - return((uint32_t)((NVIC->IABR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if active else 0 */ + return((uint32_t)(((NVIC->IABR[(((uint32_t)(int32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); } @@ -1404,10 +1445,12 @@ __STATIC_INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn) */ __STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) { - if(IRQn < 0) { - SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for Cortex-M System Interrupts */ + if((int32_t)IRQn < 0) { + SCB->SHP[(((uint32_t)(int32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8 - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } else { - NVIC->IP[(uint32_t)(IRQn)] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for device specific Interrupts */ + NVIC->IP[((uint32_t)(int32_t)IRQn)] = (uint8_t)((priority << (8 - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } } @@ -1425,10 +1468,12 @@ __STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) __STATIC_INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) { - if(IRQn < 0) { - return((uint32_t)(SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M system interrupts */ + if((int32_t)IRQn < 0) { + return(((uint32_t)SCB->SHP[(((uint32_t)(int32_t)IRQn) & 0xFUL)-4UL] >> (8 - __NVIC_PRIO_BITS))); + } else { - return((uint32_t)(NVIC->IP[(uint32_t)(IRQn)] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */ + return(((uint32_t)NVIC->IP[((uint32_t)(int32_t)IRQn)] >> (8 - __NVIC_PRIO_BITS))); + } } @@ -1446,16 +1491,16 @@ __STATIC_INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) */ __STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) { - uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ uint32_t PreemptPriorityBits; uint32_t SubPriorityBits; - PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; - SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + 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 & ((1 << (PreemptPriorityBits)) - 1)) << SubPriorityBits) | - ((SubPriority & ((1 << (SubPriorityBits )) - 1))) + ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | + ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) ); } @@ -1474,15 +1519,15 @@ __STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t P */ __STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority) { - uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ uint32_t PreemptPriorityBits; uint32_t SubPriorityBits; - PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; - SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + 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) & ((1 << (PreemptPriorityBits)) - 1); - *pSubPriority = (Priority ) & ((1 << (SubPriorityBits )) - 1); + *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); + *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); } @@ -1492,13 +1537,13 @@ __STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGr */ __STATIC_INLINE void NVIC_SystemReset(void) { - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) | - (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | - SCB_AIRCR_SYSRESETREQ_Msk); /* Keep priority group unchanged */ - __DSB(); /* Ensure completion of memory access */ - while(1); /* wait until reset */ + __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 */ + while(1) { __NOP(); } /* wait until reset */ } /*@} end of CMSIS_Core_NVICFunctions */ @@ -1531,15 +1576,15 @@ __STATIC_INLINE void NVIC_SystemReset(void) */ __STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) { - if ((ticks - 1) > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) { return (1UL); } /* Reload value impossible */ - SysTick->LOAD = ticks - 1; /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0; /* Load the SysTick Counter Value */ + 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 (0); /* Function successful */ + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ } #endif @@ -1571,11 +1616,11 @@ extern volatile int32_t ITM_RxBuffer; /*!< External variable */ __STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) { - if ((ITM->TCR & ITM_TCR_ITMENA_Msk) && /* ITM enabled */ - (ITM->TER & (1UL << 0) ) ) /* ITM Port #0 enabled */ + if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ + ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ { - while (ITM->PORT[0].u32 == 0); - ITM->PORT[0].u8 = (uint8_t) ch; + while (ITM->PORT[0].u32 == 0UL) { __NOP(); } + ITM->PORT[0].u8 = (uint8_t)ch; } return (ch); } diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/Include/system_stm32f4xx.h b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/Include/system_stm32f4xx.h deleted file mode 100644 index 5e30ef8186..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/Include/system_stm32f4xx.h +++ /dev/null @@ -1,105 +0,0 @@ -/** - ****************************************************************************** - * @file system_stm32f4xx.h - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); - * You may not use this file except in compliance with the License. - * You may obtain a copy of the License at: - * - * http://www.st.com/software_license_agreement_liberty_v2 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32f4xx_system - * @{ - */ - -/** - * @brief Define to prevent recursive inclusion - */ -#ifndef __SYSTEM_STM32F4XX_H -#define __SYSTEM_STM32F4XX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/** @addtogroup STM32F4xx_System_Includes - * @{ - */ - -/** - * @} - */ - - -/** @addtogroup STM32F4xx_System_Exported_types - * @{ - */ - -extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ - - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Exported_Constants - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Exported_Functions - * @{ - */ - -extern void SystemInit(void); -extern void SystemCoreClockUpdate(void); -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /*__SYSTEM_STM32F4XX_H */ - -/** - * @} - */ - -/** - * @} - */ -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f401xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f401xx.s deleted file mode 100644 index 1e7a2d99b4..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f401xx.s +++ /dev/null @@ -1,440 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f401xx.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F401xx Devices vector table for GCC based toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Configure the clock system - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M4 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); - * You may not use this file except in compliance with the License. - * You may obtain a copy of the License at: - * - * http://www.st.com/software_license_agreement_liberty_v2 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - ****************************************************************************** - */ - - .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: - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call static constructors */ - bl __libc_init_array -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word 0 /* Reserved */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word 0 /* Reserved */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word FPU_IRQHandler /* FPU */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word SPI4_IRQHandler /* SPI4 */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak SPI4_IRQHandler - .thumb_set SPI4_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f40_41xxx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f40_41xxx.s deleted file mode 100644 index a27cb17cea..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f40_41xxx.s +++ /dev/null @@ -1,517 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f40_41xxx.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F40xxx/41xxx Devices vector table for GCC based toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Configure the clock system and the external SRAM mounted on - * STM324xG-EVAL board 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. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); - * You may not use this file except in compliance with the License. - * You may obtain a copy of the License at: - * - * http://www.st.com/software_license_agreement_liberty_v2 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - ****************************************************************************** - */ - - .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: - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call static constructors */ - bl __libc_init_array -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word CAN1_TX_IRQHandler /* CAN1 TX */ - .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ - .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ - .word CAN1_SCE_IRQHandler /* CAN1 SCE */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FSMC_IRQHandler /* FSMC */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word ETH_IRQHandler /* Ethernet */ - .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */ - .word CAN2_TX_IRQHandler /* CAN2 TX */ - .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ - .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ - .word CAN2_SCE_IRQHandler /* CAN2 SCE */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ - .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ - .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ - .word OTG_HS_IRQHandler /* USB OTG HS */ - .word DCMI_IRQHandler /* DCMI */ - .word CRYP_IRQHandler /* CRYP crypto */ - .word HASH_RNG_IRQHandler /* Hash and Rng */ - .word FPU_IRQHandler /* FPU */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FSMC_IRQHandler - .thumb_set FSMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak ETH_IRQHandler - .thumb_set ETH_IRQHandler,Default_Handler - - .weak ETH_WKUP_IRQHandler - .thumb_set ETH_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_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_OUT_IRQHandler - .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_IN_IRQHandler - .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler - - .weak OTG_HS_WKUP_IRQHandler - .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler - - .weak OTG_HS_IRQHandler - .thumb_set OTG_HS_IRQHandler,Default_Handler - - .weak DCMI_IRQHandler - .thumb_set DCMI_IRQHandler,Default_Handler - - .weak CRYP_IRQHandler - .thumb_set CRYP_IRQHandler,Default_Handler - - .weak HASH_RNG_IRQHandler - .thumb_set HASH_RNG_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f40xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f40xx.s deleted file mode 100644 index 7d5f05ee3d..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f40xx.s +++ /dev/null @@ -1,518 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f40_41xxx.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F40xxx/41xxx Devices vector table for GCC based toolchain. - * Same as startup_stm32f40_41xxx.s and maintained for legacy purpose - * 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 mounted on - * STM324xG-EVAL board 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. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); - * You may not use this file except in compliance with the License. - * You may obtain a copy of the License at: - * - * http://www.st.com/software_license_agreement_liberty_v2 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - ****************************************************************************** - */ - - .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: - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call static constructors */ - bl __libc_init_array -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word CAN1_TX_IRQHandler /* CAN1 TX */ - .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ - .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ - .word CAN1_SCE_IRQHandler /* CAN1 SCE */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FSMC_IRQHandler /* FSMC */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word ETH_IRQHandler /* Ethernet */ - .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */ - .word CAN2_TX_IRQHandler /* CAN2 TX */ - .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ - .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ - .word CAN2_SCE_IRQHandler /* CAN2 SCE */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ - .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ - .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ - .word OTG_HS_IRQHandler /* USB OTG HS */ - .word DCMI_IRQHandler /* DCMI */ - .word CRYP_IRQHandler /* CRYP crypto */ - .word HASH_RNG_IRQHandler /* Hash and Rng */ - .word FPU_IRQHandler /* FPU */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FSMC_IRQHandler - .thumb_set FSMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak ETH_IRQHandler - .thumb_set ETH_IRQHandler,Default_Handler - - .weak ETH_WKUP_IRQHandler - .thumb_set ETH_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_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_OUT_IRQHandler - .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_IN_IRQHandler - .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler - - .weak OTG_HS_WKUP_IRQHandler - .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler - - .weak OTG_HS_IRQHandler - .thumb_set OTG_HS_IRQHandler,Default_Handler - - .weak DCMI_IRQHandler - .thumb_set DCMI_IRQHandler,Default_Handler - - .weak CRYP_IRQHandler - .thumb_set CRYP_IRQHandler,Default_Handler - - .weak HASH_RNG_IRQHandler - .thumb_set HASH_RNG_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f410xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f410xx.s deleted file mode 100644 index a0ead1a973..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f410xx.s +++ /dev/null @@ -1,449 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f410xx.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F410xx Devices vector table for GCC based toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M4 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - - .syntax unified - .cpu cortex-m4 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global Default_Handler - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss -/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ - -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - ldr sp, =_estack /* set stack pointer */ - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call static constructors */ - bl __libc_init_array -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_IRQHandler /* TIM1 Update */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word 0 /* Reserved */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word TIM5_IRQHandler /* TIM5 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC */ - .word 0 /* Reserved */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word RNG_IRQHandler /* RNG */ - .word FPU_IRQHandler /* FPU */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word SPI5_IRQHandler /* SPI5 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word FMPI2C1_EV_IRQHandler /* FMPI2C1 Event */ - .word FMPI2C1_ER_IRQHandler /* FMPI2C1 Error */ - .word LPTIM1_IRQHandler /* LP TIM1 */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_IRQHandler - .thumb_set TIM1_UP_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak RNG_IRQHandler - .thumb_set RNG_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak SPI5_IRQHandler - .thumb_set SPI5_IRQHandler,Default_Handler - - .weak FMPI2C1_EV_IRQHandler - .thumb_set FMPI2C1_EV_IRQHandler,Default_Handler - - .weak FMPI2C1_ER_IRQHandler - .thumb_set FMPI2C1_ER_IRQHandler,Default_Handler - - .weak LPTIM1_IRQHandler - .thumb_set LPTIM1_IRQHandler,Default_Handler -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f411xe.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f411xe.s deleted file mode 100644 index 450995861a..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f411xe.s +++ /dev/null @@ -1,454 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f411xe.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F411xExx Devices vector table for GCC based toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M4 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - - .syntax unified - .cpu cortex-m4 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global Default_Handler - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss -/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ - -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - ldr sp, =_estack /* set stack pointer */ - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call static constructors */ - bl __libc_init_array -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word 0 /* Reserved */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word 0 /* Reserved */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word FPU_IRQHandler /* FPU */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word SPI4_IRQHandler /* SPI4 */ - .word SPI5_IRQHandler /* SPI5 */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak SPI4_IRQHandler - .thumb_set SPI4_IRQHandler,Default_Handler - - .weak SPI5_IRQHandler - .thumb_set SPI5_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ - diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f427_437xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f427_437xx.s deleted file mode 100644 index 8954eae0d1..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f427_437xx.s +++ /dev/null @@ -1,553 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f427_437xx.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F427xx/437xx Devices vector table for GCC based toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Configure the clock system and the external SRAM mounted on - * STM324x7I-EVAL board 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. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); - * You may not use this file except in compliance with the License. - * You may obtain a copy of the License at: - * - * http://www.st.com/software_license_agreement_liberty_v2 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - ****************************************************************************** - */ - - .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: - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call static constructors */ - bl __libc_init_array -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word CAN1_TX_IRQHandler /* CAN1 TX */ - .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ - .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ - .word CAN1_SCE_IRQHandler /* CAN1 SCE */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FSMC_IRQHandler /* FSMC */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word ETH_IRQHandler /* Ethernet */ - .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */ - .word CAN2_TX_IRQHandler /* CAN2 TX */ - .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ - .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ - .word CAN2_SCE_IRQHandler /* CAN2 SCE */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ - .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ - .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ - .word OTG_HS_IRQHandler /* USB OTG HS */ - .word DCMI_IRQHandler /* DCMI */ - .word CRYP_IRQHandler /* CRYP crypto */ - .word HASH_RNG_IRQHandler /* Hash and Rng */ - .word FPU_IRQHandler /* FPU */ - .word UART7_IRQHandler /* UART7 */ - .word UART8_IRQHandler /* UART8 */ - .word SPI4_IRQHandler /* SPI4 */ - .word SPI5_IRQHandler /* SPI5 */ - .word SPI6_IRQHandler /* SPI6 */ - .word SAI1_IRQHandler /* SAI1 */ - .word LTDC_IRQHandler /* LTDC */ - .word LTDC_ER_IRQHandler /* LTDC error */ - .word DMA2D_IRQHandler /* DMA2D */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FSMC_IRQHandler - .thumb_set FSMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak ETH_IRQHandler - .thumb_set ETH_IRQHandler,Default_Handler - - .weak ETH_WKUP_IRQHandler - .thumb_set ETH_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_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_OUT_IRQHandler - .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_IN_IRQHandler - .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler - - .weak OTG_HS_WKUP_IRQHandler - .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler - - .weak OTG_HS_IRQHandler - .thumb_set OTG_HS_IRQHandler,Default_Handler - - .weak DCMI_IRQHandler - .thumb_set DCMI_IRQHandler,Default_Handler - - .weak CRYP_IRQHandler - .thumb_set CRYP_IRQHandler,Default_Handler - - .weak HASH_RNG_IRQHandler - .thumb_set HASH_RNG_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak UART7_IRQHandler - .thumb_set UART7_IRQHandler,Default_Handler - - .weak UART8_IRQHandler - .thumb_set UART8_IRQHandler,Default_Handler - - .weak SPI4_IRQHandler - .thumb_set SPI4_IRQHandler,Default_Handler - - .weak SPI5_IRQHandler - .thumb_set SPI5_IRQHandler,Default_Handler - - .weak SPI6_IRQHandler - .thumb_set SPI6_IRQHandler,Default_Handler - - .weak SAI1_IRQHandler - .thumb_set SAI1_IRQHandler,Default_Handler - - .weak LTDC_IRQHandler - .thumb_set LTDC_IRQHandler,Default_Handler - - .weak LTDC_ER_IRQHandler - .thumb_set LTDC_ER_IRQHandler,Default_Handler - - .weak DMA2D_IRQHandler - .thumb_set DMA2D_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f427xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f427xx.s deleted file mode 100644 index 91a5f189fe..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f427xx.s +++ /dev/null @@ -1,554 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f427x.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F42xxx/43xxx Devices vector table for GCC based toolchain. - * Same as startup_stm32f42_43xxx.s and maintained for legacy purpose - * 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 mounted on - * STM324x9I-EVAL/STM324x7I-EVAL boards 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. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); - * You may not use this file except in compliance with the License. - * You may obtain a copy of the License at: - * - * http://www.st.com/software_license_agreement_liberty_v2 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - ****************************************************************************** - */ - - .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: - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call static constructors */ - bl __libc_init_array -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word CAN1_TX_IRQHandler /* CAN1 TX */ - .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ - .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ - .word CAN1_SCE_IRQHandler /* CAN1 SCE */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FSMC_IRQHandler /* FSMC */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word ETH_IRQHandler /* Ethernet */ - .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */ - .word CAN2_TX_IRQHandler /* CAN2 TX */ - .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ - .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ - .word CAN2_SCE_IRQHandler /* CAN2 SCE */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ - .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ - .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ - .word OTG_HS_IRQHandler /* USB OTG HS */ - .word DCMI_IRQHandler /* DCMI */ - .word CRYP_IRQHandler /* CRYP crypto */ - .word HASH_RNG_IRQHandler /* Hash and Rng */ - .word FPU_IRQHandler /* FPU */ - .word UART7_IRQHandler /* UART7 */ - .word UART8_IRQHandler /* UART8 */ - .word SPI4_IRQHandler /* SPI4 */ - .word SPI5_IRQHandler /* SPI5 */ - .word SPI6_IRQHandler /* SPI6 */ - .word SAI1_IRQHandler /* SAI1 */ - .word LTDC_IRQHandler /* LTDC */ - .word LTDC_ER_IRQHandler /* LTDC error */ - .word DMA2D_IRQHandler /* DMA2D */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FSMC_IRQHandler - .thumb_set FSMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak ETH_IRQHandler - .thumb_set ETH_IRQHandler,Default_Handler - - .weak ETH_WKUP_IRQHandler - .thumb_set ETH_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_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_OUT_IRQHandler - .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_IN_IRQHandler - .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler - - .weak OTG_HS_WKUP_IRQHandler - .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler - - .weak OTG_HS_IRQHandler - .thumb_set OTG_HS_IRQHandler,Default_Handler - - .weak DCMI_IRQHandler - .thumb_set DCMI_IRQHandler,Default_Handler - - .weak CRYP_IRQHandler - .thumb_set CRYP_IRQHandler,Default_Handler - - .weak HASH_RNG_IRQHandler - .thumb_set HASH_RNG_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak UART7_IRQHandler - .thumb_set UART7_IRQHandler,Default_Handler - - .weak UART8_IRQHandler - .thumb_set UART8_IRQHandler,Default_Handler - - .weak SPI4_IRQHandler - .thumb_set SPI4_IRQHandler,Default_Handler - - .weak SPI5_IRQHandler - .thumb_set SPI5_IRQHandler,Default_Handler - - .weak SPI6_IRQHandler - .thumb_set SPI6_IRQHandler,Default_Handler - - .weak SAI1_IRQHandler - .thumb_set SAI1_IRQHandler,Default_Handler - - .weak LTDC_IRQHandler - .thumb_set LTDC_IRQHandler,Default_Handler - - .weak LTDC_ER_IRQHandler - .thumb_set LTDC_ER_IRQHandler,Default_Handler - - .weak DMA2D_IRQHandler - .thumb_set DMA2D_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f429_439xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f429_439xx.s deleted file mode 100644 index 341d54c848..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f429_439xx.s +++ /dev/null @@ -1,553 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f429_439xx.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F429xx/439xx Devices vector table for GCC based toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Configure the clock system and the external SRAM mounted on - * STM324x9I-EVAL board 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. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); - * You may not use this file except in compliance with the License. - * You may obtain a copy of the License at: - * - * http://www.st.com/software_license_agreement_liberty_v2 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - ****************************************************************************** - */ - - .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: - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call static constructors */ - bl __libc_init_array -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word CAN1_TX_IRQHandler /* CAN1 TX */ - .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ - .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ - .word CAN1_SCE_IRQHandler /* CAN1 SCE */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FSMC_IRQHandler /* FSMC */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word ETH_IRQHandler /* Ethernet */ - .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */ - .word CAN2_TX_IRQHandler /* CAN2 TX */ - .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ - .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ - .word CAN2_SCE_IRQHandler /* CAN2 SCE */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ - .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ - .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ - .word OTG_HS_IRQHandler /* USB OTG HS */ - .word DCMI_IRQHandler /* DCMI */ - .word CRYP_IRQHandler /* CRYP crypto */ - .word HASH_RNG_IRQHandler /* Hash and Rng */ - .word FPU_IRQHandler /* FPU */ - .word UART7_IRQHandler /* UART7 */ - .word UART8_IRQHandler /* UART8 */ - .word SPI4_IRQHandler /* SPI4 */ - .word SPI5_IRQHandler /* SPI5 */ - .word SPI6_IRQHandler /* SPI6 */ - .word SAI1_IRQHandler /* SAI1 */ - .word LTDC_IRQHandler /* LTDC */ - .word LTDC_ER_IRQHandler /* LTDC error */ - .word DMA2D_IRQHandler /* DMA2D */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FSMC_IRQHandler - .thumb_set FSMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak ETH_IRQHandler - .thumb_set ETH_IRQHandler,Default_Handler - - .weak ETH_WKUP_IRQHandler - .thumb_set ETH_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_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_OUT_IRQHandler - .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_IN_IRQHandler - .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler - - .weak OTG_HS_WKUP_IRQHandler - .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler - - .weak OTG_HS_IRQHandler - .thumb_set OTG_HS_IRQHandler,Default_Handler - - .weak DCMI_IRQHandler - .thumb_set DCMI_IRQHandler,Default_Handler - - .weak CRYP_IRQHandler - .thumb_set CRYP_IRQHandler,Default_Handler - - .weak HASH_RNG_IRQHandler - .thumb_set HASH_RNG_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak UART7_IRQHandler - .thumb_set UART7_IRQHandler,Default_Handler - - .weak UART8_IRQHandler - .thumb_set UART8_IRQHandler,Default_Handler - - .weak SPI4_IRQHandler - .thumb_set SPI4_IRQHandler,Default_Handler - - .weak SPI5_IRQHandler - .thumb_set SPI5_IRQHandler,Default_Handler - - .weak SPI6_IRQHandler - .thumb_set SPI6_IRQHandler,Default_Handler - - .weak SAI1_IRQHandler - .thumb_set SAI1_IRQHandler,Default_Handler - - .weak LTDC_IRQHandler - .thumb_set LTDC_IRQHandler,Default_Handler - - .weak LTDC_ER_IRQHandler - .thumb_set LTDC_ER_IRQHandler,Default_Handler - - .weak DMA2D_IRQHandler - .thumb_set DMA2D_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f446xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f446xx.s deleted file mode 100644 index 00d96cb942..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f446xx.s +++ /dev/null @@ -1,554 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f446xx.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F446xx Devices vector table for GCC based toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M4 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - - .syntax unified - .cpu cortex-m4 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global Default_Handler - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss -/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ - -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - ldr sp, =_estack /* set stack pointer */ - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call static constructors */ - bl __libc_init_array -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word CAN1_TX_IRQHandler /* CAN1 TX */ - .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ - .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ - .word CAN1_SCE_IRQHandler /* CAN1 SCE */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FMC_IRQHandler /* FMC */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word CAN2_TX_IRQHandler /* CAN2 TX */ - .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ - .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ - .word CAN2_SCE_IRQHandler /* CAN2 SCE */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ - .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ - .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ - .word OTG_HS_IRQHandler /* USB OTG HS */ - .word DCMI_IRQHandler /* DCMI */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word FPU_IRQHandler /* FPU */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word SPI4_IRQHandler /* SPI4 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word SAI1_IRQHandler /* SAI1 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word SAI2_IRQHandler /* SAI2 */ - .word QuadSPI_IRQHandler /* QuadSPI */ - .word CEC_IRQHandler /* CEC */ - .word SPDIF_RX_IRQHandler /* SPDIF RX */ - .word FMPI2C1_Event_IRQHandler /* I2C 4 Event */ - .word FMPI2C1_Error_IRQHandler /* I2C 4 Error */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FMC_IRQHandler - .thumb_set FMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak CAN2_TX_IRQHandler - .thumb_set CAN2_TX_IRQHandler,Default_Handler - - .weak CAN2_RX0_IRQHandler - .thumb_set CAN2_RX0_IRQHandler,Default_Handler - - .weak CAN2_RX1_IRQHandler - .thumb_set CAN2_RX1_IRQHandler,Default_Handler - - .weak CAN2_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_OUT_IRQHandler - .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_IN_IRQHandler - .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler - - .weak OTG_HS_WKUP_IRQHandler - .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler - - .weak OTG_HS_IRQHandler - .thumb_set OTG_HS_IRQHandler,Default_Handler - - .weak DCMI_IRQHandler - .thumb_set DCMI_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak SPI4_IRQHandler - .thumb_set SPI4_IRQHandler,Default_Handler - - .weak SAI1_IRQHandler - .thumb_set SAI1_IRQHandler,Default_Handler - - .weak SAI2_IRQHandler - .thumb_set SAI2_IRQHandler,Default_Handler - - .weak QuadSPI_IRQHandler - .thumb_set QuadSPI_IRQHandler,Default_Handler - - .weak CEC_IRQHandler - .thumb_set CEC_IRQHandler,Default_Handler - - .weak SPDIF_RX_IRQHandler - .thumb_set SPDIF_RX_IRQHandler,Default_Handler - - .weak FMPI2C1_Event_IRQHandler - .thumb_set FMPI2C1_Event_IRQHandler,Default_Handler - - .weak FMPI2C1_Error_IRQHandler - .thumb_set FMPI2C1_Error_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ - diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f469_479xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f469_479xx.s deleted file mode 100644 index 85fc24d49a..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/SW4STM32/startup_stm32f469_479xx.s +++ /dev/null @@ -1,567 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f469_479xx.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F469xx/479xx Devices vector table for GCC based toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M4 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); - * You may not use this file except in compliance with the License. - * You may obtain a copy of the License at: - * - * http://www.st.com/software_license_agreement_liberty_v2 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - ****************************************************************************** - */ - - .syntax unified - .cpu cortex-m4 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global Default_Handler - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss -/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ - -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - ldr sp, =_estack /* set stack pointer */ - -/* 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 initialization function.*/ - bl SystemInit -/* Call static constructors */ - bl __libc_init_array -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - g_pfnVectors: - .word _estack - .word Reset_Handler - - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word CAN1_TX_IRQHandler /* CAN1 TX */ - .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ - .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ - .word CAN1_SCE_IRQHandler /* CAN1 SCE */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FMC_IRQHandler /* FMC */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word ETH_IRQHandler /* Ethernet */ - .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */ - .word CAN2_TX_IRQHandler /* CAN2 TX */ - .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ - .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ - .word CAN2_SCE_IRQHandler /* CAN2 SCE */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ - .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ - .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ - .word OTG_HS_IRQHandler /* USB OTG HS */ - .word DCMI_IRQHandler /* DCMI */ - .word CRYP_IRQHandler /* CRYP crypto */ - .word HASH_RNG_IRQHandler /* Hash and Rng */ - .word FPU_IRQHandler /* FPU */ - .word UART7_IRQHandler /* UART7 */ - .word UART8_IRQHandler /* UART8 */ - .word SPI4_IRQHandler /* SPI4 */ - .word SPI5_IRQHandler /* SPI5 */ - .word SPI6_IRQHandler /* SPI6 */ - .word SAI1_IRQHandler /* SAI1 */ - .word LTDC_IRQHandler /* LTDC */ - .word LTDC_ER_IRQHandler /* LTDC error */ - .word DMA2D_IRQHandler /* DMA2D */ - .word QUADSPI_IRQHandler /* QUADSPI */ - .word DSI_IRQHandler /* DSI */ - - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FMC_IRQHandler - .thumb_set FMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak ETH_IRQHandler - .thumb_set ETH_IRQHandler,Default_Handler - - .weak ETH_WKUP_IRQHandler - .thumb_set ETH_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_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_OUT_IRQHandler - .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_IN_IRQHandler - .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler - - .weak OTG_HS_WKUP_IRQHandler - .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler - - .weak OTG_HS_IRQHandler - .thumb_set OTG_HS_IRQHandler,Default_Handler - - .weak DCMI_IRQHandler - .thumb_set DCMI_IRQHandler,Default_Handler - - .weak CRYP_IRQHandler - .thumb_set CRYP_IRQHandler,Default_Handler - - .weak HASH_RNG_IRQHandler - .thumb_set HASH_RNG_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak UART7_IRQHandler - .thumb_set UART7_IRQHandler,Default_Handler - - .weak UART8_IRQHandler - .thumb_set UART8_IRQHandler,Default_Handler - - .weak SPI4_IRQHandler - .thumb_set SPI4_IRQHandler,Default_Handler - - .weak SPI5_IRQHandler - .thumb_set SPI5_IRQHandler,Default_Handler - - .weak SPI6_IRQHandler - .thumb_set SPI6_IRQHandler,Default_Handler - - .weak SAI1_IRQHandler - .thumb_set SAI1_IRQHandler,Default_Handler - - .weak LTDC_IRQHandler - .thumb_set LTDC_IRQHandler,Default_Handler - - .weak LTDC_ER_IRQHandler - .thumb_set LTDC_ER_IRQHandler,Default_Handler - - .weak DMA2D_IRQHandler - .thumb_set DMA2D_IRQHandler,Default_Handler - - .weak QUADSPI_IRQHandler - .thumb_set QUADSPI_IRQHandler,Default_Handler - - .weak DSI_IRQHandler - .thumb_set DSI_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ - - - - - - - diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TASKING/cstart_thumb2.asm b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TASKING/cstart_thumb2.asm deleted file mode 100644 index 46198d6ae8..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TASKING/cstart_thumb2.asm +++ /dev/null @@ -1,142 +0,0 @@ - - -;; NOTE: To allow the use of this file for both ARMv6M and ARMv7M, -;; we will only use 16-bit Thumb intructions. - - .extern _lc_ub_stack ; usr/sys mode stack pointer - .extern _lc_ue_stack ; symbol required by debugger - .extern _lc_ub_table ; ROM to RAM copy table - .extern main - .extern _Exit - .extern exit - .weak exit - .global __get_argcv - .weak __get_argcv - .extern __argcvbuf - .weak __argcvbuf - ;;.extern __init_hardware - - .extern SystemInit - - .if @defined('__PROF_ENABLE__') - .extern __prof_init - .endif - .if @defined('__POSIX__') - .extern posix_main - .extern _posix_boot_stack_top - .endif - - .global _START - - .section .text.cstart - - .thumb -_START: - ;; anticipate possible ROM/RAM remapping - ;; by loading the 'real' program address - ldr r1,=_Next - bx r1 -_Next: - ;; initialize the stack pointer - ldr r1,=_lc_ub_stack ; TODO: make this part of the vector table - mov sp,r1 - - ; Call the clock system intitialization function. - bl SystemInit - - ;; copy initialized sections from ROM to RAM - ;; and clear uninitialized data sections in RAM - - ldr r3,=_lc_ub_table - movs r0,#0 -cploop: - ldr r4,[r3,#0] ; load type - ldr r5,[r3,#4] ; dst address - ldr r6,[r3,#8] ; src address - ldr r7,[r3,#12] ; size - - cmp r4,#1 - beq copy - cmp r4,#2 - beq clear - b done - -copy: - subs r7,r7,#1 - ldrb r1,[r6,r7] - strb r1,[r5,r7] - bne copy - - adds r3,r3,#16 - b cploop - -clear: - subs r7,r7,#1 - strb r0,[r5,r7] - bne clear - - adds r3,r3,#16 - b cploop - -done: - - - .if @defined('__POSIX__') - - ;; posix stack buffer for system upbringing - ldr r0,=_posix_boot_stack_top - ldr r0, [r0] - mov sp,r0 - - .else - - ;; load r10 with end of USR/SYS stack, which is - ;; needed in case stack overflow checking is on - ;; NOTE: use 16-bit instructions only, for ARMv6M - ldr r0,=_lc_ue_stack - mov r10,r0 - - .endif - - .if @defined('__PROF_ENABLE__') - bl __prof_init - .endif - - .if @defined('__POSIX__') - ;; call posix_main with no arguments - bl posix_main - .else - ;; retrieve argc and argv (default argv[0]==NULL & argc==0) - bl __get_argcv - ldr r1,=__argcvbuf - ;; call main - bl main - .endif - - ;; call exit using the return value from main() - ;; Note. Calling exit will also run all functions - ;; that were supplied through atexit(). - bl exit - -__get_argcv: ; weak definition - movs r0,#0 - bx lr - - .ltorg - .endsec - - .calls '_START', ' ' - .calls '_START','__init_vector_table' - .if @defined('__PROF_ENABLE__') - .calls '_START','__prof_init' - .endif - .if @defined('__POSIX__') - .calls '_START','posix_main' - .else - .calls '_START','__get_argcv' - .calls '_START','main' - .endif - .calls '_START','exit' - .calls '_START','',0 - - .end diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f401xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f401xx.s deleted file mode 100644 index ac859cc3f3..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f401xx.s +++ /dev/null @@ -1,440 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f401xx.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F401xx Devices vector table for Atollic TrueSTUDIO 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 - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M4 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); - * You may not use this file except in compliance with the License. - * You may obtain a copy of the License at: - * - * http://www.st.com/software_license_agreement_liberty_v2 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - ****************************************************************************** - */ - - .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: - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call static constructors */ - bl __libc_init_array -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word 0 /* Reserved */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word 0 /* Reserved */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word FPU_IRQHandler /* FPU */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word SPI4_IRQHandler /* SPI4 */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak SPI4_IRQHandler - .thumb_set SPI4_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f40_41xxx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f40_41xxx.s deleted file mode 100644 index 797d08516d..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f40_41xxx.s +++ /dev/null @@ -1,517 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f40_41xxx.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F40xxx/41xxx Devices vector table for Atollic TrueSTUDIO 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 mounted on - * STM324xG-EVAL board 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. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); - * You may not use this file except in compliance with the License. - * You may obtain a copy of the License at: - * - * http://www.st.com/software_license_agreement_liberty_v2 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - ****************************************************************************** - */ - - .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: - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call static constructors */ - bl __libc_init_array -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word CAN1_TX_IRQHandler /* CAN1 TX */ - .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ - .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ - .word CAN1_SCE_IRQHandler /* CAN1 SCE */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FSMC_IRQHandler /* FSMC */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word ETH_IRQHandler /* Ethernet */ - .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */ - .word CAN2_TX_IRQHandler /* CAN2 TX */ - .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ - .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ - .word CAN2_SCE_IRQHandler /* CAN2 SCE */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ - .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ - .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ - .word OTG_HS_IRQHandler /* USB OTG HS */ - .word DCMI_IRQHandler /* DCMI */ - .word CRYP_IRQHandler /* CRYP crypto */ - .word HASH_RNG_IRQHandler /* Hash and Rng */ - .word FPU_IRQHandler /* FPU */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FSMC_IRQHandler - .thumb_set FSMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak ETH_IRQHandler - .thumb_set ETH_IRQHandler,Default_Handler - - .weak ETH_WKUP_IRQHandler - .thumb_set ETH_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_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_OUT_IRQHandler - .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_IN_IRQHandler - .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler - - .weak OTG_HS_WKUP_IRQHandler - .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler - - .weak OTG_HS_IRQHandler - .thumb_set OTG_HS_IRQHandler,Default_Handler - - .weak DCMI_IRQHandler - .thumb_set DCMI_IRQHandler,Default_Handler - - .weak CRYP_IRQHandler - .thumb_set CRYP_IRQHandler,Default_Handler - - .weak HASH_RNG_IRQHandler - .thumb_set HASH_RNG_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f40xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f40xx.s deleted file mode 100644 index 031acbc5ae..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f40xx.s +++ /dev/null @@ -1,518 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f40_41xxx.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F40xxx/41xxx Devices vector table for Atollic TrueSTUDIO toolchain. - * Same as startup_stm32f40_41xxx.s and maintained for legacy purpose - * 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 mounted on - * STM324xG-EVAL board 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. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); - * You may not use this file except in compliance with the License. - * You may obtain a copy of the License at: - * - * http://www.st.com/software_license_agreement_liberty_v2 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - ****************************************************************************** - */ - - .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: - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call static constructors */ - bl __libc_init_array -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word CAN1_TX_IRQHandler /* CAN1 TX */ - .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ - .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ - .word CAN1_SCE_IRQHandler /* CAN1 SCE */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FSMC_IRQHandler /* FSMC */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word ETH_IRQHandler /* Ethernet */ - .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */ - .word CAN2_TX_IRQHandler /* CAN2 TX */ - .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ - .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ - .word CAN2_SCE_IRQHandler /* CAN2 SCE */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ - .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ - .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ - .word OTG_HS_IRQHandler /* USB OTG HS */ - .word DCMI_IRQHandler /* DCMI */ - .word CRYP_IRQHandler /* CRYP crypto */ - .word HASH_RNG_IRQHandler /* Hash and Rng */ - .word FPU_IRQHandler /* FPU */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FSMC_IRQHandler - .thumb_set FSMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak ETH_IRQHandler - .thumb_set ETH_IRQHandler,Default_Handler - - .weak ETH_WKUP_IRQHandler - .thumb_set ETH_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_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_OUT_IRQHandler - .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_IN_IRQHandler - .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler - - .weak OTG_HS_WKUP_IRQHandler - .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler - - .weak OTG_HS_IRQHandler - .thumb_set OTG_HS_IRQHandler,Default_Handler - - .weak DCMI_IRQHandler - .thumb_set DCMI_IRQHandler,Default_Handler - - .weak CRYP_IRQHandler - .thumb_set CRYP_IRQHandler,Default_Handler - - .weak HASH_RNG_IRQHandler - .thumb_set HASH_RNG_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f410xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f410xx.s deleted file mode 100644 index e2266a7905..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f410xx.s +++ /dev/null @@ -1,449 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f410xx.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F410xx Devices vector table for Atollic TrueSTUDIO toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M4 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - - .syntax unified - .cpu cortex-m4 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global Default_Handler - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss -/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ - -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - ldr sp, =_estack /* set stack pointer */ - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call static constructors */ - bl __libc_init_array -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_IRQHandler /* TIM1 Update */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word 0 /* Reserved */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word TIM5_IRQHandler /* TIM5 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC */ - .word 0 /* Reserved */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word RNG_IRQHandler /* RNG */ - .word FPU_IRQHandler /* FPU */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word SPI5_IRQHandler /* SPI5 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word FMPI2C1_EV_IRQHandler /* FMPI2C1 Event */ - .word FMPI2C1_ER_IRQHandler /* FMPI2C1 Error */ - .word LPTIM1_IRQHandler /* LP TIM1 */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_IRQHandler - .thumb_set TIM1_UP_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak RNG_IRQHandler - .thumb_set RNG_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak SPI5_IRQHandler - .thumb_set SPI5_IRQHandler,Default_Handler - - .weak FMPI2C1_EV_IRQHandler - .thumb_set FMPI2C1_EV_IRQHandler,Default_Handler - - .weak FMPI2C1_ER_IRQHandler - .thumb_set FMPI2C1_ER_IRQHandler,Default_Handler - - .weak LPTIM1_IRQHandler - .thumb_set LPTIM1_IRQHandler,Default_Handler -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f411xe.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f411xe.s deleted file mode 100644 index fe50a1910e..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f411xe.s +++ /dev/null @@ -1,454 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f411xe.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F411xExx Devices vector table for Atollic TrueSTUDIO toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M4 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - - .syntax unified - .cpu cortex-m4 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global Default_Handler - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss -/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ - -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - ldr sp, =_estack /* set stack pointer */ - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call static constructors */ - bl __libc_init_array -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word 0 /* Reserved */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word 0 /* Reserved */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word FPU_IRQHandler /* FPU */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word SPI4_IRQHandler /* SPI4 */ - .word SPI5_IRQHandler /* SPI5 */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak SPI4_IRQHandler - .thumb_set SPI4_IRQHandler,Default_Handler - - .weak SPI5_IRQHandler - .thumb_set SPI5_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ - diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f427_437xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f427_437xx.s deleted file mode 100644 index 2cc21e96a6..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f427_437xx.s +++ /dev/null @@ -1,553 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f427_437xx.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F427xx/437xx Devices vector table for Atollic TrueSTUDIO 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 mounted on - * STM324x7I-EVAL board 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. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); - * You may not use this file except in compliance with the License. - * You may obtain a copy of the License at: - * - * http://www.st.com/software_license_agreement_liberty_v2 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - ****************************************************************************** - */ - - .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: - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call static constructors */ - bl __libc_init_array -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word CAN1_TX_IRQHandler /* CAN1 TX */ - .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ - .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ - .word CAN1_SCE_IRQHandler /* CAN1 SCE */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FSMC_IRQHandler /* FSMC */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word ETH_IRQHandler /* Ethernet */ - .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */ - .word CAN2_TX_IRQHandler /* CAN2 TX */ - .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ - .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ - .word CAN2_SCE_IRQHandler /* CAN2 SCE */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ - .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ - .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ - .word OTG_HS_IRQHandler /* USB OTG HS */ - .word DCMI_IRQHandler /* DCMI */ - .word CRYP_IRQHandler /* CRYP crypto */ - .word HASH_RNG_IRQHandler /* Hash and Rng */ - .word FPU_IRQHandler /* FPU */ - .word UART7_IRQHandler /* UART7 */ - .word UART8_IRQHandler /* UART8 */ - .word SPI4_IRQHandler /* SPI4 */ - .word SPI5_IRQHandler /* SPI5 */ - .word SPI6_IRQHandler /* SPI6 */ - .word SAI1_IRQHandler /* SAI1 */ - .word LTDC_IRQHandler /* LTDC */ - .word LTDC_ER_IRQHandler /* LTDC error */ - .word DMA2D_IRQHandler /* DMA2D */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FSMC_IRQHandler - .thumb_set FSMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak ETH_IRQHandler - .thumb_set ETH_IRQHandler,Default_Handler - - .weak ETH_WKUP_IRQHandler - .thumb_set ETH_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_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_OUT_IRQHandler - .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_IN_IRQHandler - .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler - - .weak OTG_HS_WKUP_IRQHandler - .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler - - .weak OTG_HS_IRQHandler - .thumb_set OTG_HS_IRQHandler,Default_Handler - - .weak DCMI_IRQHandler - .thumb_set DCMI_IRQHandler,Default_Handler - - .weak CRYP_IRQHandler - .thumb_set CRYP_IRQHandler,Default_Handler - - .weak HASH_RNG_IRQHandler - .thumb_set HASH_RNG_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak UART7_IRQHandler - .thumb_set UART7_IRQHandler,Default_Handler - - .weak UART8_IRQHandler - .thumb_set UART8_IRQHandler,Default_Handler - - .weak SPI4_IRQHandler - .thumb_set SPI4_IRQHandler,Default_Handler - - .weak SPI5_IRQHandler - .thumb_set SPI5_IRQHandler,Default_Handler - - .weak SPI6_IRQHandler - .thumb_set SPI6_IRQHandler,Default_Handler - - .weak SAI1_IRQHandler - .thumb_set SAI1_IRQHandler,Default_Handler - - .weak LTDC_IRQHandler - .thumb_set LTDC_IRQHandler,Default_Handler - - .weak LTDC_ER_IRQHandler - .thumb_set LTDC_ER_IRQHandler,Default_Handler - - .weak DMA2D_IRQHandler - .thumb_set DMA2D_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f427xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f427xx.s deleted file mode 100644 index c53735d55b..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f427xx.s +++ /dev/null @@ -1,554 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f427x.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F42xxx/43xxx Devices vector table for Atollic TrueSTUDIO toolchain. - * Same as startup_stm32f42_43xxx.s and maintained for legacy purpose - * 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 mounted on - * STM324x9I-EVAL/STM324x7I-EVAL boards 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. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); - * You may not use this file except in compliance with the License. - * You may obtain a copy of the License at: - * - * http://www.st.com/software_license_agreement_liberty_v2 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - ****************************************************************************** - */ - - .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: - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call static constructors */ - bl __libc_init_array -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word CAN1_TX_IRQHandler /* CAN1 TX */ - .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ - .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ - .word CAN1_SCE_IRQHandler /* CAN1 SCE */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FSMC_IRQHandler /* FSMC */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word ETH_IRQHandler /* Ethernet */ - .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */ - .word CAN2_TX_IRQHandler /* CAN2 TX */ - .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ - .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ - .word CAN2_SCE_IRQHandler /* CAN2 SCE */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ - .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ - .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ - .word OTG_HS_IRQHandler /* USB OTG HS */ - .word DCMI_IRQHandler /* DCMI */ - .word CRYP_IRQHandler /* CRYP crypto */ - .word HASH_RNG_IRQHandler /* Hash and Rng */ - .word FPU_IRQHandler /* FPU */ - .word UART7_IRQHandler /* UART7 */ - .word UART8_IRQHandler /* UART8 */ - .word SPI4_IRQHandler /* SPI4 */ - .word SPI5_IRQHandler /* SPI5 */ - .word SPI6_IRQHandler /* SPI6 */ - .word SAI1_IRQHandler /* SAI1 */ - .word LTDC_IRQHandler /* LTDC */ - .word LTDC_ER_IRQHandler /* LTDC error */ - .word DMA2D_IRQHandler /* DMA2D */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FSMC_IRQHandler - .thumb_set FSMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak ETH_IRQHandler - .thumb_set ETH_IRQHandler,Default_Handler - - .weak ETH_WKUP_IRQHandler - .thumb_set ETH_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_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_OUT_IRQHandler - .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_IN_IRQHandler - .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler - - .weak OTG_HS_WKUP_IRQHandler - .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler - - .weak OTG_HS_IRQHandler - .thumb_set OTG_HS_IRQHandler,Default_Handler - - .weak DCMI_IRQHandler - .thumb_set DCMI_IRQHandler,Default_Handler - - .weak CRYP_IRQHandler - .thumb_set CRYP_IRQHandler,Default_Handler - - .weak HASH_RNG_IRQHandler - .thumb_set HASH_RNG_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak UART7_IRQHandler - .thumb_set UART7_IRQHandler,Default_Handler - - .weak UART8_IRQHandler - .thumb_set UART8_IRQHandler,Default_Handler - - .weak SPI4_IRQHandler - .thumb_set SPI4_IRQHandler,Default_Handler - - .weak SPI5_IRQHandler - .thumb_set SPI5_IRQHandler,Default_Handler - - .weak SPI6_IRQHandler - .thumb_set SPI6_IRQHandler,Default_Handler - - .weak SAI1_IRQHandler - .thumb_set SAI1_IRQHandler,Default_Handler - - .weak LTDC_IRQHandler - .thumb_set LTDC_IRQHandler,Default_Handler - - .weak LTDC_ER_IRQHandler - .thumb_set LTDC_ER_IRQHandler,Default_Handler - - .weak DMA2D_IRQHandler - .thumb_set DMA2D_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f429_439xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f429_439xx.s deleted file mode 100644 index 14ffbebb0b..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f429_439xx.s +++ /dev/null @@ -1,553 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f429_439xx.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F429xx/439xx Devices vector table for Atollic TrueSTUDIO 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 mounted on - * STM324x9I-EVAL board 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. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); - * You may not use this file except in compliance with the License. - * You may obtain a copy of the License at: - * - * http://www.st.com/software_license_agreement_liberty_v2 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - ****************************************************************************** - */ - - .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: - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call static constructors */ - bl __libc_init_array -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word CAN1_TX_IRQHandler /* CAN1 TX */ - .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ - .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ - .word CAN1_SCE_IRQHandler /* CAN1 SCE */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FSMC_IRQHandler /* FSMC */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word ETH_IRQHandler /* Ethernet */ - .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */ - .word CAN2_TX_IRQHandler /* CAN2 TX */ - .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ - .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ - .word CAN2_SCE_IRQHandler /* CAN2 SCE */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ - .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ - .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ - .word OTG_HS_IRQHandler /* USB OTG HS */ - .word DCMI_IRQHandler /* DCMI */ - .word CRYP_IRQHandler /* CRYP crypto */ - .word HASH_RNG_IRQHandler /* Hash and Rng */ - .word FPU_IRQHandler /* FPU */ - .word UART7_IRQHandler /* UART7 */ - .word UART8_IRQHandler /* UART8 */ - .word SPI4_IRQHandler /* SPI4 */ - .word SPI5_IRQHandler /* SPI5 */ - .word SPI6_IRQHandler /* SPI6 */ - .word SAI1_IRQHandler /* SAI1 */ - .word LTDC_IRQHandler /* LTDC */ - .word LTDC_ER_IRQHandler /* LTDC error */ - .word DMA2D_IRQHandler /* DMA2D */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FSMC_IRQHandler - .thumb_set FSMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak ETH_IRQHandler - .thumb_set ETH_IRQHandler,Default_Handler - - .weak ETH_WKUP_IRQHandler - .thumb_set ETH_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_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_OUT_IRQHandler - .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_IN_IRQHandler - .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler - - .weak OTG_HS_WKUP_IRQHandler - .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler - - .weak OTG_HS_IRQHandler - .thumb_set OTG_HS_IRQHandler,Default_Handler - - .weak DCMI_IRQHandler - .thumb_set DCMI_IRQHandler,Default_Handler - - .weak CRYP_IRQHandler - .thumb_set CRYP_IRQHandler,Default_Handler - - .weak HASH_RNG_IRQHandler - .thumb_set HASH_RNG_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak UART7_IRQHandler - .thumb_set UART7_IRQHandler,Default_Handler - - .weak UART8_IRQHandler - .thumb_set UART8_IRQHandler,Default_Handler - - .weak SPI4_IRQHandler - .thumb_set SPI4_IRQHandler,Default_Handler - - .weak SPI5_IRQHandler - .thumb_set SPI5_IRQHandler,Default_Handler - - .weak SPI6_IRQHandler - .thumb_set SPI6_IRQHandler,Default_Handler - - .weak SAI1_IRQHandler - .thumb_set SAI1_IRQHandler,Default_Handler - - .weak LTDC_IRQHandler - .thumb_set LTDC_IRQHandler,Default_Handler - - .weak LTDC_ER_IRQHandler - .thumb_set LTDC_ER_IRQHandler,Default_Handler - - .weak DMA2D_IRQHandler - .thumb_set DMA2D_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f446xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f446xx.s deleted file mode 100644 index 8d71efdfe6..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f446xx.s +++ /dev/null @@ -1,554 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f446xx.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F446xx Devices vector table for Atollic TrueSTUDIO toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M4 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - - .syntax unified - .cpu cortex-m4 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global Default_Handler - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss -/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ - -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - ldr sp, =_estack /* set stack pointer */ - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call static constructors */ - bl __libc_init_array -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word CAN1_TX_IRQHandler /* CAN1 TX */ - .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ - .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ - .word CAN1_SCE_IRQHandler /* CAN1 SCE */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FMC_IRQHandler /* FMC */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word CAN2_TX_IRQHandler /* CAN2 TX */ - .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ - .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ - .word CAN2_SCE_IRQHandler /* CAN2 SCE */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ - .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ - .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ - .word OTG_HS_IRQHandler /* USB OTG HS */ - .word DCMI_IRQHandler /* DCMI */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word FPU_IRQHandler /* FPU */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word SPI4_IRQHandler /* SPI4 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word SAI1_IRQHandler /* SAI1 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word SAI2_IRQHandler /* SAI2 */ - .word QuadSPI_IRQHandler /* QuadSPI */ - .word CEC_IRQHandler /* CEC */ - .word SPDIF_RX_IRQHandler /* SPDIF RX */ - .word FMPI2C1_Event_IRQHandler /* I2C 4 Event */ - .word FMPI2C1_Error_IRQHandler /* I2C 4 Error */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FMC_IRQHandler - .thumb_set FMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak CAN2_TX_IRQHandler - .thumb_set CAN2_TX_IRQHandler,Default_Handler - - .weak CAN2_RX0_IRQHandler - .thumb_set CAN2_RX0_IRQHandler,Default_Handler - - .weak CAN2_RX1_IRQHandler - .thumb_set CAN2_RX1_IRQHandler,Default_Handler - - .weak CAN2_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_OUT_IRQHandler - .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_IN_IRQHandler - .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler - - .weak OTG_HS_WKUP_IRQHandler - .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler - - .weak OTG_HS_IRQHandler - .thumb_set OTG_HS_IRQHandler,Default_Handler - - .weak DCMI_IRQHandler - .thumb_set DCMI_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak SPI4_IRQHandler - .thumb_set SPI4_IRQHandler,Default_Handler - - .weak SAI1_IRQHandler - .thumb_set SAI1_IRQHandler,Default_Handler - - .weak SAI2_IRQHandler - .thumb_set SAI2_IRQHandler,Default_Handler - - .weak QuadSPI_IRQHandler - .thumb_set QuadSPI_IRQHandler,Default_Handler - - .weak CEC_IRQHandler - .thumb_set CEC_IRQHandler,Default_Handler - - .weak SPDIF_RX_IRQHandler - .thumb_set SPDIF_RX_IRQHandler,Default_Handler - - .weak FMPI2C1_Event_IRQHandler - .thumb_set FMPI2C1_Event_IRQHandler,Default_Handler - - .weak FMPI2C1_Error_IRQHandler - .thumb_set FMPI2C1_Error_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ - diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f469_479xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f469_479xx.s deleted file mode 100644 index d2e17d63c3..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/TrueSTUDIO/startup_stm32f469_479xx.s +++ /dev/null @@ -1,567 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f469_479xx.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F469xx/479xx Devices vector table for Atollic TrueSTUDIO toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M4 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); - * You may not use this file except in compliance with the License. - * You may obtain a copy of the License at: - * - * http://www.st.com/software_license_agreement_liberty_v2 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - ****************************************************************************** - */ - - .syntax unified - .cpu cortex-m4 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global Default_Handler - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss -/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ - -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - ldr sp, =_estack /* set stack pointer */ - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call static constructors */ - bl __libc_init_array -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - g_pfnVectors: - .word _estack - .word Reset_Handler - - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word CAN1_TX_IRQHandler /* CAN1 TX */ - .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ - .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ - .word CAN1_SCE_IRQHandler /* CAN1 SCE */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FMC_IRQHandler /* FMC */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word ETH_IRQHandler /* Ethernet */ - .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */ - .word CAN2_TX_IRQHandler /* CAN2 TX */ - .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ - .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ - .word CAN2_SCE_IRQHandler /* CAN2 SCE */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ - .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ - .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ - .word OTG_HS_IRQHandler /* USB OTG HS */ - .word DCMI_IRQHandler /* DCMI */ - .word CRYP_IRQHandler /* CRYP crypto */ - .word HASH_RNG_IRQHandler /* Hash and Rng */ - .word FPU_IRQHandler /* FPU */ - .word UART7_IRQHandler /* UART7 */ - .word UART8_IRQHandler /* UART8 */ - .word SPI4_IRQHandler /* SPI4 */ - .word SPI5_IRQHandler /* SPI5 */ - .word SPI6_IRQHandler /* SPI6 */ - .word SAI1_IRQHandler /* SAI1 */ - .word LTDC_IRQHandler /* LTDC */ - .word LTDC_ER_IRQHandler /* LTDC error */ - .word DMA2D_IRQHandler /* DMA2D */ - .word QUADSPI_IRQHandler /* QUADSPI */ - .word DSI_IRQHandler /* DSI */ - - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FMC_IRQHandler - .thumb_set FMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak ETH_IRQHandler - .thumb_set ETH_IRQHandler,Default_Handler - - .weak ETH_WKUP_IRQHandler - .thumb_set ETH_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_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_OUT_IRQHandler - .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_IN_IRQHandler - .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler - - .weak OTG_HS_WKUP_IRQHandler - .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler - - .weak OTG_HS_IRQHandler - .thumb_set OTG_HS_IRQHandler,Default_Handler - - .weak DCMI_IRQHandler - .thumb_set DCMI_IRQHandler,Default_Handler - - .weak CRYP_IRQHandler - .thumb_set CRYP_IRQHandler,Default_Handler - - .weak HASH_RNG_IRQHandler - .thumb_set HASH_RNG_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak UART7_IRQHandler - .thumb_set UART7_IRQHandler,Default_Handler - - .weak UART8_IRQHandler - .thumb_set UART8_IRQHandler,Default_Handler - - .weak SPI4_IRQHandler - .thumb_set SPI4_IRQHandler,Default_Handler - - .weak SPI5_IRQHandler - .thumb_set SPI5_IRQHandler,Default_Handler - - .weak SPI6_IRQHandler - .thumb_set SPI6_IRQHandler,Default_Handler - - .weak SAI1_IRQHandler - .thumb_set SAI1_IRQHandler,Default_Handler - - .weak LTDC_IRQHandler - .thumb_set LTDC_IRQHandler,Default_Handler - - .weak LTDC_ER_IRQHandler - .thumb_set LTDC_ER_IRQHandler,Default_Handler - - .weak DMA2D_IRQHandler - .thumb_set DMA2D_IRQHandler,Default_Handler - - .weak QUADSPI_IRQHandler - .thumb_set QUADSPI_IRQHandler,Default_Handler - - .weak DSI_IRQHandler - .thumb_set DSI_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ - - - - - - - diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f401xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f401xx.s deleted file mode 100644 index 99b0b5b5b7..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f401xx.s +++ /dev/null @@ -1,384 +0,0 @@ -;******************** (C) COPYRIGHT 2015 STMicroelectronics ******************** -;* File Name : startup_stm32f401xx.s -;* Author : MCD Application Team -;* @version : V1.6.1 -;* @date : 21-October-2015 -;* Description : STM32F401xx devices vector table for MDK-ARM 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 system clock -;* - Branches to __main in the C library (which eventually -;* calls main()). -;* After Reset the CortexM4 processor is in Thread mode, -;* priority is Privileged, and the Stack is set to Main. -;* <<< Use Configuration Wizard in Context Menu >>> -;******************************************************************************* -; -; Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); -; You may not use this file except in compliance with the License. -; You may obtain a copy of the License at: -; -; http://www.st.com/software_license_agreement_liberty_v2 -; -; Unless required by applicable law or agreed to in writing, software -; distributed under the License is distributed on an "AS IS" BASIS, -; WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -; See the License for the specific language governing permissions and -; limitations under the License. -; -;******************************************************************************* - -; Amount of memory (in bytes) allocated for Stack -; Tailor this value to your application needs -; Stack Configuration -; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> -; - -Stack_Size EQU 0x00000400 - - AREA STACK, NOINIT, READWRITE, ALIGN=3 -Stack_Mem SPACE Stack_Size -__initial_sp - - -; Heap Configuration -; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> -; - -Heap_Size EQU 0x00000200 - - AREA HEAP, NOINIT, READWRITE, ALIGN=3 -__heap_base -Heap_Mem SPACE Heap_Size -__heap_limit - - PRESERVE8 - THUMB - - -; Vector Table Mapped to Address 0 at Reset - AREA RESET, DATA, READONLY - EXPORT __Vectors - EXPORT __Vectors_End - EXPORT __Vectors_Size - -__Vectors DCD __initial_sp ; Top of Stack - DCD Reset_Handler ; Reset Handler - DCD NMI_Handler ; NMI Handler - DCD HardFault_Handler ; Hard Fault Handler - DCD MemManage_Handler ; MPU Fault Handler - DCD BusFault_Handler ; Bus Fault Handler - DCD UsageFault_Handler ; Usage Fault Handler - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SVC_Handler ; SVCall Handler - DCD DebugMon_Handler ; Debug Monitor Handler - DCD 0 ; Reserved - DCD PendSV_Handler ; PendSV Handler - DCD SysTick_Handler ; SysTick Handler - - ; External Interrupts - DCD WWDG_IRQHandler ; Window WatchDog - DCD PVD_IRQHandler ; PVD through EXTI Line detection - DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line - DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line - DCD FLASH_IRQHandler ; FLASH - DCD RCC_IRQHandler ; RCC - DCD EXTI0_IRQHandler ; EXTI Line0 - DCD EXTI1_IRQHandler ; EXTI Line1 - DCD EXTI2_IRQHandler ; EXTI Line2 - DCD EXTI3_IRQHandler ; EXTI Line3 - DCD EXTI4_IRQHandler ; EXTI Line4 - DCD DMA1_Stream0_IRQHandler ; DMA1 Stream 0 - DCD DMA1_Stream1_IRQHandler ; DMA1 Stream 1 - DCD DMA1_Stream2_IRQHandler ; DMA1 Stream 2 - DCD DMA1_Stream3_IRQHandler ; DMA1 Stream 3 - DCD DMA1_Stream4_IRQHandler ; DMA1 Stream 4 - DCD DMA1_Stream5_IRQHandler ; DMA1 Stream 5 - DCD DMA1_Stream6_IRQHandler ; DMA1 Stream 6 - DCD ADC_IRQHandler ; ADC1 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD EXTI9_5_IRQHandler ; External Line[9:5]s - DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 - DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 - DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 - DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare - DCD TIM2_IRQHandler ; TIM2 - DCD TIM3_IRQHandler ; TIM3 - DCD TIM4_IRQHandler ; TIM4 - DCD I2C1_EV_IRQHandler ; I2C1 Event - DCD I2C1_ER_IRQHandler ; I2C1 Error - DCD I2C2_EV_IRQHandler ; I2C2 Event - DCD I2C2_ER_IRQHandler ; I2C2 Error - DCD SPI1_IRQHandler ; SPI1 - DCD SPI2_IRQHandler ; SPI2 - DCD USART1_IRQHandler ; USART1 - DCD USART2_IRQHandler ; USART2 - DCD 0 ; Reserved - DCD EXTI15_10_IRQHandler ; External Line[15:10]s - DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line - DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD DMA1_Stream7_IRQHandler ; DMA1 Stream7 - DCD 0 ; Reserved - DCD SDIO_IRQHandler ; SDIO - DCD TIM5_IRQHandler ; TIM5 - DCD SPI3_IRQHandler ; SPI3 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD DMA2_Stream0_IRQHandler ; DMA2 Stream 0 - DCD DMA2_Stream1_IRQHandler ; DMA2 Stream 1 - DCD DMA2_Stream2_IRQHandler ; DMA2 Stream 2 - DCD DMA2_Stream3_IRQHandler ; DMA2 Stream 3 - DCD DMA2_Stream4_IRQHandler ; DMA2 Stream 4 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD OTG_FS_IRQHandler ; USB OTG FS - DCD DMA2_Stream5_IRQHandler ; DMA2 Stream 5 - DCD DMA2_Stream6_IRQHandler ; DMA2 Stream 6 - DCD DMA2_Stream7_IRQHandler ; DMA2 Stream 7 - DCD USART6_IRQHandler ; USART6 - DCD I2C3_EV_IRQHandler ; I2C3 event - DCD I2C3_ER_IRQHandler ; I2C3 error - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD FPU_IRQHandler ; FPU - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SPI4_IRQHandler ; SPI4 - -__Vectors_End - -__Vectors_Size EQU __Vectors_End - __Vectors - - AREA |.text|, CODE, READONLY - -; Reset handler -Reset_Handler PROC - EXPORT Reset_Handler [WEAK] - IMPORT SystemInit - IMPORT __main - - LDR R0, =SystemInit - BLX R0 - LDR R0, =__main - BX R0 - ENDP - -; Dummy Exception Handlers (infinite loops which can be modified) - -NMI_Handler PROC - EXPORT NMI_Handler [WEAK] - B . - ENDP -HardFault_Handler\ - PROC - EXPORT HardFault_Handler [WEAK] - B . - ENDP -MemManage_Handler\ - PROC - EXPORT MemManage_Handler [WEAK] - B . - ENDP -BusFault_Handler\ - PROC - EXPORT BusFault_Handler [WEAK] - B . - ENDP -UsageFault_Handler\ - PROC - EXPORT UsageFault_Handler [WEAK] - B . - ENDP -SVC_Handler PROC - EXPORT SVC_Handler [WEAK] - B . - ENDP -DebugMon_Handler\ - PROC - EXPORT DebugMon_Handler [WEAK] - B . - ENDP -PendSV_Handler PROC - EXPORT PendSV_Handler [WEAK] - B . - ENDP -SysTick_Handler PROC - EXPORT SysTick_Handler [WEAK] - B . - ENDP - -Default_Handler PROC - - EXPORT WWDG_IRQHandler [WEAK] - EXPORT PVD_IRQHandler [WEAK] - EXPORT TAMP_STAMP_IRQHandler [WEAK] - EXPORT RTC_WKUP_IRQHandler [WEAK] - EXPORT FLASH_IRQHandler [WEAK] - EXPORT RCC_IRQHandler [WEAK] - EXPORT EXTI0_IRQHandler [WEAK] - EXPORT EXTI1_IRQHandler [WEAK] - EXPORT EXTI2_IRQHandler [WEAK] - EXPORT EXTI3_IRQHandler [WEAK] - EXPORT EXTI4_IRQHandler [WEAK] - EXPORT DMA1_Stream0_IRQHandler [WEAK] - EXPORT DMA1_Stream1_IRQHandler [WEAK] - EXPORT DMA1_Stream2_IRQHandler [WEAK] - EXPORT DMA1_Stream3_IRQHandler [WEAK] - EXPORT DMA1_Stream4_IRQHandler [WEAK] - EXPORT DMA1_Stream5_IRQHandler [WEAK] - EXPORT DMA1_Stream6_IRQHandler [WEAK] - EXPORT ADC_IRQHandler [WEAK] - EXPORT EXTI9_5_IRQHandler [WEAK] - EXPORT TIM1_BRK_TIM9_IRQHandler [WEAK] - EXPORT TIM1_UP_TIM10_IRQHandler [WEAK] - EXPORT TIM1_TRG_COM_TIM11_IRQHandler [WEAK] - EXPORT TIM1_CC_IRQHandler [WEAK] - EXPORT TIM2_IRQHandler [WEAK] - EXPORT TIM3_IRQHandler [WEAK] - EXPORT TIM4_IRQHandler [WEAK] - EXPORT I2C1_EV_IRQHandler [WEAK] - EXPORT I2C1_ER_IRQHandler [WEAK] - EXPORT I2C2_EV_IRQHandler [WEAK] - EXPORT I2C2_ER_IRQHandler [WEAK] - EXPORT SPI1_IRQHandler [WEAK] - EXPORT SPI2_IRQHandler [WEAK] - EXPORT USART1_IRQHandler [WEAK] - EXPORT USART2_IRQHandler [WEAK] - EXPORT EXTI15_10_IRQHandler [WEAK] - EXPORT RTC_Alarm_IRQHandler [WEAK] - EXPORT OTG_FS_WKUP_IRQHandler [WEAK] - EXPORT DMA1_Stream7_IRQHandler [WEAK] - EXPORT SDIO_IRQHandler [WEAK] - EXPORT TIM5_IRQHandler [WEAK] - EXPORT SPI3_IRQHandler [WEAK] - EXPORT DMA2_Stream0_IRQHandler [WEAK] - EXPORT DMA2_Stream1_IRQHandler [WEAK] - EXPORT DMA2_Stream2_IRQHandler [WEAK] - EXPORT DMA2_Stream3_IRQHandler [WEAK] - EXPORT DMA2_Stream4_IRQHandler [WEAK] - EXPORT OTG_FS_IRQHandler [WEAK] - EXPORT DMA2_Stream5_IRQHandler [WEAK] - EXPORT DMA2_Stream6_IRQHandler [WEAK] - EXPORT DMA2_Stream7_IRQHandler [WEAK] - EXPORT USART6_IRQHandler [WEAK] - EXPORT I2C3_EV_IRQHandler [WEAK] - EXPORT I2C3_ER_IRQHandler [WEAK] - EXPORT FPU_IRQHandler [WEAK] - EXPORT SPI4_IRQHandler [WEAK] - -WWDG_IRQHandler -PVD_IRQHandler -TAMP_STAMP_IRQHandler -RTC_WKUP_IRQHandler -FLASH_IRQHandler -RCC_IRQHandler -EXTI0_IRQHandler -EXTI1_IRQHandler -EXTI2_IRQHandler -EXTI3_IRQHandler -EXTI4_IRQHandler -DMA1_Stream0_IRQHandler -DMA1_Stream1_IRQHandler -DMA1_Stream2_IRQHandler -DMA1_Stream3_IRQHandler -DMA1_Stream4_IRQHandler -DMA1_Stream5_IRQHandler -DMA1_Stream6_IRQHandler -ADC_IRQHandler -EXTI9_5_IRQHandler -TIM1_BRK_TIM9_IRQHandler -TIM1_UP_TIM10_IRQHandler -TIM1_TRG_COM_TIM11_IRQHandler -TIM1_CC_IRQHandler -TIM2_IRQHandler -TIM3_IRQHandler -TIM4_IRQHandler -I2C1_EV_IRQHandler -I2C1_ER_IRQHandler -I2C2_EV_IRQHandler -I2C2_ER_IRQHandler -SPI1_IRQHandler -SPI2_IRQHandler -USART1_IRQHandler -USART2_IRQHandler -EXTI15_10_IRQHandler -RTC_Alarm_IRQHandler -OTG_FS_WKUP_IRQHandler -DMA1_Stream7_IRQHandler -SDIO_IRQHandler -TIM5_IRQHandler -SPI3_IRQHandler -DMA2_Stream0_IRQHandler -DMA2_Stream1_IRQHandler -DMA2_Stream2_IRQHandler -DMA2_Stream3_IRQHandler -DMA2_Stream4_IRQHandler -ETH_IRQHandler -OTG_FS_IRQHandler -DMA2_Stream5_IRQHandler -DMA2_Stream6_IRQHandler -DMA2_Stream7_IRQHandler -USART6_IRQHandler -I2C3_EV_IRQHandler -I2C3_ER_IRQHandler -FPU_IRQHandler -SPI4_IRQHandler - - B . - - ENDP - - ALIGN - -;******************************************************************************* -; User Stack and Heap initialization -;******************************************************************************* - IF :DEF:__MICROLIB - - EXPORT __initial_sp - EXPORT __heap_base - EXPORT __heap_limit - - ELSE - - IMPORT __use_two_region_memory - EXPORT __user_initial_stackheap - -__user_initial_stackheap - - LDR R0, = Heap_Mem - LDR R1, =(Stack_Mem + Stack_Size) - LDR R2, = (Heap_Mem + Heap_Size) - LDR R3, = Stack_Mem - BX LR - - ALIGN - - ENDIF - - END - -;************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE***** diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f40_41xxx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f40_41xxx.s deleted file mode 100644 index 0189c3a5a6..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f40_41xxx.s +++ /dev/null @@ -1,434 +0,0 @@ -;******************** (C) COPYRIGHT 2015 STMicroelectronics ******************** -;* File Name : startup_stm32f40_41xxx.s -;* Author : MCD Application Team -;* @version : V1.6.1 -;* @date : 21-October-2015 -;* Description : STM32F40xxx/41xxx devices vector table for MDK-ARM 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 system clock and the external SRAM mounted on -;* STM324xG-EVAL board 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 CortexM4 processor is in Thread mode, -;* priority is Privileged, and the Stack is set to Main. -;* <<< Use Configuration Wizard in Context Menu >>> -;******************************************************************************* -; -; Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); -; You may not use this file except in compliance with the License. -; You may obtain a copy of the License at: -; -; http://www.st.com/software_license_agreement_liberty_v2 -; -; Unless required by applicable law or agreed to in writing, software -; distributed under the License is distributed on an "AS IS" BASIS, -; WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -; See the License for the specific language governing permissions and -; limitations under the License. -; -;******************************************************************************* - -; Amount of memory (in bytes) allocated for Stack -; Tailor this value to your application needs -; Stack Configuration -; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> -; - -Stack_Size EQU 0x00000400 - - AREA STACK, NOINIT, READWRITE, ALIGN=3 -Stack_Mem SPACE Stack_Size -__initial_sp - - -; Heap Configuration -; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> -; - -Heap_Size EQU 0x00000200 - - AREA HEAP, NOINIT, READWRITE, ALIGN=3 -__heap_base -Heap_Mem SPACE Heap_Size -__heap_limit - - PRESERVE8 - THUMB - - -; Vector Table Mapped to Address 0 at Reset - AREA RESET, DATA, READONLY - EXPORT __Vectors - EXPORT __Vectors_End - EXPORT __Vectors_Size - -__Vectors DCD __initial_sp ; Top of Stack - DCD Reset_Handler ; Reset Handler - DCD NMI_Handler ; NMI Handler - DCD HardFault_Handler ; Hard Fault Handler - DCD MemManage_Handler ; MPU Fault Handler - DCD BusFault_Handler ; Bus Fault Handler - DCD UsageFault_Handler ; Usage Fault Handler - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SVC_Handler ; SVCall Handler - DCD DebugMon_Handler ; Debug Monitor Handler - DCD 0 ; Reserved - DCD PendSV_Handler ; PendSV Handler - DCD SysTick_Handler ; SysTick Handler - - ; External Interrupts - DCD WWDG_IRQHandler ; Window WatchDog - DCD PVD_IRQHandler ; PVD through EXTI Line detection - DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line - DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line - DCD FLASH_IRQHandler ; FLASH - DCD RCC_IRQHandler ; RCC - DCD EXTI0_IRQHandler ; EXTI Line0 - DCD EXTI1_IRQHandler ; EXTI Line1 - DCD EXTI2_IRQHandler ; EXTI Line2 - DCD EXTI3_IRQHandler ; EXTI Line3 - DCD EXTI4_IRQHandler ; EXTI Line4 - DCD DMA1_Stream0_IRQHandler ; DMA1 Stream 0 - DCD DMA1_Stream1_IRQHandler ; DMA1 Stream 1 - DCD DMA1_Stream2_IRQHandler ; DMA1 Stream 2 - DCD DMA1_Stream3_IRQHandler ; DMA1 Stream 3 - DCD DMA1_Stream4_IRQHandler ; DMA1 Stream 4 - DCD DMA1_Stream5_IRQHandler ; DMA1 Stream 5 - DCD DMA1_Stream6_IRQHandler ; DMA1 Stream 6 - DCD ADC_IRQHandler ; ADC1, ADC2 and ADC3s - DCD CAN1_TX_IRQHandler ; CAN1 TX - DCD CAN1_RX0_IRQHandler ; CAN1 RX0 - DCD CAN1_RX1_IRQHandler ; CAN1 RX1 - DCD CAN1_SCE_IRQHandler ; CAN1 SCE - DCD EXTI9_5_IRQHandler ; External Line[9:5]s - DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 - DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 - DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 - DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare - DCD TIM2_IRQHandler ; TIM2 - DCD TIM3_IRQHandler ; TIM3 - DCD TIM4_IRQHandler ; TIM4 - DCD I2C1_EV_IRQHandler ; I2C1 Event - DCD I2C1_ER_IRQHandler ; I2C1 Error - DCD I2C2_EV_IRQHandler ; I2C2 Event - DCD I2C2_ER_IRQHandler ; I2C2 Error - DCD SPI1_IRQHandler ; SPI1 - DCD SPI2_IRQHandler ; SPI2 - DCD USART1_IRQHandler ; USART1 - DCD USART2_IRQHandler ; USART2 - DCD USART3_IRQHandler ; USART3 - DCD EXTI15_10_IRQHandler ; External Line[15:10]s - DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line - DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line - DCD TIM8_BRK_TIM12_IRQHandler ; TIM8 Break and TIM12 - DCD TIM8_UP_TIM13_IRQHandler ; TIM8 Update and TIM13 - DCD TIM8_TRG_COM_TIM14_IRQHandler ; TIM8 Trigger and Commutation and TIM14 - DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare - DCD DMA1_Stream7_IRQHandler ; DMA1 Stream7 - DCD FSMC_IRQHandler ; FSMC - DCD SDIO_IRQHandler ; SDIO - DCD TIM5_IRQHandler ; TIM5 - DCD SPI3_IRQHandler ; SPI3 - DCD UART4_IRQHandler ; UART4 - DCD UART5_IRQHandler ; UART5 - DCD TIM6_DAC_IRQHandler ; TIM6 and DAC1&2 underrun errors - DCD TIM7_IRQHandler ; TIM7 - DCD DMA2_Stream0_IRQHandler ; DMA2 Stream 0 - DCD DMA2_Stream1_IRQHandler ; DMA2 Stream 1 - DCD DMA2_Stream2_IRQHandler ; DMA2 Stream 2 - DCD DMA2_Stream3_IRQHandler ; DMA2 Stream 3 - DCD DMA2_Stream4_IRQHandler ; DMA2 Stream 4 - DCD ETH_IRQHandler ; Ethernet - DCD ETH_WKUP_IRQHandler ; Ethernet Wakeup through EXTI line - DCD CAN2_TX_IRQHandler ; CAN2 TX - DCD CAN2_RX0_IRQHandler ; CAN2 RX0 - DCD CAN2_RX1_IRQHandler ; CAN2 RX1 - DCD CAN2_SCE_IRQHandler ; CAN2 SCE - DCD OTG_FS_IRQHandler ; USB OTG FS - DCD DMA2_Stream5_IRQHandler ; DMA2 Stream 5 - DCD DMA2_Stream6_IRQHandler ; DMA2 Stream 6 - DCD DMA2_Stream7_IRQHandler ; DMA2 Stream 7 - DCD USART6_IRQHandler ; USART6 - DCD I2C3_EV_IRQHandler ; I2C3 event - DCD I2C3_ER_IRQHandler ; I2C3 error - DCD OTG_HS_EP1_OUT_IRQHandler ; USB OTG HS End Point 1 Out - DCD OTG_HS_EP1_IN_IRQHandler ; USB OTG HS End Point 1 In - DCD OTG_HS_WKUP_IRQHandler ; USB OTG HS Wakeup through EXTI - DCD OTG_HS_IRQHandler ; USB OTG HS - DCD DCMI_IRQHandler ; DCMI - DCD CRYP_IRQHandler ; CRYP crypto - DCD HASH_RNG_IRQHandler ; Hash and Rng - DCD FPU_IRQHandler ; FPU - -__Vectors_End - -__Vectors_Size EQU __Vectors_End - __Vectors - - AREA |.text|, CODE, READONLY - -; Reset handler -Reset_Handler PROC - EXPORT Reset_Handler [WEAK] - IMPORT SystemInit - IMPORT __main - - LDR R0, =SystemInit - BLX R0 - LDR R0, =__main - BX R0 - ENDP - -; Dummy Exception Handlers (infinite loops which can be modified) - -NMI_Handler PROC - EXPORT NMI_Handler [WEAK] - B . - ENDP -HardFault_Handler\ - PROC - EXPORT HardFault_Handler [WEAK] - B . - ENDP -MemManage_Handler\ - PROC - EXPORT MemManage_Handler [WEAK] - B . - ENDP -BusFault_Handler\ - PROC - EXPORT BusFault_Handler [WEAK] - B . - ENDP -UsageFault_Handler\ - PROC - EXPORT UsageFault_Handler [WEAK] - B . - ENDP -SVC_Handler PROC - EXPORT SVC_Handler [WEAK] - B . - ENDP -DebugMon_Handler\ - PROC - EXPORT DebugMon_Handler [WEAK] - B . - ENDP -PendSV_Handler PROC - EXPORT PendSV_Handler [WEAK] - B . - ENDP -SysTick_Handler PROC - EXPORT SysTick_Handler [WEAK] - B . - ENDP - -Default_Handler PROC - - EXPORT WWDG_IRQHandler [WEAK] - EXPORT PVD_IRQHandler [WEAK] - EXPORT TAMP_STAMP_IRQHandler [WEAK] - EXPORT RTC_WKUP_IRQHandler [WEAK] - EXPORT FLASH_IRQHandler [WEAK] - EXPORT RCC_IRQHandler [WEAK] - EXPORT EXTI0_IRQHandler [WEAK] - EXPORT EXTI1_IRQHandler [WEAK] - EXPORT EXTI2_IRQHandler [WEAK] - EXPORT EXTI3_IRQHandler [WEAK] - EXPORT EXTI4_IRQHandler [WEAK] - EXPORT DMA1_Stream0_IRQHandler [WEAK] - EXPORT DMA1_Stream1_IRQHandler [WEAK] - EXPORT DMA1_Stream2_IRQHandler [WEAK] - EXPORT DMA1_Stream3_IRQHandler [WEAK] - EXPORT DMA1_Stream4_IRQHandler [WEAK] - EXPORT DMA1_Stream5_IRQHandler [WEAK] - EXPORT DMA1_Stream6_IRQHandler [WEAK] - EXPORT ADC_IRQHandler [WEAK] - EXPORT CAN1_TX_IRQHandler [WEAK] - EXPORT CAN1_RX0_IRQHandler [WEAK] - EXPORT CAN1_RX1_IRQHandler [WEAK] - EXPORT CAN1_SCE_IRQHandler [WEAK] - EXPORT EXTI9_5_IRQHandler [WEAK] - EXPORT TIM1_BRK_TIM9_IRQHandler [WEAK] - EXPORT TIM1_UP_TIM10_IRQHandler [WEAK] - EXPORT TIM1_TRG_COM_TIM11_IRQHandler [WEAK] - EXPORT TIM1_CC_IRQHandler [WEAK] - EXPORT TIM2_IRQHandler [WEAK] - EXPORT TIM3_IRQHandler [WEAK] - EXPORT TIM4_IRQHandler [WEAK] - EXPORT I2C1_EV_IRQHandler [WEAK] - EXPORT I2C1_ER_IRQHandler [WEAK] - EXPORT I2C2_EV_IRQHandler [WEAK] - EXPORT I2C2_ER_IRQHandler [WEAK] - EXPORT SPI1_IRQHandler [WEAK] - EXPORT SPI2_IRQHandler [WEAK] - EXPORT USART1_IRQHandler [WEAK] - EXPORT USART2_IRQHandler [WEAK] - EXPORT USART3_IRQHandler [WEAK] - EXPORT EXTI15_10_IRQHandler [WEAK] - EXPORT RTC_Alarm_IRQHandler [WEAK] - EXPORT OTG_FS_WKUP_IRQHandler [WEAK] - EXPORT TIM8_BRK_TIM12_IRQHandler [WEAK] - EXPORT TIM8_UP_TIM13_IRQHandler [WEAK] - EXPORT TIM8_TRG_COM_TIM14_IRQHandler [WEAK] - EXPORT TIM8_CC_IRQHandler [WEAK] - EXPORT DMA1_Stream7_IRQHandler [WEAK] - EXPORT FSMC_IRQHandler [WEAK] - EXPORT SDIO_IRQHandler [WEAK] - EXPORT TIM5_IRQHandler [WEAK] - EXPORT SPI3_IRQHandler [WEAK] - EXPORT UART4_IRQHandler [WEAK] - EXPORT UART5_IRQHandler [WEAK] - EXPORT TIM6_DAC_IRQHandler [WEAK] - EXPORT TIM7_IRQHandler [WEAK] - EXPORT DMA2_Stream0_IRQHandler [WEAK] - EXPORT DMA2_Stream1_IRQHandler [WEAK] - EXPORT DMA2_Stream2_IRQHandler [WEAK] - EXPORT DMA2_Stream3_IRQHandler [WEAK] - EXPORT DMA2_Stream4_IRQHandler [WEAK] - EXPORT ETH_IRQHandler [WEAK] - EXPORT ETH_WKUP_IRQHandler [WEAK] - EXPORT CAN2_TX_IRQHandler [WEAK] - EXPORT CAN2_RX0_IRQHandler [WEAK] - EXPORT CAN2_RX1_IRQHandler [WEAK] - EXPORT CAN2_SCE_IRQHandler [WEAK] - EXPORT OTG_FS_IRQHandler [WEAK] - EXPORT DMA2_Stream5_IRQHandler [WEAK] - EXPORT DMA2_Stream6_IRQHandler [WEAK] - EXPORT DMA2_Stream7_IRQHandler [WEAK] - EXPORT USART6_IRQHandler [WEAK] - EXPORT I2C3_EV_IRQHandler [WEAK] - EXPORT I2C3_ER_IRQHandler [WEAK] - EXPORT OTG_HS_EP1_OUT_IRQHandler [WEAK] - EXPORT OTG_HS_EP1_IN_IRQHandler [WEAK] - EXPORT OTG_HS_WKUP_IRQHandler [WEAK] - EXPORT OTG_HS_IRQHandler [WEAK] - EXPORT DCMI_IRQHandler [WEAK] - EXPORT CRYP_IRQHandler [WEAK] - EXPORT HASH_RNG_IRQHandler [WEAK] - EXPORT FPU_IRQHandler [WEAK] - -WWDG_IRQHandler -PVD_IRQHandler -TAMP_STAMP_IRQHandler -RTC_WKUP_IRQHandler -FLASH_IRQHandler -RCC_IRQHandler -EXTI0_IRQHandler -EXTI1_IRQHandler -EXTI2_IRQHandler -EXTI3_IRQHandler -EXTI4_IRQHandler -DMA1_Stream0_IRQHandler -DMA1_Stream1_IRQHandler -DMA1_Stream2_IRQHandler -DMA1_Stream3_IRQHandler -DMA1_Stream4_IRQHandler -DMA1_Stream5_IRQHandler -DMA1_Stream6_IRQHandler -ADC_IRQHandler -CAN1_TX_IRQHandler -CAN1_RX0_IRQHandler -CAN1_RX1_IRQHandler -CAN1_SCE_IRQHandler -EXTI9_5_IRQHandler -TIM1_BRK_TIM9_IRQHandler -TIM1_UP_TIM10_IRQHandler -TIM1_TRG_COM_TIM11_IRQHandler -TIM1_CC_IRQHandler -TIM2_IRQHandler -TIM3_IRQHandler -TIM4_IRQHandler -I2C1_EV_IRQHandler -I2C1_ER_IRQHandler -I2C2_EV_IRQHandler -I2C2_ER_IRQHandler -SPI1_IRQHandler -SPI2_IRQHandler -USART1_IRQHandler -USART2_IRQHandler -USART3_IRQHandler -EXTI15_10_IRQHandler -RTC_Alarm_IRQHandler -OTG_FS_WKUP_IRQHandler -TIM8_BRK_TIM12_IRQHandler -TIM8_UP_TIM13_IRQHandler -TIM8_TRG_COM_TIM14_IRQHandler -TIM8_CC_IRQHandler -DMA1_Stream7_IRQHandler -FSMC_IRQHandler -SDIO_IRQHandler -TIM5_IRQHandler -SPI3_IRQHandler -UART4_IRQHandler -UART5_IRQHandler -TIM6_DAC_IRQHandler -TIM7_IRQHandler -DMA2_Stream0_IRQHandler -DMA2_Stream1_IRQHandler -DMA2_Stream2_IRQHandler -DMA2_Stream3_IRQHandler -DMA2_Stream4_IRQHandler -ETH_IRQHandler -ETH_WKUP_IRQHandler -CAN2_TX_IRQHandler -CAN2_RX0_IRQHandler -CAN2_RX1_IRQHandler -CAN2_SCE_IRQHandler -OTG_FS_IRQHandler -DMA2_Stream5_IRQHandler -DMA2_Stream6_IRQHandler -DMA2_Stream7_IRQHandler -USART6_IRQHandler -I2C3_EV_IRQHandler -I2C3_ER_IRQHandler -OTG_HS_EP1_OUT_IRQHandler -OTG_HS_EP1_IN_IRQHandler -OTG_HS_WKUP_IRQHandler -OTG_HS_IRQHandler -DCMI_IRQHandler -CRYP_IRQHandler -HASH_RNG_IRQHandler -FPU_IRQHandler - - B . - - ENDP - - ALIGN - -;******************************************************************************* -; User Stack and Heap initialization -;******************************************************************************* - IF :DEF:__MICROLIB - - EXPORT __initial_sp - EXPORT __heap_base - EXPORT __heap_limit - - ELSE - - IMPORT __use_two_region_memory - EXPORT __user_initial_stackheap - -__user_initial_stackheap - - LDR R0, = Heap_Mem - LDR R1, =(Stack_Mem + Stack_Size) - LDR R2, = (Heap_Mem + Heap_Size) - LDR R3, = Stack_Mem - BX LR - - ALIGN - - ENDIF - - END - -;************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE***** diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f40xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f40xx.s deleted file mode 100644 index fb88bb2f80..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f40xx.s +++ /dev/null @@ -1,435 +0,0 @@ -;******************** (C) COPYRIGHT 2015 STMicroelectronics ******************** -;* File Name : startup_stm32f40xx.s -;* Author : MCD Application Team -;* @version : V1.6.1 -;* @date : 21-October-2015 -;* Description : STM32F40xxx/41xxx devices vector table for MDK-ARM toolchain. -;* Same as startup_stm32f40_41xxx.s and maintained for legacy purpose -;* 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 system clock and the external SRAM mounted on -;* STM324xG-EVAL board 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 CortexM4 processor is in Thread mode, -;* priority is Privileged, and the Stack is set to Main. -;* <<< Use Configuration Wizard in Context Menu >>> -;******************************************************************************* -; -; Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); -; You may not use this file except in compliance with the License. -; You may obtain a copy of the License at: -; -; http://www.st.com/software_license_agreement_liberty_v2 -; -; Unless required by applicable law or agreed to in writing, software -; distributed under the License is distributed on an "AS IS" BASIS, -; WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -; See the License for the specific language governing permissions and -; limitations under the License. -; -;******************************************************************************* - -; Amount of memory (in bytes) allocated for Stack -; Tailor this value to your application needs -; Stack Configuration -; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> -; - -Stack_Size EQU 0x00000400 - - AREA STACK, NOINIT, READWRITE, ALIGN=3 -Stack_Mem SPACE Stack_Size -__initial_sp - - -; Heap Configuration -; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> -; - -Heap_Size EQU 0x00000200 - - AREA HEAP, NOINIT, READWRITE, ALIGN=3 -__heap_base -Heap_Mem SPACE Heap_Size -__heap_limit - - PRESERVE8 - THUMB - - -; Vector Table Mapped to Address 0 at Reset - AREA RESET, DATA, READONLY - EXPORT __Vectors - EXPORT __Vectors_End - EXPORT __Vectors_Size - -__Vectors DCD __initial_sp ; Top of Stack - DCD Reset_Handler ; Reset Handler - DCD NMI_Handler ; NMI Handler - DCD HardFault_Handler ; Hard Fault Handler - DCD MemManage_Handler ; MPU Fault Handler - DCD BusFault_Handler ; Bus Fault Handler - DCD UsageFault_Handler ; Usage Fault Handler - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SVC_Handler ; SVCall Handler - DCD DebugMon_Handler ; Debug Monitor Handler - DCD 0 ; Reserved - DCD PendSV_Handler ; PendSV Handler - DCD SysTick_Handler ; SysTick Handler - - ; External Interrupts - DCD WWDG_IRQHandler ; Window WatchDog - DCD PVD_IRQHandler ; PVD through EXTI Line detection - DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line - DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line - DCD FLASH_IRQHandler ; FLASH - DCD RCC_IRQHandler ; RCC - DCD EXTI0_IRQHandler ; EXTI Line0 - DCD EXTI1_IRQHandler ; EXTI Line1 - DCD EXTI2_IRQHandler ; EXTI Line2 - DCD EXTI3_IRQHandler ; EXTI Line3 - DCD EXTI4_IRQHandler ; EXTI Line4 - DCD DMA1_Stream0_IRQHandler ; DMA1 Stream 0 - DCD DMA1_Stream1_IRQHandler ; DMA1 Stream 1 - DCD DMA1_Stream2_IRQHandler ; DMA1 Stream 2 - DCD DMA1_Stream3_IRQHandler ; DMA1 Stream 3 - DCD DMA1_Stream4_IRQHandler ; DMA1 Stream 4 - DCD DMA1_Stream5_IRQHandler ; DMA1 Stream 5 - DCD DMA1_Stream6_IRQHandler ; DMA1 Stream 6 - DCD ADC_IRQHandler ; ADC1, ADC2 and ADC3s - DCD CAN1_TX_IRQHandler ; CAN1 TX - DCD CAN1_RX0_IRQHandler ; CAN1 RX0 - DCD CAN1_RX1_IRQHandler ; CAN1 RX1 - DCD CAN1_SCE_IRQHandler ; CAN1 SCE - DCD EXTI9_5_IRQHandler ; External Line[9:5]s - DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 - DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 - DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 - DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare - DCD TIM2_IRQHandler ; TIM2 - DCD TIM3_IRQHandler ; TIM3 - DCD TIM4_IRQHandler ; TIM4 - DCD I2C1_EV_IRQHandler ; I2C1 Event - DCD I2C1_ER_IRQHandler ; I2C1 Error - DCD I2C2_EV_IRQHandler ; I2C2 Event - DCD I2C2_ER_IRQHandler ; I2C2 Error - DCD SPI1_IRQHandler ; SPI1 - DCD SPI2_IRQHandler ; SPI2 - DCD USART1_IRQHandler ; USART1 - DCD USART2_IRQHandler ; USART2 - DCD USART3_IRQHandler ; USART3 - DCD EXTI15_10_IRQHandler ; External Line[15:10]s - DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line - DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line - DCD TIM8_BRK_TIM12_IRQHandler ; TIM8 Break and TIM12 - DCD TIM8_UP_TIM13_IRQHandler ; TIM8 Update and TIM13 - DCD TIM8_TRG_COM_TIM14_IRQHandler ; TIM8 Trigger and Commutation and TIM14 - DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare - DCD DMA1_Stream7_IRQHandler ; DMA1 Stream7 - DCD FSMC_IRQHandler ; FSMC - DCD SDIO_IRQHandler ; SDIO - DCD TIM5_IRQHandler ; TIM5 - DCD SPI3_IRQHandler ; SPI3 - DCD UART4_IRQHandler ; UART4 - DCD UART5_IRQHandler ; UART5 - DCD TIM6_DAC_IRQHandler ; TIM6 and DAC1&2 underrun errors - DCD TIM7_IRQHandler ; TIM7 - DCD DMA2_Stream0_IRQHandler ; DMA2 Stream 0 - DCD DMA2_Stream1_IRQHandler ; DMA2 Stream 1 - DCD DMA2_Stream2_IRQHandler ; DMA2 Stream 2 - DCD DMA2_Stream3_IRQHandler ; DMA2 Stream 3 - DCD DMA2_Stream4_IRQHandler ; DMA2 Stream 4 - DCD ETH_IRQHandler ; Ethernet - DCD ETH_WKUP_IRQHandler ; Ethernet Wakeup through EXTI line - DCD CAN2_TX_IRQHandler ; CAN2 TX - DCD CAN2_RX0_IRQHandler ; CAN2 RX0 - DCD CAN2_RX1_IRQHandler ; CAN2 RX1 - DCD CAN2_SCE_IRQHandler ; CAN2 SCE - DCD OTG_FS_IRQHandler ; USB OTG FS - DCD DMA2_Stream5_IRQHandler ; DMA2 Stream 5 - DCD DMA2_Stream6_IRQHandler ; DMA2 Stream 6 - DCD DMA2_Stream7_IRQHandler ; DMA2 Stream 7 - DCD USART6_IRQHandler ; USART6 - DCD I2C3_EV_IRQHandler ; I2C3 event - DCD I2C3_ER_IRQHandler ; I2C3 error - DCD OTG_HS_EP1_OUT_IRQHandler ; USB OTG HS End Point 1 Out - DCD OTG_HS_EP1_IN_IRQHandler ; USB OTG HS End Point 1 In - DCD OTG_HS_WKUP_IRQHandler ; USB OTG HS Wakeup through EXTI - DCD OTG_HS_IRQHandler ; USB OTG HS - DCD DCMI_IRQHandler ; DCMI - DCD CRYP_IRQHandler ; CRYP crypto - DCD HASH_RNG_IRQHandler ; Hash and Rng - DCD FPU_IRQHandler ; FPU - -__Vectors_End - -__Vectors_Size EQU __Vectors_End - __Vectors - - AREA |.text|, CODE, READONLY - -; Reset handler -Reset_Handler PROC - EXPORT Reset_Handler [WEAK] - IMPORT SystemInit - IMPORT __main - - LDR R0, =SystemInit - BLX R0 - LDR R0, =__main - BX R0 - ENDP - -; Dummy Exception Handlers (infinite loops which can be modified) - -NMI_Handler PROC - EXPORT NMI_Handler [WEAK] - B . - ENDP -HardFault_Handler\ - PROC - EXPORT HardFault_Handler [WEAK] - B . - ENDP -MemManage_Handler\ - PROC - EXPORT MemManage_Handler [WEAK] - B . - ENDP -BusFault_Handler\ - PROC - EXPORT BusFault_Handler [WEAK] - B . - ENDP -UsageFault_Handler\ - PROC - EXPORT UsageFault_Handler [WEAK] - B . - ENDP -SVC_Handler PROC - EXPORT SVC_Handler [WEAK] - B . - ENDP -DebugMon_Handler\ - PROC - EXPORT DebugMon_Handler [WEAK] - B . - ENDP -PendSV_Handler PROC - EXPORT PendSV_Handler [WEAK] - B . - ENDP -SysTick_Handler PROC - EXPORT SysTick_Handler [WEAK] - B . - ENDP - -Default_Handler PROC - - EXPORT WWDG_IRQHandler [WEAK] - EXPORT PVD_IRQHandler [WEAK] - EXPORT TAMP_STAMP_IRQHandler [WEAK] - EXPORT RTC_WKUP_IRQHandler [WEAK] - EXPORT FLASH_IRQHandler [WEAK] - EXPORT RCC_IRQHandler [WEAK] - EXPORT EXTI0_IRQHandler [WEAK] - EXPORT EXTI1_IRQHandler [WEAK] - EXPORT EXTI2_IRQHandler [WEAK] - EXPORT EXTI3_IRQHandler [WEAK] - EXPORT EXTI4_IRQHandler [WEAK] - EXPORT DMA1_Stream0_IRQHandler [WEAK] - EXPORT DMA1_Stream1_IRQHandler [WEAK] - EXPORT DMA1_Stream2_IRQHandler [WEAK] - EXPORT DMA1_Stream3_IRQHandler [WEAK] - EXPORT DMA1_Stream4_IRQHandler [WEAK] - EXPORT DMA1_Stream5_IRQHandler [WEAK] - EXPORT DMA1_Stream6_IRQHandler [WEAK] - EXPORT ADC_IRQHandler [WEAK] - EXPORT CAN1_TX_IRQHandler [WEAK] - EXPORT CAN1_RX0_IRQHandler [WEAK] - EXPORT CAN1_RX1_IRQHandler [WEAK] - EXPORT CAN1_SCE_IRQHandler [WEAK] - EXPORT EXTI9_5_IRQHandler [WEAK] - EXPORT TIM1_BRK_TIM9_IRQHandler [WEAK] - EXPORT TIM1_UP_TIM10_IRQHandler [WEAK] - EXPORT TIM1_TRG_COM_TIM11_IRQHandler [WEAK] - EXPORT TIM1_CC_IRQHandler [WEAK] - EXPORT TIM2_IRQHandler [WEAK] - EXPORT TIM3_IRQHandler [WEAK] - EXPORT TIM4_IRQHandler [WEAK] - EXPORT I2C1_EV_IRQHandler [WEAK] - EXPORT I2C1_ER_IRQHandler [WEAK] - EXPORT I2C2_EV_IRQHandler [WEAK] - EXPORT I2C2_ER_IRQHandler [WEAK] - EXPORT SPI1_IRQHandler [WEAK] - EXPORT SPI2_IRQHandler [WEAK] - EXPORT USART1_IRQHandler [WEAK] - EXPORT USART2_IRQHandler [WEAK] - EXPORT USART3_IRQHandler [WEAK] - EXPORT EXTI15_10_IRQHandler [WEAK] - EXPORT RTC_Alarm_IRQHandler [WEAK] - EXPORT OTG_FS_WKUP_IRQHandler [WEAK] - EXPORT TIM8_BRK_TIM12_IRQHandler [WEAK] - EXPORT TIM8_UP_TIM13_IRQHandler [WEAK] - EXPORT TIM8_TRG_COM_TIM14_IRQHandler [WEAK] - EXPORT TIM8_CC_IRQHandler [WEAK] - EXPORT DMA1_Stream7_IRQHandler [WEAK] - EXPORT FSMC_IRQHandler [WEAK] - EXPORT SDIO_IRQHandler [WEAK] - EXPORT TIM5_IRQHandler [WEAK] - EXPORT SPI3_IRQHandler [WEAK] - EXPORT UART4_IRQHandler [WEAK] - EXPORT UART5_IRQHandler [WEAK] - EXPORT TIM6_DAC_IRQHandler [WEAK] - EXPORT TIM7_IRQHandler [WEAK] - EXPORT DMA2_Stream0_IRQHandler [WEAK] - EXPORT DMA2_Stream1_IRQHandler [WEAK] - EXPORT DMA2_Stream2_IRQHandler [WEAK] - EXPORT DMA2_Stream3_IRQHandler [WEAK] - EXPORT DMA2_Stream4_IRQHandler [WEAK] - EXPORT ETH_IRQHandler [WEAK] - EXPORT ETH_WKUP_IRQHandler [WEAK] - EXPORT CAN2_TX_IRQHandler [WEAK] - EXPORT CAN2_RX0_IRQHandler [WEAK] - EXPORT CAN2_RX1_IRQHandler [WEAK] - EXPORT CAN2_SCE_IRQHandler [WEAK] - EXPORT OTG_FS_IRQHandler [WEAK] - EXPORT DMA2_Stream5_IRQHandler [WEAK] - EXPORT DMA2_Stream6_IRQHandler [WEAK] - EXPORT DMA2_Stream7_IRQHandler [WEAK] - EXPORT USART6_IRQHandler [WEAK] - EXPORT I2C3_EV_IRQHandler [WEAK] - EXPORT I2C3_ER_IRQHandler [WEAK] - EXPORT OTG_HS_EP1_OUT_IRQHandler [WEAK] - EXPORT OTG_HS_EP1_IN_IRQHandler [WEAK] - EXPORT OTG_HS_WKUP_IRQHandler [WEAK] - EXPORT OTG_HS_IRQHandler [WEAK] - EXPORT DCMI_IRQHandler [WEAK] - EXPORT CRYP_IRQHandler [WEAK] - EXPORT HASH_RNG_IRQHandler [WEAK] - EXPORT FPU_IRQHandler [WEAK] - -WWDG_IRQHandler -PVD_IRQHandler -TAMP_STAMP_IRQHandler -RTC_WKUP_IRQHandler -FLASH_IRQHandler -RCC_IRQHandler -EXTI0_IRQHandler -EXTI1_IRQHandler -EXTI2_IRQHandler -EXTI3_IRQHandler -EXTI4_IRQHandler -DMA1_Stream0_IRQHandler -DMA1_Stream1_IRQHandler -DMA1_Stream2_IRQHandler -DMA1_Stream3_IRQHandler -DMA1_Stream4_IRQHandler -DMA1_Stream5_IRQHandler -DMA1_Stream6_IRQHandler -ADC_IRQHandler -CAN1_TX_IRQHandler -CAN1_RX0_IRQHandler -CAN1_RX1_IRQHandler -CAN1_SCE_IRQHandler -EXTI9_5_IRQHandler -TIM1_BRK_TIM9_IRQHandler -TIM1_UP_TIM10_IRQHandler -TIM1_TRG_COM_TIM11_IRQHandler -TIM1_CC_IRQHandler -TIM2_IRQHandler -TIM3_IRQHandler -TIM4_IRQHandler -I2C1_EV_IRQHandler -I2C1_ER_IRQHandler -I2C2_EV_IRQHandler -I2C2_ER_IRQHandler -SPI1_IRQHandler -SPI2_IRQHandler -USART1_IRQHandler -USART2_IRQHandler -USART3_IRQHandler -EXTI15_10_IRQHandler -RTC_Alarm_IRQHandler -OTG_FS_WKUP_IRQHandler -TIM8_BRK_TIM12_IRQHandler -TIM8_UP_TIM13_IRQHandler -TIM8_TRG_COM_TIM14_IRQHandler -TIM8_CC_IRQHandler -DMA1_Stream7_IRQHandler -FSMC_IRQHandler -SDIO_IRQHandler -TIM5_IRQHandler -SPI3_IRQHandler -UART4_IRQHandler -UART5_IRQHandler -TIM6_DAC_IRQHandler -TIM7_IRQHandler -DMA2_Stream0_IRQHandler -DMA2_Stream1_IRQHandler -DMA2_Stream2_IRQHandler -DMA2_Stream3_IRQHandler -DMA2_Stream4_IRQHandler -ETH_IRQHandler -ETH_WKUP_IRQHandler -CAN2_TX_IRQHandler -CAN2_RX0_IRQHandler -CAN2_RX1_IRQHandler -CAN2_SCE_IRQHandler -OTG_FS_IRQHandler -DMA2_Stream5_IRQHandler -DMA2_Stream6_IRQHandler -DMA2_Stream7_IRQHandler -USART6_IRQHandler -I2C3_EV_IRQHandler -I2C3_ER_IRQHandler -OTG_HS_EP1_OUT_IRQHandler -OTG_HS_EP1_IN_IRQHandler -OTG_HS_WKUP_IRQHandler -OTG_HS_IRQHandler -DCMI_IRQHandler -CRYP_IRQHandler -HASH_RNG_IRQHandler -FPU_IRQHandler - - B . - - ENDP - - ALIGN - -;******************************************************************************* -; User Stack and Heap initialization -;******************************************************************************* - IF :DEF:__MICROLIB - - EXPORT __initial_sp - EXPORT __heap_base - EXPORT __heap_limit - - ELSE - - IMPORT __use_two_region_memory - EXPORT __user_initial_stackheap - -__user_initial_stackheap - - LDR R0, = Heap_Mem - LDR R1, =(Stack_Mem + Stack_Size) - LDR R2, = (Heap_Mem + Heap_Size) - LDR R3, = Stack_Mem - BX LR - - ALIGN - - ENDIF - - END - -;************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE***** diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f410xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f410xx.s deleted file mode 100644 index 12fa722025..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f410xx.s +++ /dev/null @@ -1,398 +0,0 @@ -;******************** (C) COPYRIGHT 2015 STMicroelectronics ******************** -;* File Name : startup_stm32f410xx.s -;* Author : MCD Application Team -;* @version : V1.6.1 -;* @date : 21-October-2015 -;* Description : STM32F410xx devices vector table for MDK-ARM toolchain. -;* This module performs: -;* - Set the initial SP -;* - Set the initial PC == Reset_Handler -;* - Set the vector table entries with the exceptions ISR address -;* - Branches to __main in the C library (which eventually -;* calls main()). -;* After Reset the CortexM4 processor is in Thread mode, -;* priority is Privileged, and the Stack is set to Main. -;* <<< Use Configuration Wizard in Context Menu >>> -;******************************************************************************* -; -;* Redistribution and use in source and binary forms, with or without modification, -;* are permitted provided that the following conditions are met: -;* 1. Redistributions of source code must retain the above copyright notice, -;* this list of conditions and the following disclaimer. -;* 2. Redistributions in binary form must reproduce the above copyright notice, -;* this list of conditions and the following disclaimer in the documentation -;* and/or other materials provided with the distribution. -;* 3. Neither the name of STMicroelectronics nor the names of its contributors -;* may be used to endorse or promote products derived from this software -;* without specific prior written permission. -;* -;* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -;* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE -;* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL -;* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -;* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -;* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, -;* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE -;* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -; -;******************************************************************************* - -; Amount of memory (in bytes) allocated for Stack -; Tailor this value to your application needs -; Stack Configuration -; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> -; - -Stack_Size EQU 0x00000400 - - AREA STACK, NOINIT, READWRITE, ALIGN=3 -Stack_Mem SPACE Stack_Size -__initial_sp - - -; Heap Configuration -; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> -; - -Heap_Size EQU 0x00000200 - - AREA HEAP, NOINIT, READWRITE, ALIGN=3 -__heap_base -Heap_Mem SPACE Heap_Size -__heap_limit - - PRESERVE8 - THUMB - - -; Vector Table Mapped to Address 0 at Reset - AREA RESET, DATA, READONLY - EXPORT __Vectors - EXPORT __Vectors_End - EXPORT __Vectors_Size - -__Vectors DCD __initial_sp ; Top of Stack - DCD Reset_Handler ; Reset Handler - DCD NMI_Handler ; NMI Handler - DCD HardFault_Handler ; Hard Fault Handler - DCD MemManage_Handler ; MPU Fault Handler - DCD BusFault_Handler ; Bus Fault Handler - DCD UsageFault_Handler ; Usage Fault Handler - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SVC_Handler ; SVCall Handler - DCD DebugMon_Handler ; Debug Monitor Handler - DCD 0 ; Reserved - DCD PendSV_Handler ; PendSV Handler - DCD SysTick_Handler ; SysTick Handler - - ; External Interrupts - DCD WWDG_IRQHandler ; Window WatchDog - DCD PVD_IRQHandler ; PVD through EXTI Line detection - DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line - DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line - DCD FLASH_IRQHandler ; FLASH - DCD RCC_IRQHandler ; RCC - DCD EXTI0_IRQHandler ; EXTI Line0 - DCD EXTI1_IRQHandler ; EXTI Line1 - DCD EXTI2_IRQHandler ; EXTI Line2 - DCD EXTI3_IRQHandler ; EXTI Line3 - DCD EXTI4_IRQHandler ; EXTI Line4 - DCD DMA1_Stream0_IRQHandler ; DMA1 Stream 0 - DCD DMA1_Stream1_IRQHandler ; DMA1 Stream 1 - DCD DMA1_Stream2_IRQHandler ; DMA1 Stream 2 - DCD DMA1_Stream3_IRQHandler ; DMA1 Stream 3 - DCD DMA1_Stream4_IRQHandler ; DMA1 Stream 4 - DCD DMA1_Stream5_IRQHandler ; DMA1 Stream 5 - DCD DMA1_Stream6_IRQHandler ; DMA1 Stream 6 - DCD ADC_IRQHandler ; ADC1, ADC2 and ADC3s - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD EXTI9_5_IRQHandler ; External Line[9:5]s - DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 - DCD TIM1_UP_IRQHandler ; TIM1 Update - DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 - DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD I2C1_EV_IRQHandler ; I2C1 Event - DCD I2C1_ER_IRQHandler ; I2C1 Error - DCD I2C2_EV_IRQHandler ; I2C2 Event - DCD I2C2_ER_IRQHandler ; I2C2 Error - DCD SPI1_IRQHandler ; SPI1 - DCD SPI2_IRQHandler ; SPI2 - DCD USART1_IRQHandler ; USART1 - DCD USART2_IRQHandler ; USART2 - DCD 0 ; Reserved - DCD EXTI15_10_IRQHandler ; External Line[15:10]s - DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD DMA1_Stream7_IRQHandler ; DMA1 Stream7 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD TIM5_IRQHandler ; TIM5 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD TIM6_DAC_IRQHandler ; TIM6 and DAC - DCD 0 ; Reserved - DCD DMA2_Stream0_IRQHandler ; DMA2 Stream 0 - DCD DMA2_Stream1_IRQHandler ; DMA2 Stream 1 - DCD DMA2_Stream2_IRQHandler ; DMA2 Stream 2 - DCD DMA2_Stream3_IRQHandler ; DMA2 Stream 3 - DCD DMA2_Stream4_IRQHandler ; DMA2 Stream 4 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD DMA2_Stream5_IRQHandler ; DMA2 Stream 5 - DCD DMA2_Stream6_IRQHandler ; DMA2 Stream 6 - DCD DMA2_Stream7_IRQHandler ; DMA2 Stream 7 - DCD USART6_IRQHandler ; USART6 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD RNG_IRQHandler ; RNG - DCD FPU_IRQHandler ; FPU - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SPI5_IRQHandler ; SPI5 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD FMPI2C1_EV_IRQHandler ; FMPI2C1 Event - DCD FMPI2C1_ER_IRQHandler ; FMPI2C1 Error - DCD LPTIM1_IRQHandler ; LP TIM1 - -__Vectors_End - -__Vectors_Size EQU __Vectors_End - __Vectors - - AREA |.text|, CODE, READONLY - -; Reset handler -Reset_Handler PROC - EXPORT Reset_Handler [WEAK] - IMPORT SystemInit - IMPORT __main - - LDR R0, =SystemInit - BLX R0 - LDR R0, =__main - BX R0 - ENDP - -; Dummy Exception Handlers (infinite loops which can be modified) - -NMI_Handler PROC - EXPORT NMI_Handler [WEAK] - B . - ENDP -HardFault_Handler\ - PROC - EXPORT HardFault_Handler [WEAK] - B . - ENDP -MemManage_Handler\ - PROC - EXPORT MemManage_Handler [WEAK] - B . - ENDP -BusFault_Handler\ - PROC - EXPORT BusFault_Handler [WEAK] - B . - ENDP -UsageFault_Handler\ - PROC - EXPORT UsageFault_Handler [WEAK] - B . - ENDP -SVC_Handler PROC - EXPORT SVC_Handler [WEAK] - B . - ENDP -DebugMon_Handler\ - PROC - EXPORT DebugMon_Handler [WEAK] - B . - ENDP -PendSV_Handler PROC - EXPORT PendSV_Handler [WEAK] - B . - ENDP -SysTick_Handler PROC - EXPORT SysTick_Handler [WEAK] - B . - ENDP - -Default_Handler PROC - - EXPORT WWDG_IRQHandler [WEAK] - EXPORT PVD_IRQHandler [WEAK] - EXPORT TAMP_STAMP_IRQHandler [WEAK] - EXPORT RTC_WKUP_IRQHandler [WEAK] - EXPORT FLASH_IRQHandler [WEAK] - EXPORT RCC_IRQHandler [WEAK] - EXPORT EXTI0_IRQHandler [WEAK] - EXPORT EXTI1_IRQHandler [WEAK] - EXPORT EXTI2_IRQHandler [WEAK] - EXPORT EXTI3_IRQHandler [WEAK] - EXPORT EXTI4_IRQHandler [WEAK] - EXPORT DMA1_Stream0_IRQHandler [WEAK] - EXPORT DMA1_Stream1_IRQHandler [WEAK] - EXPORT DMA1_Stream2_IRQHandler [WEAK] - EXPORT DMA1_Stream3_IRQHandler [WEAK] - EXPORT DMA1_Stream4_IRQHandler [WEAK] - EXPORT DMA1_Stream5_IRQHandler [WEAK] - EXPORT DMA1_Stream6_IRQHandler [WEAK] - EXPORT ADC_IRQHandler [WEAK] - EXPORT EXTI9_5_IRQHandler [WEAK] - EXPORT TIM1_BRK_TIM9_IRQHandler [WEAK] - EXPORT TIM1_UP_IRQHandler [WEAK] - EXPORT TIM1_TRG_COM_TIM11_IRQHandler [WEAK] - EXPORT TIM1_CC_IRQHandler [WEAK] - EXPORT I2C1_EV_IRQHandler [WEAK] - EXPORT I2C1_ER_IRQHandler [WEAK] - EXPORT I2C2_EV_IRQHandler [WEAK] - EXPORT I2C2_ER_IRQHandler [WEAK] - EXPORT SPI1_IRQHandler [WEAK] - EXPORT SPI2_IRQHandler [WEAK] - EXPORT USART1_IRQHandler [WEAK] - EXPORT USART2_IRQHandler [WEAK] - EXPORT EXTI15_10_IRQHandler [WEAK] - EXPORT RTC_Alarm_IRQHandler [WEAK] - EXPORT DMA1_Stream7_IRQHandler [WEAK] - EXPORT TIM5_IRQHandler [WEAK] - EXPORT TIM6_DAC_IRQHandler [WEAK] - EXPORT DMA2_Stream0_IRQHandler [WEAK] - EXPORT DMA2_Stream1_IRQHandler [WEAK] - EXPORT DMA2_Stream2_IRQHandler [WEAK] - EXPORT DMA2_Stream3_IRQHandler [WEAK] - EXPORT DMA2_Stream4_IRQHandler [WEAK] - EXPORT DMA2_Stream4_IRQHandler [WEAK] - EXPORT DMA2_Stream5_IRQHandler [WEAK] - EXPORT DMA2_Stream6_IRQHandler [WEAK] - EXPORT DMA2_Stream7_IRQHandler [WEAK] - EXPORT USART6_IRQHandler [WEAK] - EXPORT RNG_IRQHandler [WEAK] - EXPORT FPU_IRQHandler [WEAK] - EXPORT SPI5_IRQHandler [WEAK] - EXPORT FMPI2C1_EV_IRQHandler [WEAK] - EXPORT FMPI2C1_ER_IRQHandler [WEAK] - EXPORT LPTIM1_IRQHandler [WEAK] - -WWDG_IRQHandler -PVD_IRQHandler -TAMP_STAMP_IRQHandler -RTC_WKUP_IRQHandler -FLASH_IRQHandler -RCC_IRQHandler -EXTI0_IRQHandler -EXTI1_IRQHandler -EXTI2_IRQHandler -EXTI3_IRQHandler -EXTI4_IRQHandler -DMA1_Stream0_IRQHandler -DMA1_Stream1_IRQHandler -DMA1_Stream2_IRQHandler -DMA1_Stream3_IRQHandler -DMA1_Stream4_IRQHandler -DMA1_Stream5_IRQHandler -DMA1_Stream6_IRQHandler -ADC_IRQHandler -EXTI9_5_IRQHandler -TIM1_BRK_TIM9_IRQHandler -TIM1_UP_IRQHandler -TIM1_TRG_COM_TIM11_IRQHandler -TIM1_CC_IRQHandler -I2C1_EV_IRQHandler -I2C1_ER_IRQHandler -I2C2_EV_IRQHandler -I2C2_ER_IRQHandler -SPI1_IRQHandler -SPI2_IRQHandler -USART1_IRQHandler -USART2_IRQHandler -EXTI15_10_IRQHandler -RTC_Alarm_IRQHandler -DMA1_Stream7_IRQHandler -TIM5_IRQHandler -TIM6_DAC_IRQHandler -DMA2_Stream0_IRQHandler -DMA2_Stream1_IRQHandler -DMA2_Stream2_IRQHandler -DMA2_Stream3_IRQHandler -DMA2_Stream4_IRQHandler -DMA2_Stream5_IRQHandler -DMA2_Stream6_IRQHandler -DMA2_Stream7_IRQHandler -USART6_IRQHandler -RNG_IRQHandler -FPU_IRQHandler -SPI5_IRQHandler -FMPI2C1_EV_IRQHandler -FMPI2C1_ER_IRQHandler -LPTIM1_IRQHandler - - B . - - ENDP - - ALIGN - -;******************************************************************************* -; User Stack and Heap initialization -;******************************************************************************* - IF :DEF:__MICROLIB - - EXPORT __initial_sp - EXPORT __heap_base - EXPORT __heap_limit - - ELSE - - IMPORT __use_two_region_memory - EXPORT __user_initial_stackheap - -__user_initial_stackheap - - LDR R0, = Heap_Mem - LDR R1, =(Stack_Mem + Stack_Size) - LDR R2, = (Heap_Mem + Heap_Size) - LDR R3, = Stack_Mem - BX LR - - ALIGN - - ENDIF - - END - -;************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE***** diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f411xe.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f411xe.s deleted file mode 100644 index c279c925d4..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f411xe.s +++ /dev/null @@ -1,395 +0,0 @@ -;******************** (C) COPYRIGHT 2015 STMicroelectronics ******************** -;* File Name : startup_stm32f411xe.s -;* Author : MCD Application Team -;* @version : V1.6.1 -;* @date : 21-October-2015 -;* Description : STM32F411xExx devices vector table for MDK-ARM toolchain. -;* This module performs: -;* - Set the initial SP -;* - Set the initial PC == Reset_Handler -;* - Set the vector table entries with the exceptions ISR address -;* - Branches to __main in the C library (which eventually -;* calls main()). -;* After Reset the CortexM4 processor is in Thread mode, -;* priority is Privileged, and the Stack is set to Main. -;* <<< Use Configuration Wizard in Context Menu >>> -;******************************************************************************* -; -;* Redistribution and use in source and binary forms, with or without modification, -;* are permitted provided that the following conditions are met: -;* 1. Redistributions of source code must retain the above copyright notice, -;* this list of conditions and the following disclaimer. -;* 2. Redistributions in binary form must reproduce the above copyright notice, -;* this list of conditions and the following disclaimer in the documentation -;* and/or other materials provided with the distribution. -;* 3. Neither the name of STMicroelectronics nor the names of its contributors -;* may be used to endorse or promote products derived from this software -;* without specific prior written permission. -;* -;* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -;* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE -;* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL -;* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -;* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -;* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, -;* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE -;* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -; -;******************************************************************************* - -; Amount of memory (in bytes) allocated for Stack -; Tailor this value to your application needs -; Stack Configuration -; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> -; - -Stack_Size EQU 0x00000400 - - AREA STACK, NOINIT, READWRITE, ALIGN=3 -Stack_Mem SPACE Stack_Size -__initial_sp - - -; Heap Configuration -; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> -; - -Heap_Size EQU 0x00000200 - - AREA HEAP, NOINIT, READWRITE, ALIGN=3 -__heap_base -Heap_Mem SPACE Heap_Size -__heap_limit - - PRESERVE8 - THUMB - - -; Vector Table Mapped to Address 0 at Reset - AREA RESET, DATA, READONLY - EXPORT __Vectors - EXPORT __Vectors_End - EXPORT __Vectors_Size - -__Vectors DCD __initial_sp ; Top of Stack - DCD Reset_Handler ; Reset Handler - DCD NMI_Handler ; NMI Handler - DCD HardFault_Handler ; Hard Fault Handler - DCD MemManage_Handler ; MPU Fault Handler - DCD BusFault_Handler ; Bus Fault Handler - DCD UsageFault_Handler ; Usage Fault Handler - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SVC_Handler ; SVCall Handler - DCD DebugMon_Handler ; Debug Monitor Handler - DCD 0 ; Reserved - DCD PendSV_Handler ; PendSV Handler - DCD SysTick_Handler ; SysTick Handler - - ; External Interrupts - DCD WWDG_IRQHandler ; Window WatchDog - DCD PVD_IRQHandler ; PVD through EXTI Line detection - DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line - DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line - DCD FLASH_IRQHandler ; FLASH - DCD RCC_IRQHandler ; RCC - DCD EXTI0_IRQHandler ; EXTI Line0 - DCD EXTI1_IRQHandler ; EXTI Line1 - DCD EXTI2_IRQHandler ; EXTI Line2 - DCD EXTI3_IRQHandler ; EXTI Line3 - DCD EXTI4_IRQHandler ; EXTI Line4 - DCD DMA1_Stream0_IRQHandler ; DMA1 Stream 0 - DCD DMA1_Stream1_IRQHandler ; DMA1 Stream 1 - DCD DMA1_Stream2_IRQHandler ; DMA1 Stream 2 - DCD DMA1_Stream3_IRQHandler ; DMA1 Stream 3 - DCD DMA1_Stream4_IRQHandler ; DMA1 Stream 4 - DCD DMA1_Stream5_IRQHandler ; DMA1 Stream 5 - DCD DMA1_Stream6_IRQHandler ; DMA1 Stream 6 - DCD ADC_IRQHandler ; ADC1, ADC2 and ADC3s - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD EXTI9_5_IRQHandler ; External Line[9:5]s - DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 - DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 - DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 - DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare - DCD TIM2_IRQHandler ; TIM2 - DCD TIM3_IRQHandler ; TIM3 - DCD TIM4_IRQHandler ; TIM4 - DCD I2C1_EV_IRQHandler ; I2C1 Event - DCD I2C1_ER_IRQHandler ; I2C1 Error - DCD I2C2_EV_IRQHandler ; I2C2 Event - DCD I2C2_ER_IRQHandler ; I2C2 Error - DCD SPI1_IRQHandler ; SPI1 - DCD SPI2_IRQHandler ; SPI2 - DCD USART1_IRQHandler ; USART1 - DCD USART2_IRQHandler ; USART2 - DCD 0 ; Reserved - DCD EXTI15_10_IRQHandler ; External Line[15:10]s - DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line - DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD DMA1_Stream7_IRQHandler ; DMA1 Stream7 - DCD 0 ; Reserved - DCD SDIO_IRQHandler ; SDIO - DCD TIM5_IRQHandler ; TIM5 - DCD SPI3_IRQHandler ; SPI3 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD DMA2_Stream0_IRQHandler ; DMA2 Stream 0 - DCD DMA2_Stream1_IRQHandler ; DMA2 Stream 1 - DCD DMA2_Stream2_IRQHandler ; DMA2 Stream 2 - DCD DMA2_Stream3_IRQHandler ; DMA2 Stream 3 - DCD DMA2_Stream4_IRQHandler ; DMA2 Stream 4 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD OTG_FS_IRQHandler ; USB OTG FS - DCD DMA2_Stream5_IRQHandler ; DMA2 Stream 5 - DCD DMA2_Stream6_IRQHandler ; DMA2 Stream 6 - DCD DMA2_Stream7_IRQHandler ; DMA2 Stream 7 - DCD USART6_IRQHandler ; USART6 - DCD I2C3_EV_IRQHandler ; I2C3 event - DCD I2C3_ER_IRQHandler ; I2C3 error - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD FPU_IRQHandler ; FPU - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SPI4_IRQHandler ; SPI4 - DCD SPI5_IRQHandler ; SPI5 - -__Vectors_End - -__Vectors_Size EQU __Vectors_End - __Vectors - - AREA |.text|, CODE, READONLY - -; Reset handler -Reset_Handler PROC - EXPORT Reset_Handler [WEAK] - IMPORT SystemInit - IMPORT __main - - LDR R0, =SystemInit - BLX R0 - LDR R0, =__main - BX R0 - ENDP - -; Dummy Exception Handlers (infinite loops which can be modified) - -NMI_Handler PROC - EXPORT NMI_Handler [WEAK] - B . - ENDP -HardFault_Handler\ - PROC - EXPORT HardFault_Handler [WEAK] - B . - ENDP -MemManage_Handler\ - PROC - EXPORT MemManage_Handler [WEAK] - B . - ENDP -BusFault_Handler\ - PROC - EXPORT BusFault_Handler [WEAK] - B . - ENDP -UsageFault_Handler\ - PROC - EXPORT UsageFault_Handler [WEAK] - B . - ENDP -SVC_Handler PROC - EXPORT SVC_Handler [WEAK] - B . - ENDP -DebugMon_Handler\ - PROC - EXPORT DebugMon_Handler [WEAK] - B . - ENDP -PendSV_Handler PROC - EXPORT PendSV_Handler [WEAK] - B . - ENDP -SysTick_Handler PROC - EXPORT SysTick_Handler [WEAK] - B . - ENDP - -Default_Handler PROC - - EXPORT WWDG_IRQHandler [WEAK] - EXPORT PVD_IRQHandler [WEAK] - EXPORT TAMP_STAMP_IRQHandler [WEAK] - EXPORT RTC_WKUP_IRQHandler [WEAK] - EXPORT FLASH_IRQHandler [WEAK] - EXPORT RCC_IRQHandler [WEAK] - EXPORT EXTI0_IRQHandler [WEAK] - EXPORT EXTI1_IRQHandler [WEAK] - EXPORT EXTI2_IRQHandler [WEAK] - EXPORT EXTI3_IRQHandler [WEAK] - EXPORT EXTI4_IRQHandler [WEAK] - EXPORT DMA1_Stream0_IRQHandler [WEAK] - EXPORT DMA1_Stream1_IRQHandler [WEAK] - EXPORT DMA1_Stream2_IRQHandler [WEAK] - EXPORT DMA1_Stream3_IRQHandler [WEAK] - EXPORT DMA1_Stream4_IRQHandler [WEAK] - EXPORT DMA1_Stream5_IRQHandler [WEAK] - EXPORT DMA1_Stream6_IRQHandler [WEAK] - EXPORT ADC_IRQHandler [WEAK] - EXPORT EXTI9_5_IRQHandler [WEAK] - EXPORT TIM1_BRK_TIM9_IRQHandler [WEAK] - EXPORT TIM1_UP_TIM10_IRQHandler [WEAK] - EXPORT TIM1_TRG_COM_TIM11_IRQHandler [WEAK] - EXPORT TIM1_CC_IRQHandler [WEAK] - EXPORT TIM2_IRQHandler [WEAK] - EXPORT TIM3_IRQHandler [WEAK] - EXPORT TIM4_IRQHandler [WEAK] - EXPORT I2C1_EV_IRQHandler [WEAK] - EXPORT I2C1_ER_IRQHandler [WEAK] - EXPORT I2C2_EV_IRQHandler [WEAK] - EXPORT I2C2_ER_IRQHandler [WEAK] - EXPORT SPI1_IRQHandler [WEAK] - EXPORT SPI2_IRQHandler [WEAK] - EXPORT USART1_IRQHandler [WEAK] - EXPORT USART2_IRQHandler [WEAK] - EXPORT EXTI15_10_IRQHandler [WEAK] - EXPORT RTC_Alarm_IRQHandler [WEAK] - EXPORT OTG_FS_WKUP_IRQHandler [WEAK] - EXPORT DMA1_Stream7_IRQHandler [WEAK] - EXPORT SDIO_IRQHandler [WEAK] - EXPORT TIM5_IRQHandler [WEAK] - EXPORT SPI3_IRQHandler [WEAK] - EXPORT DMA2_Stream0_IRQHandler [WEAK] - EXPORT DMA2_Stream1_IRQHandler [WEAK] - EXPORT DMA2_Stream2_IRQHandler [WEAK] - EXPORT DMA2_Stream3_IRQHandler [WEAK] - EXPORT DMA2_Stream4_IRQHandler [WEAK] - EXPORT OTG_FS_IRQHandler [WEAK] - EXPORT DMA2_Stream5_IRQHandler [WEAK] - EXPORT DMA2_Stream6_IRQHandler [WEAK] - EXPORT DMA2_Stream7_IRQHandler [WEAK] - EXPORT USART6_IRQHandler [WEAK] - EXPORT I2C3_EV_IRQHandler [WEAK] - EXPORT I2C3_ER_IRQHandler [WEAK] - EXPORT FPU_IRQHandler [WEAK] - EXPORT SPI4_IRQHandler [WEAK] - EXPORT SPI5_IRQHandler [WEAK] - -WWDG_IRQHandler -PVD_IRQHandler -TAMP_STAMP_IRQHandler -RTC_WKUP_IRQHandler -FLASH_IRQHandler -RCC_IRQHandler -EXTI0_IRQHandler -EXTI1_IRQHandler -EXTI2_IRQHandler -EXTI3_IRQHandler -EXTI4_IRQHandler -DMA1_Stream0_IRQHandler -DMA1_Stream1_IRQHandler -DMA1_Stream2_IRQHandler -DMA1_Stream3_IRQHandler -DMA1_Stream4_IRQHandler -DMA1_Stream5_IRQHandler -DMA1_Stream6_IRQHandler -ADC_IRQHandler -EXTI9_5_IRQHandler -TIM1_BRK_TIM9_IRQHandler -TIM1_UP_TIM10_IRQHandler -TIM1_TRG_COM_TIM11_IRQHandler -TIM1_CC_IRQHandler -TIM2_IRQHandler -TIM3_IRQHandler -TIM4_IRQHandler -I2C1_EV_IRQHandler -I2C1_ER_IRQHandler -I2C2_EV_IRQHandler -I2C2_ER_IRQHandler -SPI1_IRQHandler -SPI2_IRQHandler -USART1_IRQHandler -USART2_IRQHandler -EXTI15_10_IRQHandler -RTC_Alarm_IRQHandler -OTG_FS_WKUP_IRQHandler -DMA1_Stream7_IRQHandler -SDIO_IRQHandler -TIM5_IRQHandler -SPI3_IRQHandler -DMA2_Stream0_IRQHandler -DMA2_Stream1_IRQHandler -DMA2_Stream2_IRQHandler -DMA2_Stream3_IRQHandler -DMA2_Stream4_IRQHandler -OTG_FS_IRQHandler -DMA2_Stream5_IRQHandler -DMA2_Stream6_IRQHandler -DMA2_Stream7_IRQHandler -USART6_IRQHandler -I2C3_EV_IRQHandler -I2C3_ER_IRQHandler -FPU_IRQHandler -SPI4_IRQHandler -SPI5_IRQHandler - - B . - - ENDP - - ALIGN - -;******************************************************************************* -; User Stack and Heap initialization -;******************************************************************************* - IF :DEF:__MICROLIB - - EXPORT __initial_sp - EXPORT __heap_base - EXPORT __heap_limit - - ELSE - - IMPORT __use_two_region_memory - EXPORT __user_initial_stackheap - -__user_initial_stackheap - - LDR R0, = Heap_Mem - LDR R1, =(Stack_Mem + Stack_Size) - LDR R2, = (Heap_Mem + Heap_Size) - LDR R3, = Stack_Mem - BX LR - - ALIGN - - ENDIF - - END - -;************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE***** diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f427_437xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f427_437xx.s deleted file mode 100644 index 23b9eb35f2..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f427_437xx.s +++ /dev/null @@ -1,456 +0,0 @@ -;******************** (C) COPYRIGHT 2015 STMicroelectronics ******************** -;* File Name : startup_stm32f427_437xx.s -;* Author : MCD Application Team -;* @version : V1.6.1 -;* @date : 21-October-2015 -;* Description : STM32F427xx/437xx devices vector table for MDK-ARM 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 system clock and the external SRAM/SDRAM mounted -;* on STM324x7I-EVAL board 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 CortexM4 processor is in Thread mode, -;* priority is Privileged, and the Stack is set to Main. -;* <<< Use Configuration Wizard in Context Menu >>> -;******************************************************************************* -; -; Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); -; You may not use this file except in compliance with the License. -; You may obtain a copy of the License at: -; -; http://www.st.com/software_license_agreement_liberty_v2 -; -; Unless required by applicable law or agreed to in writing, software -; distributed under the License is distributed on an "AS IS" BASIS, -; WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -; See the License for the specific language governing permissions and -; limitations under the License. -; -;******************************************************************************* - -; Amount of memory (in bytes) allocated for Stack -; Tailor this value to your application needs -; Stack Configuration -; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> -; - -Stack_Size EQU 0x00000400 - - AREA STACK, NOINIT, READWRITE, ALIGN=3 -Stack_Mem SPACE Stack_Size -__initial_sp - - -; Heap Configuration -; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> -; - -Heap_Size EQU 0x00000200 - - AREA HEAP, NOINIT, READWRITE, ALIGN=3 -__heap_base -Heap_Mem SPACE Heap_Size -__heap_limit - - PRESERVE8 - THUMB - - -; Vector Table Mapped to Address 0 at Reset - AREA RESET, DATA, READONLY - EXPORT __Vectors - EXPORT __Vectors_End - EXPORT __Vectors_Size - -__Vectors DCD __initial_sp ; Top of Stack - DCD Reset_Handler ; Reset Handler - DCD NMI_Handler ; NMI Handler - DCD HardFault_Handler ; Hard Fault Handler - DCD MemManage_Handler ; MPU Fault Handler - DCD BusFault_Handler ; Bus Fault Handler - DCD UsageFault_Handler ; Usage Fault Handler - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SVC_Handler ; SVCall Handler - DCD DebugMon_Handler ; Debug Monitor Handler - DCD 0 ; Reserved - DCD PendSV_Handler ; PendSV Handler - DCD SysTick_Handler ; SysTick Handler - - ; External Interrupts - DCD WWDG_IRQHandler ; Window WatchDog - DCD PVD_IRQHandler ; PVD through EXTI Line detection - DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line - DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line - DCD FLASH_IRQHandler ; FLASH - DCD RCC_IRQHandler ; RCC - DCD EXTI0_IRQHandler ; EXTI Line0 - DCD EXTI1_IRQHandler ; EXTI Line1 - DCD EXTI2_IRQHandler ; EXTI Line2 - DCD EXTI3_IRQHandler ; EXTI Line3 - DCD EXTI4_IRQHandler ; EXTI Line4 - DCD DMA1_Stream0_IRQHandler ; DMA1 Stream 0 - DCD DMA1_Stream1_IRQHandler ; DMA1 Stream 1 - DCD DMA1_Stream2_IRQHandler ; DMA1 Stream 2 - DCD DMA1_Stream3_IRQHandler ; DMA1 Stream 3 - DCD DMA1_Stream4_IRQHandler ; DMA1 Stream 4 - DCD DMA1_Stream5_IRQHandler ; DMA1 Stream 5 - DCD DMA1_Stream6_IRQHandler ; DMA1 Stream 6 - DCD ADC_IRQHandler ; ADC1, ADC2 and ADC3s - DCD CAN1_TX_IRQHandler ; CAN1 TX - DCD CAN1_RX0_IRQHandler ; CAN1 RX0 - DCD CAN1_RX1_IRQHandler ; CAN1 RX1 - DCD CAN1_SCE_IRQHandler ; CAN1 SCE - DCD EXTI9_5_IRQHandler ; External Line[9:5]s - DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 - DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 - DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 - DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare - DCD TIM2_IRQHandler ; TIM2 - DCD TIM3_IRQHandler ; TIM3 - DCD TIM4_IRQHandler ; TIM4 - DCD I2C1_EV_IRQHandler ; I2C1 Event - DCD I2C1_ER_IRQHandler ; I2C1 Error - DCD I2C2_EV_IRQHandler ; I2C2 Event - DCD I2C2_ER_IRQHandler ; I2C2 Error - DCD SPI1_IRQHandler ; SPI1 - DCD SPI2_IRQHandler ; SPI2 - DCD USART1_IRQHandler ; USART1 - DCD USART2_IRQHandler ; USART2 - DCD USART3_IRQHandler ; USART3 - DCD EXTI15_10_IRQHandler ; External Line[15:10]s - DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line - DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line - DCD TIM8_BRK_TIM12_IRQHandler ; TIM8 Break and TIM12 - DCD TIM8_UP_TIM13_IRQHandler ; TIM8 Update and TIM13 - DCD TIM8_TRG_COM_TIM14_IRQHandler ; TIM8 Trigger and Commutation and TIM14 - DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare - DCD DMA1_Stream7_IRQHandler ; DMA1 Stream7 - DCD FMC_IRQHandler ; FMC - DCD SDIO_IRQHandler ; SDIO - DCD TIM5_IRQHandler ; TIM5 - DCD SPI3_IRQHandler ; SPI3 - DCD UART4_IRQHandler ; UART4 - DCD UART5_IRQHandler ; UART5 - DCD TIM6_DAC_IRQHandler ; TIM6 and DAC1&2 underrun errors - DCD TIM7_IRQHandler ; TIM7 - DCD DMA2_Stream0_IRQHandler ; DMA2 Stream 0 - DCD DMA2_Stream1_IRQHandler ; DMA2 Stream 1 - DCD DMA2_Stream2_IRQHandler ; DMA2 Stream 2 - DCD DMA2_Stream3_IRQHandler ; DMA2 Stream 3 - DCD DMA2_Stream4_IRQHandler ; DMA2 Stream 4 - DCD ETH_IRQHandler ; Ethernet - DCD ETH_WKUP_IRQHandler ; Ethernet Wakeup through EXTI line - DCD CAN2_TX_IRQHandler ; CAN2 TX - DCD CAN2_RX0_IRQHandler ; CAN2 RX0 - DCD CAN2_RX1_IRQHandler ; CAN2 RX1 - DCD CAN2_SCE_IRQHandler ; CAN2 SCE - DCD OTG_FS_IRQHandler ; USB OTG FS - DCD DMA2_Stream5_IRQHandler ; DMA2 Stream 5 - DCD DMA2_Stream6_IRQHandler ; DMA2 Stream 6 - DCD DMA2_Stream7_IRQHandler ; DMA2 Stream 7 - DCD USART6_IRQHandler ; USART6 - DCD I2C3_EV_IRQHandler ; I2C3 event - DCD I2C3_ER_IRQHandler ; I2C3 error - DCD OTG_HS_EP1_OUT_IRQHandler ; USB OTG HS End Point 1 Out - DCD OTG_HS_EP1_IN_IRQHandler ; USB OTG HS End Point 1 In - DCD OTG_HS_WKUP_IRQHandler ; USB OTG HS Wakeup through EXTI - DCD OTG_HS_IRQHandler ; USB OTG HS - DCD DCMI_IRQHandler ; DCMI - DCD CRYP_IRQHandler ; CRYP crypto - DCD HASH_RNG_IRQHandler ; Hash and Rng - DCD FPU_IRQHandler ; FPU - DCD UART7_IRQHandler ; UART7 - DCD UART8_IRQHandler ; UART8 - DCD SPI4_IRQHandler ; SPI4 - DCD SPI5_IRQHandler ; SPI5 - DCD SPI6_IRQHandler ; SPI6 - DCD SAI1_IRQHandler ; SAI1 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD DMA2D_IRQHandler ; DMA2D - -__Vectors_End - -__Vectors_Size EQU __Vectors_End - __Vectors - - AREA |.text|, CODE, READONLY - -; Reset handler -Reset_Handler PROC - EXPORT Reset_Handler [WEAK] - IMPORT SystemInit - IMPORT __main - - LDR R0, =SystemInit - BLX R0 - LDR R0, =__main - BX R0 - ENDP - -; Dummy Exception Handlers (infinite loops which can be modified) - -NMI_Handler PROC - EXPORT NMI_Handler [WEAK] - B . - ENDP -HardFault_Handler\ - PROC - EXPORT HardFault_Handler [WEAK] - B . - ENDP -MemManage_Handler\ - PROC - EXPORT MemManage_Handler [WEAK] - B . - ENDP -BusFault_Handler\ - PROC - EXPORT BusFault_Handler [WEAK] - B . - ENDP -UsageFault_Handler\ - PROC - EXPORT UsageFault_Handler [WEAK] - B . - ENDP -SVC_Handler PROC - EXPORT SVC_Handler [WEAK] - B . - ENDP -DebugMon_Handler\ - PROC - EXPORT DebugMon_Handler [WEAK] - B . - ENDP -PendSV_Handler PROC - EXPORT PendSV_Handler [WEAK] - B . - ENDP -SysTick_Handler PROC - EXPORT SysTick_Handler [WEAK] - B . - ENDP - -Default_Handler PROC - - EXPORT WWDG_IRQHandler [WEAK] - EXPORT PVD_IRQHandler [WEAK] - EXPORT TAMP_STAMP_IRQHandler [WEAK] - EXPORT RTC_WKUP_IRQHandler [WEAK] - EXPORT FLASH_IRQHandler [WEAK] - EXPORT RCC_IRQHandler [WEAK] - EXPORT EXTI0_IRQHandler [WEAK] - EXPORT EXTI1_IRQHandler [WEAK] - EXPORT EXTI2_IRQHandler [WEAK] - EXPORT EXTI3_IRQHandler [WEAK] - EXPORT EXTI4_IRQHandler [WEAK] - EXPORT DMA1_Stream0_IRQHandler [WEAK] - EXPORT DMA1_Stream1_IRQHandler [WEAK] - EXPORT DMA1_Stream2_IRQHandler [WEAK] - EXPORT DMA1_Stream3_IRQHandler [WEAK] - EXPORT DMA1_Stream4_IRQHandler [WEAK] - EXPORT DMA1_Stream5_IRQHandler [WEAK] - EXPORT DMA1_Stream6_IRQHandler [WEAK] - EXPORT ADC_IRQHandler [WEAK] - EXPORT CAN1_TX_IRQHandler [WEAK] - EXPORT CAN1_RX0_IRQHandler [WEAK] - EXPORT CAN1_RX1_IRQHandler [WEAK] - EXPORT CAN1_SCE_IRQHandler [WEAK] - EXPORT EXTI9_5_IRQHandler [WEAK] - EXPORT TIM1_BRK_TIM9_IRQHandler [WEAK] - EXPORT TIM1_UP_TIM10_IRQHandler [WEAK] - EXPORT TIM1_TRG_COM_TIM11_IRQHandler [WEAK] - EXPORT TIM1_CC_IRQHandler [WEAK] - EXPORT TIM2_IRQHandler [WEAK] - EXPORT TIM3_IRQHandler [WEAK] - EXPORT TIM4_IRQHandler [WEAK] - EXPORT I2C1_EV_IRQHandler [WEAK] - EXPORT I2C1_ER_IRQHandler [WEAK] - EXPORT I2C2_EV_IRQHandler [WEAK] - EXPORT I2C2_ER_IRQHandler [WEAK] - EXPORT SPI1_IRQHandler [WEAK] - EXPORT SPI2_IRQHandler [WEAK] - EXPORT USART1_IRQHandler [WEAK] - EXPORT USART2_IRQHandler [WEAK] - EXPORT USART3_IRQHandler [WEAK] - EXPORT EXTI15_10_IRQHandler [WEAK] - EXPORT RTC_Alarm_IRQHandler [WEAK] - EXPORT OTG_FS_WKUP_IRQHandler [WEAK] - EXPORT TIM8_BRK_TIM12_IRQHandler [WEAK] - EXPORT TIM8_UP_TIM13_IRQHandler [WEAK] - EXPORT TIM8_TRG_COM_TIM14_IRQHandler [WEAK] - EXPORT TIM8_CC_IRQHandler [WEAK] - EXPORT DMA1_Stream7_IRQHandler [WEAK] - EXPORT FMC_IRQHandler [WEAK] - EXPORT SDIO_IRQHandler [WEAK] - EXPORT TIM5_IRQHandler [WEAK] - EXPORT SPI3_IRQHandler [WEAK] - EXPORT UART4_IRQHandler [WEAK] - EXPORT UART5_IRQHandler [WEAK] - EXPORT TIM6_DAC_IRQHandler [WEAK] - EXPORT TIM7_IRQHandler [WEAK] - EXPORT DMA2_Stream0_IRQHandler [WEAK] - EXPORT DMA2_Stream1_IRQHandler [WEAK] - EXPORT DMA2_Stream2_IRQHandler [WEAK] - EXPORT DMA2_Stream3_IRQHandler [WEAK] - EXPORT DMA2_Stream4_IRQHandler [WEAK] - EXPORT ETH_IRQHandler [WEAK] - EXPORT ETH_WKUP_IRQHandler [WEAK] - EXPORT CAN2_TX_IRQHandler [WEAK] - EXPORT CAN2_RX0_IRQHandler [WEAK] - EXPORT CAN2_RX1_IRQHandler [WEAK] - EXPORT CAN2_SCE_IRQHandler [WEAK] - EXPORT OTG_FS_IRQHandler [WEAK] - EXPORT DMA2_Stream5_IRQHandler [WEAK] - EXPORT DMA2_Stream6_IRQHandler [WEAK] - EXPORT DMA2_Stream7_IRQHandler [WEAK] - EXPORT USART6_IRQHandler [WEAK] - EXPORT I2C3_EV_IRQHandler [WEAK] - EXPORT I2C3_ER_IRQHandler [WEAK] - EXPORT OTG_HS_EP1_OUT_IRQHandler [WEAK] - EXPORT OTG_HS_EP1_IN_IRQHandler [WEAK] - EXPORT OTG_HS_WKUP_IRQHandler [WEAK] - EXPORT OTG_HS_IRQHandler [WEAK] - EXPORT DCMI_IRQHandler [WEAK] - EXPORT CRYP_IRQHandler [WEAK] - EXPORT HASH_RNG_IRQHandler [WEAK] - EXPORT FPU_IRQHandler [WEAK] - EXPORT UART7_IRQHandler [WEAK] - EXPORT UART8_IRQHandler [WEAK] - EXPORT SPI4_IRQHandler [WEAK] - EXPORT SPI5_IRQHandler [WEAK] - EXPORT SPI6_IRQHandler [WEAK] - EXPORT SAI1_IRQHandler [WEAK] - EXPORT DMA2D_IRQHandler [WEAK] - -WWDG_IRQHandler -PVD_IRQHandler -TAMP_STAMP_IRQHandler -RTC_WKUP_IRQHandler -FLASH_IRQHandler -RCC_IRQHandler -EXTI0_IRQHandler -EXTI1_IRQHandler -EXTI2_IRQHandler -EXTI3_IRQHandler -EXTI4_IRQHandler -DMA1_Stream0_IRQHandler -DMA1_Stream1_IRQHandler -DMA1_Stream2_IRQHandler -DMA1_Stream3_IRQHandler -DMA1_Stream4_IRQHandler -DMA1_Stream5_IRQHandler -DMA1_Stream6_IRQHandler -ADC_IRQHandler -CAN1_TX_IRQHandler -CAN1_RX0_IRQHandler -CAN1_RX1_IRQHandler -CAN1_SCE_IRQHandler -EXTI9_5_IRQHandler -TIM1_BRK_TIM9_IRQHandler -TIM1_UP_TIM10_IRQHandler -TIM1_TRG_COM_TIM11_IRQHandler -TIM1_CC_IRQHandler -TIM2_IRQHandler -TIM3_IRQHandler -TIM4_IRQHandler -I2C1_EV_IRQHandler -I2C1_ER_IRQHandler -I2C2_EV_IRQHandler -I2C2_ER_IRQHandler -SPI1_IRQHandler -SPI2_IRQHandler -USART1_IRQHandler -USART2_IRQHandler -USART3_IRQHandler -EXTI15_10_IRQHandler -RTC_Alarm_IRQHandler -OTG_FS_WKUP_IRQHandler -TIM8_BRK_TIM12_IRQHandler -TIM8_UP_TIM13_IRQHandler -TIM8_TRG_COM_TIM14_IRQHandler -TIM8_CC_IRQHandler -DMA1_Stream7_IRQHandler -FMC_IRQHandler -SDIO_IRQHandler -TIM5_IRQHandler -SPI3_IRQHandler -UART4_IRQHandler -UART5_IRQHandler -TIM6_DAC_IRQHandler -TIM7_IRQHandler -DMA2_Stream0_IRQHandler -DMA2_Stream1_IRQHandler -DMA2_Stream2_IRQHandler -DMA2_Stream3_IRQHandler -DMA2_Stream4_IRQHandler -ETH_IRQHandler -ETH_WKUP_IRQHandler -CAN2_TX_IRQHandler -CAN2_RX0_IRQHandler -CAN2_RX1_IRQHandler -CAN2_SCE_IRQHandler -OTG_FS_IRQHandler -DMA2_Stream5_IRQHandler -DMA2_Stream6_IRQHandler -DMA2_Stream7_IRQHandler -USART6_IRQHandler -I2C3_EV_IRQHandler -I2C3_ER_IRQHandler -OTG_HS_EP1_OUT_IRQHandler -OTG_HS_EP1_IN_IRQHandler -OTG_HS_WKUP_IRQHandler -OTG_HS_IRQHandler -DCMI_IRQHandler -CRYP_IRQHandler -HASH_RNG_IRQHandler -FPU_IRQHandler -UART7_IRQHandler -UART8_IRQHandler -SPI4_IRQHandler -SPI5_IRQHandler -SPI6_IRQHandler -SAI1_IRQHandler -DMA2D_IRQHandler - B . - - ENDP - - ALIGN - -;******************************************************************************* -; User Stack and Heap initialization -;******************************************************************************* - IF :DEF:__MICROLIB - - EXPORT __initial_sp - EXPORT __heap_base - EXPORT __heap_limit - - ELSE - - IMPORT __use_two_region_memory - EXPORT __user_initial_stackheap - -__user_initial_stackheap - - LDR R0, = Heap_Mem - LDR R1, =(Stack_Mem + Stack_Size) - LDR R2, = (Heap_Mem + Heap_Size) - LDR R3, = Stack_Mem - BX LR - - ALIGN - - ENDIF - - END - -;************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE***** diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f427x.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f427x.s deleted file mode 100644 index 2d78111707..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f427x.s +++ /dev/null @@ -1,457 +0,0 @@ -;******************** (C) COPYRIGHT 2015 STMicroelectronics ******************** -;* File Name : startup_stm32f427x.s -;* Author : MCD Application Team -;* @version : V1.6.1 -;* @date : 21-October-2015 -;* Description : STM32F427xx/437xx devices vector table for MDK-ARM toolchain. -;* Same as startup_stm32f427_437xx.s and maintained for legacy purpose -;* 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 system clock and the external SRAM/SDRAM mounted -;* on STM324x9I-EVAL/STM324x7I-EVALs board 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 CortexM4 processor is in Thread mode, -;* priority is Privileged, and the Stack is set to Main. -;* <<< Use Configuration Wizard in Context Menu >>> -;******************************************************************************* -; -; Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); -; You may not use this file except in compliance with the License. -; You may obtain a copy of the License at: -; -; http://www.st.com/software_license_agreement_liberty_v2 -; -; Unless required by applicable law or agreed to in writing, software -; distributed under the License is distributed on an "AS IS" BASIS, -; WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -; See the License for the specific language governing permissions and -; limitations under the License. -; -;******************************************************************************* - -; Amount of memory (in bytes) allocated for Stack -; Tailor this value to your application needs -; Stack Configuration -; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> -; - -Stack_Size EQU 0x00000400 - - AREA STACK, NOINIT, READWRITE, ALIGN=3 -Stack_Mem SPACE Stack_Size -__initial_sp - - -; Heap Configuration -; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> -; - -Heap_Size EQU 0x00000200 - - AREA HEAP, NOINIT, READWRITE, ALIGN=3 -__heap_base -Heap_Mem SPACE Heap_Size -__heap_limit - - PRESERVE8 - THUMB - - -; Vector Table Mapped to Address 0 at Reset - AREA RESET, DATA, READONLY - EXPORT __Vectors - EXPORT __Vectors_End - EXPORT __Vectors_Size - -__Vectors DCD __initial_sp ; Top of Stack - DCD Reset_Handler ; Reset Handler - DCD NMI_Handler ; NMI Handler - DCD HardFault_Handler ; Hard Fault Handler - DCD MemManage_Handler ; MPU Fault Handler - DCD BusFault_Handler ; Bus Fault Handler - DCD UsageFault_Handler ; Usage Fault Handler - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SVC_Handler ; SVCall Handler - DCD DebugMon_Handler ; Debug Monitor Handler - DCD 0 ; Reserved - DCD PendSV_Handler ; PendSV Handler - DCD SysTick_Handler ; SysTick Handler - - ; External Interrupts - DCD WWDG_IRQHandler ; Window WatchDog - DCD PVD_IRQHandler ; PVD through EXTI Line detection - DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line - DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line - DCD FLASH_IRQHandler ; FLASH - DCD RCC_IRQHandler ; RCC - DCD EXTI0_IRQHandler ; EXTI Line0 - DCD EXTI1_IRQHandler ; EXTI Line1 - DCD EXTI2_IRQHandler ; EXTI Line2 - DCD EXTI3_IRQHandler ; EXTI Line3 - DCD EXTI4_IRQHandler ; EXTI Line4 - DCD DMA1_Stream0_IRQHandler ; DMA1 Stream 0 - DCD DMA1_Stream1_IRQHandler ; DMA1 Stream 1 - DCD DMA1_Stream2_IRQHandler ; DMA1 Stream 2 - DCD DMA1_Stream3_IRQHandler ; DMA1 Stream 3 - DCD DMA1_Stream4_IRQHandler ; DMA1 Stream 4 - DCD DMA1_Stream5_IRQHandler ; DMA1 Stream 5 - DCD DMA1_Stream6_IRQHandler ; DMA1 Stream 6 - DCD ADC_IRQHandler ; ADC1, ADC2 and ADC3s - DCD CAN1_TX_IRQHandler ; CAN1 TX - DCD CAN1_RX0_IRQHandler ; CAN1 RX0 - DCD CAN1_RX1_IRQHandler ; CAN1 RX1 - DCD CAN1_SCE_IRQHandler ; CAN1 SCE - DCD EXTI9_5_IRQHandler ; External Line[9:5]s - DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 - DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 - DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 - DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare - DCD TIM2_IRQHandler ; TIM2 - DCD TIM3_IRQHandler ; TIM3 - DCD TIM4_IRQHandler ; TIM4 - DCD I2C1_EV_IRQHandler ; I2C1 Event - DCD I2C1_ER_IRQHandler ; I2C1 Error - DCD I2C2_EV_IRQHandler ; I2C2 Event - DCD I2C2_ER_IRQHandler ; I2C2 Error - DCD SPI1_IRQHandler ; SPI1 - DCD SPI2_IRQHandler ; SPI2 - DCD USART1_IRQHandler ; USART1 - DCD USART2_IRQHandler ; USART2 - DCD USART3_IRQHandler ; USART3 - DCD EXTI15_10_IRQHandler ; External Line[15:10]s - DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line - DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line - DCD TIM8_BRK_TIM12_IRQHandler ; TIM8 Break and TIM12 - DCD TIM8_UP_TIM13_IRQHandler ; TIM8 Update and TIM13 - DCD TIM8_TRG_COM_TIM14_IRQHandler ; TIM8 Trigger and Commutation and TIM14 - DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare - DCD DMA1_Stream7_IRQHandler ; DMA1 Stream7 - DCD FMC_IRQHandler ; FMC - DCD SDIO_IRQHandler ; SDIO - DCD TIM5_IRQHandler ; TIM5 - DCD SPI3_IRQHandler ; SPI3 - DCD UART4_IRQHandler ; UART4 - DCD UART5_IRQHandler ; UART5 - DCD TIM6_DAC_IRQHandler ; TIM6 and DAC1&2 underrun errors - DCD TIM7_IRQHandler ; TIM7 - DCD DMA2_Stream0_IRQHandler ; DMA2 Stream 0 - DCD DMA2_Stream1_IRQHandler ; DMA2 Stream 1 - DCD DMA2_Stream2_IRQHandler ; DMA2 Stream 2 - DCD DMA2_Stream3_IRQHandler ; DMA2 Stream 3 - DCD DMA2_Stream4_IRQHandler ; DMA2 Stream 4 - DCD ETH_IRQHandler ; Ethernet - DCD ETH_WKUP_IRQHandler ; Ethernet Wakeup through EXTI line - DCD CAN2_TX_IRQHandler ; CAN2 TX - DCD CAN2_RX0_IRQHandler ; CAN2 RX0 - DCD CAN2_RX1_IRQHandler ; CAN2 RX1 - DCD CAN2_SCE_IRQHandler ; CAN2 SCE - DCD OTG_FS_IRQHandler ; USB OTG FS - DCD DMA2_Stream5_IRQHandler ; DMA2 Stream 5 - DCD DMA2_Stream6_IRQHandler ; DMA2 Stream 6 - DCD DMA2_Stream7_IRQHandler ; DMA2 Stream 7 - DCD USART6_IRQHandler ; USART6 - DCD I2C3_EV_IRQHandler ; I2C3 event - DCD I2C3_ER_IRQHandler ; I2C3 error - DCD OTG_HS_EP1_OUT_IRQHandler ; USB OTG HS End Point 1 Out - DCD OTG_HS_EP1_IN_IRQHandler ; USB OTG HS End Point 1 In - DCD OTG_HS_WKUP_IRQHandler ; USB OTG HS Wakeup through EXTI - DCD OTG_HS_IRQHandler ; USB OTG HS - DCD DCMI_IRQHandler ; DCMI - DCD CRYP_IRQHandler ; CRYP crypto - DCD HASH_RNG_IRQHandler ; Hash and Rng - DCD FPU_IRQHandler ; FPU - DCD UART7_IRQHandler ; UART7 - DCD UART8_IRQHandler ; UART8 - DCD SPI4_IRQHandler ; SPI4 - DCD SPI5_IRQHandler ; SPI5 - DCD SPI6_IRQHandler ; SPI6 - DCD SAI1_IRQHandler ; SAI1 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD DMA2D_IRQHandler ; DMA2D - -__Vectors_End - -__Vectors_Size EQU __Vectors_End - __Vectors - - AREA |.text|, CODE, READONLY - -; Reset handler -Reset_Handler PROC - EXPORT Reset_Handler [WEAK] - IMPORT SystemInit - IMPORT __main - - LDR R0, =SystemInit - BLX R0 - LDR R0, =__main - BX R0 - ENDP - -; Dummy Exception Handlers (infinite loops which can be modified) - -NMI_Handler PROC - EXPORT NMI_Handler [WEAK] - B . - ENDP -HardFault_Handler\ - PROC - EXPORT HardFault_Handler [WEAK] - B . - ENDP -MemManage_Handler\ - PROC - EXPORT MemManage_Handler [WEAK] - B . - ENDP -BusFault_Handler\ - PROC - EXPORT BusFault_Handler [WEAK] - B . - ENDP -UsageFault_Handler\ - PROC - EXPORT UsageFault_Handler [WEAK] - B . - ENDP -SVC_Handler PROC - EXPORT SVC_Handler [WEAK] - B . - ENDP -DebugMon_Handler\ - PROC - EXPORT DebugMon_Handler [WEAK] - B . - ENDP -PendSV_Handler PROC - EXPORT PendSV_Handler [WEAK] - B . - ENDP -SysTick_Handler PROC - EXPORT SysTick_Handler [WEAK] - B . - ENDP - -Default_Handler PROC - - EXPORT WWDG_IRQHandler [WEAK] - EXPORT PVD_IRQHandler [WEAK] - EXPORT TAMP_STAMP_IRQHandler [WEAK] - EXPORT RTC_WKUP_IRQHandler [WEAK] - EXPORT FLASH_IRQHandler [WEAK] - EXPORT RCC_IRQHandler [WEAK] - EXPORT EXTI0_IRQHandler [WEAK] - EXPORT EXTI1_IRQHandler [WEAK] - EXPORT EXTI2_IRQHandler [WEAK] - EXPORT EXTI3_IRQHandler [WEAK] - EXPORT EXTI4_IRQHandler [WEAK] - EXPORT DMA1_Stream0_IRQHandler [WEAK] - EXPORT DMA1_Stream1_IRQHandler [WEAK] - EXPORT DMA1_Stream2_IRQHandler [WEAK] - EXPORT DMA1_Stream3_IRQHandler [WEAK] - EXPORT DMA1_Stream4_IRQHandler [WEAK] - EXPORT DMA1_Stream5_IRQHandler [WEAK] - EXPORT DMA1_Stream6_IRQHandler [WEAK] - EXPORT ADC_IRQHandler [WEAK] - EXPORT CAN1_TX_IRQHandler [WEAK] - EXPORT CAN1_RX0_IRQHandler [WEAK] - EXPORT CAN1_RX1_IRQHandler [WEAK] - EXPORT CAN1_SCE_IRQHandler [WEAK] - EXPORT EXTI9_5_IRQHandler [WEAK] - EXPORT TIM1_BRK_TIM9_IRQHandler [WEAK] - EXPORT TIM1_UP_TIM10_IRQHandler [WEAK] - EXPORT TIM1_TRG_COM_TIM11_IRQHandler [WEAK] - EXPORT TIM1_CC_IRQHandler [WEAK] - EXPORT TIM2_IRQHandler [WEAK] - EXPORT TIM3_IRQHandler [WEAK] - EXPORT TIM4_IRQHandler [WEAK] - EXPORT I2C1_EV_IRQHandler [WEAK] - EXPORT I2C1_ER_IRQHandler [WEAK] - EXPORT I2C2_EV_IRQHandler [WEAK] - EXPORT I2C2_ER_IRQHandler [WEAK] - EXPORT SPI1_IRQHandler [WEAK] - EXPORT SPI2_IRQHandler [WEAK] - EXPORT USART1_IRQHandler [WEAK] - EXPORT USART2_IRQHandler [WEAK] - EXPORT USART3_IRQHandler [WEAK] - EXPORT EXTI15_10_IRQHandler [WEAK] - EXPORT RTC_Alarm_IRQHandler [WEAK] - EXPORT OTG_FS_WKUP_IRQHandler [WEAK] - EXPORT TIM8_BRK_TIM12_IRQHandler [WEAK] - EXPORT TIM8_UP_TIM13_IRQHandler [WEAK] - EXPORT TIM8_TRG_COM_TIM14_IRQHandler [WEAK] - EXPORT TIM8_CC_IRQHandler [WEAK] - EXPORT DMA1_Stream7_IRQHandler [WEAK] - EXPORT FMC_IRQHandler [WEAK] - EXPORT SDIO_IRQHandler [WEAK] - EXPORT TIM5_IRQHandler [WEAK] - EXPORT SPI3_IRQHandler [WEAK] - EXPORT UART4_IRQHandler [WEAK] - EXPORT UART5_IRQHandler [WEAK] - EXPORT TIM6_DAC_IRQHandler [WEAK] - EXPORT TIM7_IRQHandler [WEAK] - EXPORT DMA2_Stream0_IRQHandler [WEAK] - EXPORT DMA2_Stream1_IRQHandler [WEAK] - EXPORT DMA2_Stream2_IRQHandler [WEAK] - EXPORT DMA2_Stream3_IRQHandler [WEAK] - EXPORT DMA2_Stream4_IRQHandler [WEAK] - EXPORT ETH_IRQHandler [WEAK] - EXPORT ETH_WKUP_IRQHandler [WEAK] - EXPORT CAN2_TX_IRQHandler [WEAK] - EXPORT CAN2_RX0_IRQHandler [WEAK] - EXPORT CAN2_RX1_IRQHandler [WEAK] - EXPORT CAN2_SCE_IRQHandler [WEAK] - EXPORT OTG_FS_IRQHandler [WEAK] - EXPORT DMA2_Stream5_IRQHandler [WEAK] - EXPORT DMA2_Stream6_IRQHandler [WEAK] - EXPORT DMA2_Stream7_IRQHandler [WEAK] - EXPORT USART6_IRQHandler [WEAK] - EXPORT I2C3_EV_IRQHandler [WEAK] - EXPORT I2C3_ER_IRQHandler [WEAK] - EXPORT OTG_HS_EP1_OUT_IRQHandler [WEAK] - EXPORT OTG_HS_EP1_IN_IRQHandler [WEAK] - EXPORT OTG_HS_WKUP_IRQHandler [WEAK] - EXPORT OTG_HS_IRQHandler [WEAK] - EXPORT DCMI_IRQHandler [WEAK] - EXPORT CRYP_IRQHandler [WEAK] - EXPORT HASH_RNG_IRQHandler [WEAK] - EXPORT FPU_IRQHandler [WEAK] - EXPORT UART7_IRQHandler [WEAK] - EXPORT UART8_IRQHandler [WEAK] - EXPORT SPI4_IRQHandler [WEAK] - EXPORT SPI5_IRQHandler [WEAK] - EXPORT SPI6_IRQHandler [WEAK] - EXPORT SAI1_IRQHandler [WEAK] - EXPORT DMA2D_IRQHandler [WEAK] - -WWDG_IRQHandler -PVD_IRQHandler -TAMP_STAMP_IRQHandler -RTC_WKUP_IRQHandler -FLASH_IRQHandler -RCC_IRQHandler -EXTI0_IRQHandler -EXTI1_IRQHandler -EXTI2_IRQHandler -EXTI3_IRQHandler -EXTI4_IRQHandler -DMA1_Stream0_IRQHandler -DMA1_Stream1_IRQHandler -DMA1_Stream2_IRQHandler -DMA1_Stream3_IRQHandler -DMA1_Stream4_IRQHandler -DMA1_Stream5_IRQHandler -DMA1_Stream6_IRQHandler -ADC_IRQHandler -CAN1_TX_IRQHandler -CAN1_RX0_IRQHandler -CAN1_RX1_IRQHandler -CAN1_SCE_IRQHandler -EXTI9_5_IRQHandler -TIM1_BRK_TIM9_IRQHandler -TIM1_UP_TIM10_IRQHandler -TIM1_TRG_COM_TIM11_IRQHandler -TIM1_CC_IRQHandler -TIM2_IRQHandler -TIM3_IRQHandler -TIM4_IRQHandler -I2C1_EV_IRQHandler -I2C1_ER_IRQHandler -I2C2_EV_IRQHandler -I2C2_ER_IRQHandler -SPI1_IRQHandler -SPI2_IRQHandler -USART1_IRQHandler -USART2_IRQHandler -USART3_IRQHandler -EXTI15_10_IRQHandler -RTC_Alarm_IRQHandler -OTG_FS_WKUP_IRQHandler -TIM8_BRK_TIM12_IRQHandler -TIM8_UP_TIM13_IRQHandler -TIM8_TRG_COM_TIM14_IRQHandler -TIM8_CC_IRQHandler -DMA1_Stream7_IRQHandler -FMC_IRQHandler -SDIO_IRQHandler -TIM5_IRQHandler -SPI3_IRQHandler -UART4_IRQHandler -UART5_IRQHandler -TIM6_DAC_IRQHandler -TIM7_IRQHandler -DMA2_Stream0_IRQHandler -DMA2_Stream1_IRQHandler -DMA2_Stream2_IRQHandler -DMA2_Stream3_IRQHandler -DMA2_Stream4_IRQHandler -ETH_IRQHandler -ETH_WKUP_IRQHandler -CAN2_TX_IRQHandler -CAN2_RX0_IRQHandler -CAN2_RX1_IRQHandler -CAN2_SCE_IRQHandler -OTG_FS_IRQHandler -DMA2_Stream5_IRQHandler -DMA2_Stream6_IRQHandler -DMA2_Stream7_IRQHandler -USART6_IRQHandler -I2C3_EV_IRQHandler -I2C3_ER_IRQHandler -OTG_HS_EP1_OUT_IRQHandler -OTG_HS_EP1_IN_IRQHandler -OTG_HS_WKUP_IRQHandler -OTG_HS_IRQHandler -DCMI_IRQHandler -CRYP_IRQHandler -HASH_RNG_IRQHandler -FPU_IRQHandler -UART7_IRQHandler -UART8_IRQHandler -SPI4_IRQHandler -SPI5_IRQHandler -SPI6_IRQHandler -SAI1_IRQHandler -DMA2D_IRQHandler - B . - - ENDP - - ALIGN - -;******************************************************************************* -; User Stack and Heap initialization -;******************************************************************************* - IF :DEF:__MICROLIB - - EXPORT __initial_sp - EXPORT __heap_base - EXPORT __heap_limit - - ELSE - - IMPORT __use_two_region_memory - EXPORT __user_initial_stackheap - -__user_initial_stackheap - - LDR R0, = Heap_Mem - LDR R1, =(Stack_Mem + Stack_Size) - LDR R2, = (Heap_Mem + Heap_Size) - LDR R3, = Stack_Mem - BX LR - - ALIGN - - ENDIF - - END - -;************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE***** diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f429_439xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f429_439xx.s deleted file mode 100644 index cc70b139f3..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f429_439xx.s +++ /dev/null @@ -1,460 +0,0 @@ -;******************** (C) COPYRIGHT 2015 STMicroelectronics ******************** -;* File Name : startup_stm32f429_439xx.s -;* Author : MCD Application Team -;* @version : V1.6.1 -;* @date : 21-October-2015 -;* Description : STM32F429xx/439xx devices vector table for MDK-ARM 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 system clock and the external SRAM/SDRAM mounted -;* on STM324x9I-EVAL boards 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 CortexM4 processor is in Thread mode, -;* priority is Privileged, and the Stack is set to Main. -;* <<< Use Configuration Wizard in Context Menu >>> -;******************************************************************************* -; -; Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); -; You may not use this file except in compliance with the License. -; You may obtain a copy of the License at: -; -; http://www.st.com/software_license_agreement_liberty_v2 -; -; Unless required by applicable law or agreed to in writing, software -; distributed under the License is distributed on an "AS IS" BASIS, -; WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -; See the License for the specific language governing permissions and -; limitations under the License. -; -;******************************************************************************* - -; Amount of memory (in bytes) allocated for Stack -; Tailor this value to your application needs -; Stack Configuration -; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> -; - -Stack_Size EQU 0x00000400 - - AREA STACK, NOINIT, READWRITE, ALIGN=3 -Stack_Mem SPACE Stack_Size -__initial_sp - - -; Heap Configuration -; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> -; - -Heap_Size EQU 0x00000200 - - AREA HEAP, NOINIT, READWRITE, ALIGN=3 -__heap_base -Heap_Mem SPACE Heap_Size -__heap_limit - - PRESERVE8 - THUMB - - -; Vector Table Mapped to Address 0 at Reset - AREA RESET, DATA, READONLY - EXPORT __Vectors - EXPORT __Vectors_End - EXPORT __Vectors_Size - -__Vectors DCD __initial_sp ; Top of Stack - DCD Reset_Handler ; Reset Handler - DCD NMI_Handler ; NMI Handler - DCD HardFault_Handler ; Hard Fault Handler - DCD MemManage_Handler ; MPU Fault Handler - DCD BusFault_Handler ; Bus Fault Handler - DCD UsageFault_Handler ; Usage Fault Handler - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SVC_Handler ; SVCall Handler - DCD DebugMon_Handler ; Debug Monitor Handler - DCD 0 ; Reserved - DCD PendSV_Handler ; PendSV Handler - DCD SysTick_Handler ; SysTick Handler - - ; External Interrupts - DCD WWDG_IRQHandler ; Window WatchDog - DCD PVD_IRQHandler ; PVD through EXTI Line detection - DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line - DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line - DCD FLASH_IRQHandler ; FLASH - DCD RCC_IRQHandler ; RCC - DCD EXTI0_IRQHandler ; EXTI Line0 - DCD EXTI1_IRQHandler ; EXTI Line1 - DCD EXTI2_IRQHandler ; EXTI Line2 - DCD EXTI3_IRQHandler ; EXTI Line3 - DCD EXTI4_IRQHandler ; EXTI Line4 - DCD DMA1_Stream0_IRQHandler ; DMA1 Stream 0 - DCD DMA1_Stream1_IRQHandler ; DMA1 Stream 1 - DCD DMA1_Stream2_IRQHandler ; DMA1 Stream 2 - DCD DMA1_Stream3_IRQHandler ; DMA1 Stream 3 - DCD DMA1_Stream4_IRQHandler ; DMA1 Stream 4 - DCD DMA1_Stream5_IRQHandler ; DMA1 Stream 5 - DCD DMA1_Stream6_IRQHandler ; DMA1 Stream 6 - DCD ADC_IRQHandler ; ADC1, ADC2 and ADC3s - DCD CAN1_TX_IRQHandler ; CAN1 TX - DCD CAN1_RX0_IRQHandler ; CAN1 RX0 - DCD CAN1_RX1_IRQHandler ; CAN1 RX1 - DCD CAN1_SCE_IRQHandler ; CAN1 SCE - DCD EXTI9_5_IRQHandler ; External Line[9:5]s - DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 - DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 - DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 - DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare - DCD TIM2_IRQHandler ; TIM2 - DCD TIM3_IRQHandler ; TIM3 - DCD TIM4_IRQHandler ; TIM4 - DCD I2C1_EV_IRQHandler ; I2C1 Event - DCD I2C1_ER_IRQHandler ; I2C1 Error - DCD I2C2_EV_IRQHandler ; I2C2 Event - DCD I2C2_ER_IRQHandler ; I2C2 Error - DCD SPI1_IRQHandler ; SPI1 - DCD SPI2_IRQHandler ; SPI2 - DCD USART1_IRQHandler ; USART1 - DCD USART2_IRQHandler ; USART2 - DCD USART3_IRQHandler ; USART3 - DCD EXTI15_10_IRQHandler ; External Line[15:10]s - DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line - DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line - DCD TIM8_BRK_TIM12_IRQHandler ; TIM8 Break and TIM12 - DCD TIM8_UP_TIM13_IRQHandler ; TIM8 Update and TIM13 - DCD TIM8_TRG_COM_TIM14_IRQHandler ; TIM8 Trigger and Commutation and TIM14 - DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare - DCD DMA1_Stream7_IRQHandler ; DMA1 Stream7 - DCD FMC_IRQHandler ; FMC - DCD SDIO_IRQHandler ; SDIO - DCD TIM5_IRQHandler ; TIM5 - DCD SPI3_IRQHandler ; SPI3 - DCD UART4_IRQHandler ; UART4 - DCD UART5_IRQHandler ; UART5 - DCD TIM6_DAC_IRQHandler ; TIM6 and DAC1&2 underrun errors - DCD TIM7_IRQHandler ; TIM7 - DCD DMA2_Stream0_IRQHandler ; DMA2 Stream 0 - DCD DMA2_Stream1_IRQHandler ; DMA2 Stream 1 - DCD DMA2_Stream2_IRQHandler ; DMA2 Stream 2 - DCD DMA2_Stream3_IRQHandler ; DMA2 Stream 3 - DCD DMA2_Stream4_IRQHandler ; DMA2 Stream 4 - DCD ETH_IRQHandler ; Ethernet - DCD ETH_WKUP_IRQHandler ; Ethernet Wakeup through EXTI line - DCD CAN2_TX_IRQHandler ; CAN2 TX - DCD CAN2_RX0_IRQHandler ; CAN2 RX0 - DCD CAN2_RX1_IRQHandler ; CAN2 RX1 - DCD CAN2_SCE_IRQHandler ; CAN2 SCE - DCD OTG_FS_IRQHandler ; USB OTG FS - DCD DMA2_Stream5_IRQHandler ; DMA2 Stream 5 - DCD DMA2_Stream6_IRQHandler ; DMA2 Stream 6 - DCD DMA2_Stream7_IRQHandler ; DMA2 Stream 7 - DCD USART6_IRQHandler ; USART6 - DCD I2C3_EV_IRQHandler ; I2C3 event - DCD I2C3_ER_IRQHandler ; I2C3 error - DCD OTG_HS_EP1_OUT_IRQHandler ; USB OTG HS End Point 1 Out - DCD OTG_HS_EP1_IN_IRQHandler ; USB OTG HS End Point 1 In - DCD OTG_HS_WKUP_IRQHandler ; USB OTG HS Wakeup through EXTI - DCD OTG_HS_IRQHandler ; USB OTG HS - DCD DCMI_IRQHandler ; DCMI - DCD CRYP_IRQHandler ; CRYP crypto - DCD HASH_RNG_IRQHandler ; Hash and Rng - DCD FPU_IRQHandler ; FPU - DCD UART7_IRQHandler ; UART7 - DCD UART8_IRQHandler ; UART8 - DCD SPI4_IRQHandler ; SPI4 - DCD SPI5_IRQHandler ; SPI5 - DCD SPI6_IRQHandler ; SPI6 - DCD SAI1_IRQHandler ; SAI1 - DCD LTDC_IRQHandler ; LTDC - DCD LTDC_ER_IRQHandler ; LTDC error - DCD DMA2D_IRQHandler ; DMA2D - -__Vectors_End - -__Vectors_Size EQU __Vectors_End - __Vectors - - AREA |.text|, CODE, READONLY - -; Reset handler -Reset_Handler PROC - EXPORT Reset_Handler [WEAK] - IMPORT SystemInit - IMPORT __main - - LDR R0, =SystemInit - BLX R0 - LDR R0, =__main - BX R0 - ENDP - -; Dummy Exception Handlers (infinite loops which can be modified) - -NMI_Handler PROC - EXPORT NMI_Handler [WEAK] - B . - ENDP -HardFault_Handler\ - PROC - EXPORT HardFault_Handler [WEAK] - B . - ENDP -MemManage_Handler\ - PROC - EXPORT MemManage_Handler [WEAK] - B . - ENDP -BusFault_Handler\ - PROC - EXPORT BusFault_Handler [WEAK] - B . - ENDP -UsageFault_Handler\ - PROC - EXPORT UsageFault_Handler [WEAK] - B . - ENDP -SVC_Handler PROC - EXPORT SVC_Handler [WEAK] - B . - ENDP -DebugMon_Handler\ - PROC - EXPORT DebugMon_Handler [WEAK] - B . - ENDP -PendSV_Handler PROC - EXPORT PendSV_Handler [WEAK] - B . - ENDP -SysTick_Handler PROC - EXPORT SysTick_Handler [WEAK] - B . - ENDP - -Default_Handler PROC - - EXPORT WWDG_IRQHandler [WEAK] - EXPORT PVD_IRQHandler [WEAK] - EXPORT TAMP_STAMP_IRQHandler [WEAK] - EXPORT RTC_WKUP_IRQHandler [WEAK] - EXPORT FLASH_IRQHandler [WEAK] - EXPORT RCC_IRQHandler [WEAK] - EXPORT EXTI0_IRQHandler [WEAK] - EXPORT EXTI1_IRQHandler [WEAK] - EXPORT EXTI2_IRQHandler [WEAK] - EXPORT EXTI3_IRQHandler [WEAK] - EXPORT EXTI4_IRQHandler [WEAK] - EXPORT DMA1_Stream0_IRQHandler [WEAK] - EXPORT DMA1_Stream1_IRQHandler [WEAK] - EXPORT DMA1_Stream2_IRQHandler [WEAK] - EXPORT DMA1_Stream3_IRQHandler [WEAK] - EXPORT DMA1_Stream4_IRQHandler [WEAK] - EXPORT DMA1_Stream5_IRQHandler [WEAK] - EXPORT DMA1_Stream6_IRQHandler [WEAK] - EXPORT ADC_IRQHandler [WEAK] - EXPORT CAN1_TX_IRQHandler [WEAK] - EXPORT CAN1_RX0_IRQHandler [WEAK] - EXPORT CAN1_RX1_IRQHandler [WEAK] - EXPORT CAN1_SCE_IRQHandler [WEAK] - EXPORT EXTI9_5_IRQHandler [WEAK] - EXPORT TIM1_BRK_TIM9_IRQHandler [WEAK] - EXPORT TIM1_UP_TIM10_IRQHandler [WEAK] - EXPORT TIM1_TRG_COM_TIM11_IRQHandler [WEAK] - EXPORT TIM1_CC_IRQHandler [WEAK] - EXPORT TIM2_IRQHandler [WEAK] - EXPORT TIM3_IRQHandler [WEAK] - EXPORT TIM4_IRQHandler [WEAK] - EXPORT I2C1_EV_IRQHandler [WEAK] - EXPORT I2C1_ER_IRQHandler [WEAK] - EXPORT I2C2_EV_IRQHandler [WEAK] - EXPORT I2C2_ER_IRQHandler [WEAK] - EXPORT SPI1_IRQHandler [WEAK] - EXPORT SPI2_IRQHandler [WEAK] - EXPORT USART1_IRQHandler [WEAK] - EXPORT USART2_IRQHandler [WEAK] - EXPORT USART3_IRQHandler [WEAK] - EXPORT EXTI15_10_IRQHandler [WEAK] - EXPORT RTC_Alarm_IRQHandler [WEAK] - EXPORT OTG_FS_WKUP_IRQHandler [WEAK] - EXPORT TIM8_BRK_TIM12_IRQHandler [WEAK] - EXPORT TIM8_UP_TIM13_IRQHandler [WEAK] - EXPORT TIM8_TRG_COM_TIM14_IRQHandler [WEAK] - EXPORT TIM8_CC_IRQHandler [WEAK] - EXPORT DMA1_Stream7_IRQHandler [WEAK] - EXPORT FMC_IRQHandler [WEAK] - EXPORT SDIO_IRQHandler [WEAK] - EXPORT TIM5_IRQHandler [WEAK] - EXPORT SPI3_IRQHandler [WEAK] - EXPORT UART4_IRQHandler [WEAK] - EXPORT UART5_IRQHandler [WEAK] - EXPORT TIM6_DAC_IRQHandler [WEAK] - EXPORT TIM7_IRQHandler [WEAK] - EXPORT DMA2_Stream0_IRQHandler [WEAK] - EXPORT DMA2_Stream1_IRQHandler [WEAK] - EXPORT DMA2_Stream2_IRQHandler [WEAK] - EXPORT DMA2_Stream3_IRQHandler [WEAK] - EXPORT DMA2_Stream4_IRQHandler [WEAK] - EXPORT ETH_IRQHandler [WEAK] - EXPORT ETH_WKUP_IRQHandler [WEAK] - EXPORT CAN2_TX_IRQHandler [WEAK] - EXPORT CAN2_RX0_IRQHandler [WEAK] - EXPORT CAN2_RX1_IRQHandler [WEAK] - EXPORT CAN2_SCE_IRQHandler [WEAK] - EXPORT OTG_FS_IRQHandler [WEAK] - EXPORT DMA2_Stream5_IRQHandler [WEAK] - EXPORT DMA2_Stream6_IRQHandler [WEAK] - EXPORT DMA2_Stream7_IRQHandler [WEAK] - EXPORT USART6_IRQHandler [WEAK] - EXPORT I2C3_EV_IRQHandler [WEAK] - EXPORT I2C3_ER_IRQHandler [WEAK] - EXPORT OTG_HS_EP1_OUT_IRQHandler [WEAK] - EXPORT OTG_HS_EP1_IN_IRQHandler [WEAK] - EXPORT OTG_HS_WKUP_IRQHandler [WEAK] - EXPORT OTG_HS_IRQHandler [WEAK] - EXPORT DCMI_IRQHandler [WEAK] - EXPORT CRYP_IRQHandler [WEAK] - EXPORT HASH_RNG_IRQHandler [WEAK] - EXPORT FPU_IRQHandler [WEAK] - EXPORT UART7_IRQHandler [WEAK] - EXPORT UART8_IRQHandler [WEAK] - EXPORT SPI4_IRQHandler [WEAK] - EXPORT SPI5_IRQHandler [WEAK] - EXPORT SPI6_IRQHandler [WEAK] - EXPORT SAI1_IRQHandler [WEAK] - EXPORT LTDC_IRQHandler [WEAK] - EXPORT LTDC_ER_IRQHandler [WEAK] - EXPORT DMA2D_IRQHandler [WEAK] - -WWDG_IRQHandler -PVD_IRQHandler -TAMP_STAMP_IRQHandler -RTC_WKUP_IRQHandler -FLASH_IRQHandler -RCC_IRQHandler -EXTI0_IRQHandler -EXTI1_IRQHandler -EXTI2_IRQHandler -EXTI3_IRQHandler -EXTI4_IRQHandler -DMA1_Stream0_IRQHandler -DMA1_Stream1_IRQHandler -DMA1_Stream2_IRQHandler -DMA1_Stream3_IRQHandler -DMA1_Stream4_IRQHandler -DMA1_Stream5_IRQHandler -DMA1_Stream6_IRQHandler -ADC_IRQHandler -CAN1_TX_IRQHandler -CAN1_RX0_IRQHandler -CAN1_RX1_IRQHandler -CAN1_SCE_IRQHandler -EXTI9_5_IRQHandler -TIM1_BRK_TIM9_IRQHandler -TIM1_UP_TIM10_IRQHandler -TIM1_TRG_COM_TIM11_IRQHandler -TIM1_CC_IRQHandler -TIM2_IRQHandler -TIM3_IRQHandler -TIM4_IRQHandler -I2C1_EV_IRQHandler -I2C1_ER_IRQHandler -I2C2_EV_IRQHandler -I2C2_ER_IRQHandler -SPI1_IRQHandler -SPI2_IRQHandler -USART1_IRQHandler -USART2_IRQHandler -USART3_IRQHandler -EXTI15_10_IRQHandler -RTC_Alarm_IRQHandler -OTG_FS_WKUP_IRQHandler -TIM8_BRK_TIM12_IRQHandler -TIM8_UP_TIM13_IRQHandler -TIM8_TRG_COM_TIM14_IRQHandler -TIM8_CC_IRQHandler -DMA1_Stream7_IRQHandler -FMC_IRQHandler -SDIO_IRQHandler -TIM5_IRQHandler -SPI3_IRQHandler -UART4_IRQHandler -UART5_IRQHandler -TIM6_DAC_IRQHandler -TIM7_IRQHandler -DMA2_Stream0_IRQHandler -DMA2_Stream1_IRQHandler -DMA2_Stream2_IRQHandler -DMA2_Stream3_IRQHandler -DMA2_Stream4_IRQHandler -ETH_IRQHandler -ETH_WKUP_IRQHandler -CAN2_TX_IRQHandler -CAN2_RX0_IRQHandler -CAN2_RX1_IRQHandler -CAN2_SCE_IRQHandler -OTG_FS_IRQHandler -DMA2_Stream5_IRQHandler -DMA2_Stream6_IRQHandler -DMA2_Stream7_IRQHandler -USART6_IRQHandler -I2C3_EV_IRQHandler -I2C3_ER_IRQHandler -OTG_HS_EP1_OUT_IRQHandler -OTG_HS_EP1_IN_IRQHandler -OTG_HS_WKUP_IRQHandler -OTG_HS_IRQHandler -DCMI_IRQHandler -CRYP_IRQHandler -HASH_RNG_IRQHandler -FPU_IRQHandler -UART7_IRQHandler -UART8_IRQHandler -SPI4_IRQHandler -SPI5_IRQHandler -SPI6_IRQHandler -SAI1_IRQHandler -LTDC_IRQHandler -LTDC_ER_IRQHandler -DMA2D_IRQHandler - B . - - ENDP - - ALIGN - -;******************************************************************************* -; User Stack and Heap initialization -;******************************************************************************* - IF :DEF:__MICROLIB - - EXPORT __initial_sp - EXPORT __heap_base - EXPORT __heap_limit - - ELSE - - IMPORT __use_two_region_memory - EXPORT __user_initial_stackheap - -__user_initial_stackheap - - LDR R0, = Heap_Mem - LDR R1, =(Stack_Mem + Stack_Size) - LDR R2, = (Heap_Mem + Heap_Size) - LDR R3, = Stack_Mem - BX LR - - ALIGN - - ENDIF - - END - -;************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE***** diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f446xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f446xx.s deleted file mode 100644 index 598ae5feb4..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f446xx.s +++ /dev/null @@ -1,462 +0,0 @@ -;******************** (C) COPYRIGHT 2015 STMicroelectronics ******************** -;* File Name : startup_stm32f446xx.s -;* Author : MCD Application Team -;* @version : V1.6.1 -;* @date : 21-October-2015 -;* Description : STM32F446x devices vector table for MDK-ARM toolchain. -;* This module performs: -;* - Set the initial SP -;* - Set the initial PC == Reset_Handler -;* - Set the vector table entries with the exceptions ISR address -;* After Reset the CortexM4 processor is in Thread mode, -;* priority is Privileged, and the Stack is set to Main. -;* <<< Use Configuration Wizard in Context Menu >>> -;******************************************************************************* -; -;* Redistribution and use in source and binary forms, with or without modification, -;* are permitted provided that the following conditions are met: -;* 1. Redistributions of source code must retain the above copyright notice, -;* this list of conditions and the following disclaimer. -;* 2. Redistributions in binary form must reproduce the above copyright notice, -;* this list of conditions and the following disclaimer in the documentation -;* and/or other materials provided with the distribution. -;* 3. Neither the name of STMicroelectronics nor the names of its contributors -;* may be used to endorse or promote products derived from this software -;* without specific prior written permission. -;* -;* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -;* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE -;* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL -;* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -;* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -;* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, -;* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE -;* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -; -;******************************************************************************* - -; Amount of memory (in bytes) allocated for Stack -; Tailor this value to your application needs -; Stack Configuration -; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> -; - -Stack_Size EQU 0x00000400 - - AREA STACK, NOINIT, READWRITE, ALIGN=3 -Stack_Mem SPACE Stack_Size -__initial_sp - - -; Heap Configuration -; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> -; - -Heap_Size EQU 0x00000200 - - AREA HEAP, NOINIT, READWRITE, ALIGN=3 -__heap_base -Heap_Mem SPACE Heap_Size -__heap_limit - - PRESERVE8 - THUMB - - -; Vector Table Mapped to Address 0 at Reset - AREA RESET, DATA, READONLY - EXPORT __Vectors - EXPORT __Vectors_End - EXPORT __Vectors_Size - -__Vectors DCD __initial_sp ; Top of Stack - DCD Reset_Handler ; Reset Handler - DCD NMI_Handler ; NMI Handler - DCD HardFault_Handler ; Hard Fault Handler - DCD MemManage_Handler ; MPU Fault Handler - DCD BusFault_Handler ; Bus Fault Handler - DCD UsageFault_Handler ; Usage Fault Handler - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SVC_Handler ; SVCall Handler - DCD DebugMon_Handler ; Debug Monitor Handler - DCD 0 ; Reserved - DCD PendSV_Handler ; PendSV Handler - DCD SysTick_Handler ; SysTick Handler - - ; External Interrupts - DCD WWDG_IRQHandler ; Window WatchDog - DCD PVD_IRQHandler ; PVD through EXTI Line detection - DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line - DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line - DCD FLASH_IRQHandler ; FLASH - DCD RCC_IRQHandler ; RCC - DCD EXTI0_IRQHandler ; EXTI Line0 - DCD EXTI1_IRQHandler ; EXTI Line1 - DCD EXTI2_IRQHandler ; EXTI Line2 - DCD EXTI3_IRQHandler ; EXTI Line3 - DCD EXTI4_IRQHandler ; EXTI Line4 - DCD DMA1_Stream0_IRQHandler ; DMA1 Stream 0 - DCD DMA1_Stream1_IRQHandler ; DMA1 Stream 1 - DCD DMA1_Stream2_IRQHandler ; DMA1 Stream 2 - DCD DMA1_Stream3_IRQHandler ; DMA1 Stream 3 - DCD DMA1_Stream4_IRQHandler ; DMA1 Stream 4 - DCD DMA1_Stream5_IRQHandler ; DMA1 Stream 5 - DCD DMA1_Stream6_IRQHandler ; DMA1 Stream 6 - DCD ADC_IRQHandler ; ADC1, ADC2 and ADC3s - DCD CAN1_TX_IRQHandler ; CAN1 TX - DCD CAN1_RX0_IRQHandler ; CAN1 RX0 - DCD CAN1_RX1_IRQHandler ; CAN1 RX1 - DCD CAN1_SCE_IRQHandler ; CAN1 SCE - DCD EXTI9_5_IRQHandler ; External Line[9:5]s - DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 - DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 - DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 - DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare - DCD TIM2_IRQHandler ; TIM2 - DCD TIM3_IRQHandler ; TIM3 - DCD TIM4_IRQHandler ; TIM4 - DCD I2C1_EV_IRQHandler ; I2C1 Event - DCD I2C1_ER_IRQHandler ; I2C1 Error - DCD I2C2_EV_IRQHandler ; I2C2 Event - DCD I2C2_ER_IRQHandler ; I2C2 Error - DCD SPI1_IRQHandler ; SPI1 - DCD SPI2_IRQHandler ; SPI2 - DCD USART1_IRQHandler ; USART1 - DCD USART2_IRQHandler ; USART2 - DCD USART3_IRQHandler ; USART3 - DCD EXTI15_10_IRQHandler ; External Line[15:10]s - DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line - DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line - DCD TIM8_BRK_TIM12_IRQHandler ; TIM8 Break and TIM12 - DCD TIM8_UP_TIM13_IRQHandler ; TIM8 Update and TIM13 - DCD TIM8_TRG_COM_TIM14_IRQHandler ; TIM8 Trigger and Commutation and TIM14 - DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare - DCD DMA1_Stream7_IRQHandler ; DMA1 Stream7 - DCD FMC_IRQHandler ; FMC - DCD SDIO_IRQHandler ; SDIO - DCD TIM5_IRQHandler ; TIM5 - DCD SPI3_IRQHandler ; SPI3 - DCD UART4_IRQHandler ; UART4 - DCD UART5_IRQHandler ; UART5 - DCD TIM6_DAC_IRQHandler ; TIM6 and DAC1&2 underrun errors - DCD TIM7_IRQHandler ; TIM7 - DCD DMA2_Stream0_IRQHandler ; DMA2 Stream 0 - DCD DMA2_Stream1_IRQHandler ; DMA2 Stream 1 - DCD DMA2_Stream2_IRQHandler ; DMA2 Stream 2 - DCD DMA2_Stream3_IRQHandler ; DMA2 Stream 3 - DCD DMA2_Stream4_IRQHandler ; DMA2 Stream 4 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD CAN2_TX_IRQHandler ; CAN2 TX - DCD CAN2_RX0_IRQHandler ; CAN2 RX0 - DCD CAN2_RX1_IRQHandler ; CAN2 RX1 - DCD CAN2_SCE_IRQHandler ; CAN2 SCE - DCD OTG_FS_IRQHandler ; USB OTG FS - DCD DMA2_Stream5_IRQHandler ; DMA2 Stream 5 - DCD DMA2_Stream6_IRQHandler ; DMA2 Stream 6 - DCD DMA2_Stream7_IRQHandler ; DMA2 Stream 7 - DCD USART6_IRQHandler ; USART6 - DCD I2C3_EV_IRQHandler ; I2C3 event - DCD I2C3_ER_IRQHandler ; I2C3 error - DCD OTG_HS_EP1_OUT_IRQHandler ; USB OTG HS End Point 1 Out - DCD OTG_HS_EP1_IN_IRQHandler ; USB OTG HS End Point 1 In - DCD OTG_HS_WKUP_IRQHandler ; USB OTG HS Wakeup through EXTI - DCD OTG_HS_IRQHandler ; USB OTG HS - DCD DCMI_IRQHandler ; DCMI - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD FPU_IRQHandler ; FPU - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SPI4_IRQHandler ; SPI4 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SAI1_IRQHandler ; SAI1 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SAI2_IRQHandler ; SAI2 - DCD QuadSPI_IRQHandler ; QuadSPI - DCD CEC_IRQHandler ; CEC - DCD SPDIF_RX_IRQHandler ; SPDIF RX - DCD FMPI2C1_Event_IRQHandler ; I2C 4 Event - DCD FMPI2C1_Error_IRQHandler ; I2C 4 Error -__Vectors_End - -__Vectors_Size EQU __Vectors_End - __Vectors - - AREA |.text|, CODE, READONLY - -; Reset handler -Reset_Handler PROC - EXPORT Reset_Handler [WEAK] - IMPORT SystemInit - IMPORT __main - - LDR R0, =SystemInit - BLX R0 - LDR R0, =__main - BX R0 - ENDP - -; Dummy Exception Handlers (infinite loops which can be modified) - -NMI_Handler PROC - EXPORT NMI_Handler [WEAK] - B . - ENDP -HardFault_Handler\ - PROC - EXPORT HardFault_Handler [WEAK] - B . - ENDP -MemManage_Handler\ - PROC - EXPORT MemManage_Handler [WEAK] - B . - ENDP -BusFault_Handler\ - PROC - EXPORT BusFault_Handler [WEAK] - B . - ENDP -UsageFault_Handler\ - PROC - EXPORT UsageFault_Handler [WEAK] - B . - ENDP -SVC_Handler PROC - EXPORT SVC_Handler [WEAK] - B . - ENDP -DebugMon_Handler\ - PROC - EXPORT DebugMon_Handler [WEAK] - B . - ENDP -PendSV_Handler PROC - EXPORT PendSV_Handler [WEAK] - B . - ENDP -SysTick_Handler PROC - EXPORT SysTick_Handler [WEAK] - B . - ENDP - -Default_Handler PROC - - EXPORT WWDG_IRQHandler [WEAK] - EXPORT PVD_IRQHandler [WEAK] - EXPORT TAMP_STAMP_IRQHandler [WEAK] - EXPORT RTC_WKUP_IRQHandler [WEAK] - EXPORT FLASH_IRQHandler [WEAK] - EXPORT RCC_IRQHandler [WEAK] - EXPORT EXTI0_IRQHandler [WEAK] - EXPORT EXTI1_IRQHandler [WEAK] - EXPORT EXTI2_IRQHandler [WEAK] - EXPORT EXTI3_IRQHandler [WEAK] - EXPORT EXTI4_IRQHandler [WEAK] - EXPORT DMA1_Stream0_IRQHandler [WEAK] - EXPORT DMA1_Stream1_IRQHandler [WEAK] - EXPORT DMA1_Stream2_IRQHandler [WEAK] - EXPORT DMA1_Stream3_IRQHandler [WEAK] - EXPORT DMA1_Stream4_IRQHandler [WEAK] - EXPORT DMA1_Stream5_IRQHandler [WEAK] - EXPORT DMA1_Stream6_IRQHandler [WEAK] - EXPORT ADC_IRQHandler [WEAK] - EXPORT CAN1_TX_IRQHandler [WEAK] - EXPORT CAN1_RX0_IRQHandler [WEAK] - EXPORT CAN1_RX1_IRQHandler [WEAK] - EXPORT CAN1_SCE_IRQHandler [WEAK] - EXPORT EXTI9_5_IRQHandler [WEAK] - EXPORT TIM1_BRK_TIM9_IRQHandler [WEAK] - EXPORT TIM1_UP_TIM10_IRQHandler [WEAK] - EXPORT TIM1_TRG_COM_TIM11_IRQHandler [WEAK] - EXPORT TIM1_CC_IRQHandler [WEAK] - EXPORT TIM2_IRQHandler [WEAK] - EXPORT TIM3_IRQHandler [WEAK] - EXPORT TIM4_IRQHandler [WEAK] - EXPORT I2C1_EV_IRQHandler [WEAK] - EXPORT I2C1_ER_IRQHandler [WEAK] - EXPORT I2C2_EV_IRQHandler [WEAK] - EXPORT I2C2_ER_IRQHandler [WEAK] - EXPORT SPI1_IRQHandler [WEAK] - EXPORT SPI2_IRQHandler [WEAK] - EXPORT USART1_IRQHandler [WEAK] - EXPORT USART2_IRQHandler [WEAK] - EXPORT USART3_IRQHandler [WEAK] - EXPORT EXTI15_10_IRQHandler [WEAK] - EXPORT RTC_Alarm_IRQHandler [WEAK] - EXPORT OTG_FS_WKUP_IRQHandler [WEAK] - EXPORT TIM8_BRK_TIM12_IRQHandler [WEAK] - EXPORT TIM8_UP_TIM13_IRQHandler [WEAK] - EXPORT TIM8_TRG_COM_TIM14_IRQHandler [WEAK] - EXPORT TIM8_CC_IRQHandler [WEAK] - EXPORT DMA1_Stream7_IRQHandler [WEAK] - EXPORT FMC_IRQHandler [WEAK] - EXPORT SDIO_IRQHandler [WEAK] - EXPORT TIM5_IRQHandler [WEAK] - EXPORT SPI3_IRQHandler [WEAK] - EXPORT UART4_IRQHandler [WEAK] - EXPORT UART5_IRQHandler [WEAK] - EXPORT TIM6_DAC_IRQHandler [WEAK] - EXPORT TIM7_IRQHandler [WEAK] - EXPORT DMA2_Stream0_IRQHandler [WEAK] - EXPORT DMA2_Stream1_IRQHandler [WEAK] - EXPORT DMA2_Stream2_IRQHandler [WEAK] - EXPORT DMA2_Stream3_IRQHandler [WEAK] - EXPORT DMA2_Stream4_IRQHandler [WEAK] - EXPORT CAN2_TX_IRQHandler [WEAK] - EXPORT CAN2_RX0_IRQHandler [WEAK] - EXPORT CAN2_RX1_IRQHandler [WEAK] - EXPORT CAN2_SCE_IRQHandler [WEAK] - EXPORT OTG_FS_IRQHandler [WEAK] - EXPORT DMA2_Stream5_IRQHandler [WEAK] - EXPORT DMA2_Stream6_IRQHandler [WEAK] - EXPORT DMA2_Stream7_IRQHandler [WEAK] - EXPORT USART6_IRQHandler [WEAK] - EXPORT I2C3_EV_IRQHandler [WEAK] - EXPORT I2C3_ER_IRQHandler [WEAK] - EXPORT OTG_HS_EP1_OUT_IRQHandler [WEAK] - EXPORT OTG_HS_EP1_IN_IRQHandler [WEAK] - EXPORT OTG_HS_WKUP_IRQHandler [WEAK] - EXPORT OTG_HS_IRQHandler [WEAK] - EXPORT DCMI_IRQHandler [WEAK] - EXPORT FPU_IRQHandler [WEAK] - EXPORT SPI4_IRQHandler [WEAK] - EXPORT SAI1_IRQHandler [WEAK] - EXPORT SPI4_IRQHandler [WEAK] - EXPORT SAI1_IRQHandler [WEAK] - EXPORT SAI2_IRQHandler [WEAK] - EXPORT QuadSPI_IRQHandler [WEAK] - EXPORT CEC_IRQHandler [WEAK] - EXPORT SPDIF_RX_IRQHandler [WEAK] - EXPORT FMPI2C1_Event_IRQHandler [WEAK] - EXPORT FMPI2C1_Error_IRQHandler [WEAK] - -WWDG_IRQHandler -PVD_IRQHandler -TAMP_STAMP_IRQHandler -RTC_WKUP_IRQHandler -FLASH_IRQHandler -RCC_IRQHandler -EXTI0_IRQHandler -EXTI1_IRQHandler -EXTI2_IRQHandler -EXTI3_IRQHandler -EXTI4_IRQHandler -DMA1_Stream0_IRQHandler -DMA1_Stream1_IRQHandler -DMA1_Stream2_IRQHandler -DMA1_Stream3_IRQHandler -DMA1_Stream4_IRQHandler -DMA1_Stream5_IRQHandler -DMA1_Stream6_IRQHandler -ADC_IRQHandler -CAN1_TX_IRQHandler -CAN1_RX0_IRQHandler -CAN1_RX1_IRQHandler -CAN1_SCE_IRQHandler -EXTI9_5_IRQHandler -TIM1_BRK_TIM9_IRQHandler -TIM1_UP_TIM10_IRQHandler -TIM1_TRG_COM_TIM11_IRQHandler -TIM1_CC_IRQHandler -TIM2_IRQHandler -TIM3_IRQHandler -TIM4_IRQHandler -I2C1_EV_IRQHandler -I2C1_ER_IRQHandler -I2C2_EV_IRQHandler -I2C2_ER_IRQHandler -SPI1_IRQHandler -SPI2_IRQHandler -USART1_IRQHandler -USART2_IRQHandler -USART3_IRQHandler -EXTI15_10_IRQHandler -RTC_Alarm_IRQHandler -OTG_FS_WKUP_IRQHandler -TIM8_BRK_TIM12_IRQHandler -TIM8_UP_TIM13_IRQHandler -TIM8_TRG_COM_TIM14_IRQHandler -TIM8_CC_IRQHandler -DMA1_Stream7_IRQHandler -FMC_IRQHandler -SDIO_IRQHandler -TIM5_IRQHandler -SPI3_IRQHandler -UART4_IRQHandler -UART5_IRQHandler -TIM6_DAC_IRQHandler -TIM7_IRQHandler -DMA2_Stream0_IRQHandler -DMA2_Stream1_IRQHandler -DMA2_Stream2_IRQHandler -DMA2_Stream3_IRQHandler -DMA2_Stream4_IRQHandler -CAN2_TX_IRQHandler -CAN2_RX0_IRQHandler -CAN2_RX1_IRQHandler -CAN2_SCE_IRQHandler -OTG_FS_IRQHandler -DMA2_Stream5_IRQHandler -DMA2_Stream6_IRQHandler -DMA2_Stream7_IRQHandler -USART6_IRQHandler -I2C3_EV_IRQHandler -I2C3_ER_IRQHandler -OTG_HS_EP1_OUT_IRQHandler -OTG_HS_EP1_IN_IRQHandler -OTG_HS_WKUP_IRQHandler -OTG_HS_IRQHandler -DCMI_IRQHandler -FPU_IRQHandler -SPI4_IRQHandler -SAI1_IRQHandler -SAI2_IRQHandler -QuadSPI_IRQHandler -CEC_IRQHandler -SPDIF_RX_IRQHandler -FMPI2C1_Event_IRQHandler -FMPI2C1_Error_IRQHandler - B . - - ENDP - - ALIGN - -;******************************************************************************* -; User Stack and Heap initialization -;******************************************************************************* - IF :DEF:__MICROLIB - - EXPORT __initial_sp - EXPORT __heap_base - EXPORT __heap_limit - - ELSE - - IMPORT __use_two_region_memory - EXPORT __user_initial_stackheap - -__user_initial_stackheap - - LDR R0, = Heap_Mem - LDR R1, =(Stack_Mem + Stack_Size) - LDR R2, = (Heap_Mem + Heap_Size) - LDR R3, = Stack_Mem - BX LR - - ALIGN - - ENDIF - - END - -;************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE***** diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f469_479xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f469_479xx.s deleted file mode 100644 index d937deb35a..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/arm/startup_stm32f469_479xx.s +++ /dev/null @@ -1,463 +0,0 @@ -;******************** (C) COPYRIGHT 2015 STMicroelectronics ******************** -;* File Name : startup_stm32f469_479xx.s -;* Author : MCD Application Team -;* @version : V1.6.1 -;* @date : 21-October-2015 -;* Description : STM32F469xx/479xx devices vector table for MDK-ARM toolchain. -;* This module performs: -;* - Set the initial SP -;* - Set the initial PC == Reset_Handler -;* - Set the vector table entries with the exceptions ISR address -;* - Branches to __main in the C library (which eventually -;* calls main()). -;* After Reset the CortexM4 processor is in Thread mode, -;* priority is Privileged, and the Stack is set to Main. -;* <<< Use Configuration Wizard in Context Menu >>> -;******************************************************************************* -; -; Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); -; You may not use this file except in compliance with the License. -; You may obtain a copy of the License at: -; -; http://www.st.com/software_license_agreement_liberty_v2 -; -; Unless required by applicable law or agreed to in writing, software -; distributed under the License is distributed on an "AS IS" BASIS, -; WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -; See the License for the specific language governing permissions and -; limitations under the License. -; -;******************************************************************************* - -; Amount of memory (in bytes) allocated for Stack -; Tailor this value to your application needs -; Stack Configuration -; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> -; - -Stack_Size EQU 0x00000400 - - AREA STACK, NOINIT, READWRITE, ALIGN=3 -Stack_Mem SPACE Stack_Size -__initial_sp - - -; Heap Configuration -; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> -; - -Heap_Size EQU 0x00000200 - - AREA HEAP, NOINIT, READWRITE, ALIGN=3 -__heap_base -Heap_Mem SPACE Heap_Size -__heap_limit - - PRESERVE8 - THUMB - - -; Vector Table Mapped to Address 0 at Reset - AREA RESET, DATA, READONLY - EXPORT __Vectors - EXPORT __Vectors_End - EXPORT __Vectors_Size - -__Vectors DCD __initial_sp ; Top of Stack - DCD Reset_Handler ; Reset Handler - DCD NMI_Handler ; NMI Handler - DCD HardFault_Handler ; Hard Fault Handler - DCD MemManage_Handler ; MPU Fault Handler - DCD BusFault_Handler ; Bus Fault Handler - DCD UsageFault_Handler ; Usage Fault Handler - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SVC_Handler ; SVCall Handler - DCD DebugMon_Handler ; Debug Monitor Handler - DCD 0 ; Reserved - DCD PendSV_Handler ; PendSV Handler - DCD SysTick_Handler ; SysTick Handler - - ; External Interrupts - DCD WWDG_IRQHandler ; Window WatchDog - DCD PVD_IRQHandler ; PVD through EXTI Line detection - DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line - DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line - DCD FLASH_IRQHandler ; FLASH - DCD RCC_IRQHandler ; RCC - DCD EXTI0_IRQHandler ; EXTI Line0 - DCD EXTI1_IRQHandler ; EXTI Line1 - DCD EXTI2_IRQHandler ; EXTI Line2 - DCD EXTI3_IRQHandler ; EXTI Line3 - DCD EXTI4_IRQHandler ; EXTI Line4 - DCD DMA1_Stream0_IRQHandler ; DMA1 Stream 0 - DCD DMA1_Stream1_IRQHandler ; DMA1 Stream 1 - DCD DMA1_Stream2_IRQHandler ; DMA1 Stream 2 - DCD DMA1_Stream3_IRQHandler ; DMA1 Stream 3 - DCD DMA1_Stream4_IRQHandler ; DMA1 Stream 4 - DCD DMA1_Stream5_IRQHandler ; DMA1 Stream 5 - DCD DMA1_Stream6_IRQHandler ; DMA1 Stream 6 - DCD ADC_IRQHandler ; ADC1, ADC2 and ADC3s - DCD CAN1_TX_IRQHandler ; CAN1 TX - DCD CAN1_RX0_IRQHandler ; CAN1 RX0 - DCD CAN1_RX1_IRQHandler ; CAN1 RX1 - DCD CAN1_SCE_IRQHandler ; CAN1 SCE - DCD EXTI9_5_IRQHandler ; External Line[9:5]s - DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 - DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 - DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 - DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare - DCD TIM2_IRQHandler ; TIM2 - DCD TIM3_IRQHandler ; TIM3 - DCD TIM4_IRQHandler ; TIM4 - DCD I2C1_EV_IRQHandler ; I2C1 Event - DCD I2C1_ER_IRQHandler ; I2C1 Error - DCD I2C2_EV_IRQHandler ; I2C2 Event - DCD I2C2_ER_IRQHandler ; I2C2 Error - DCD SPI1_IRQHandler ; SPI1 - DCD SPI2_IRQHandler ; SPI2 - DCD USART1_IRQHandler ; USART1 - DCD USART2_IRQHandler ; USART2 - DCD USART3_IRQHandler ; USART3 - DCD EXTI15_10_IRQHandler ; External Line[15:10]s - DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line - DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line - DCD TIM8_BRK_TIM12_IRQHandler ; TIM8 Break and TIM12 - DCD TIM8_UP_TIM13_IRQHandler ; TIM8 Update and TIM13 - DCD TIM8_TRG_COM_TIM14_IRQHandler ; TIM8 Trigger and Commutation and TIM14 - DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare - DCD DMA1_Stream7_IRQHandler ; DMA1 Stream7 - DCD FMC_IRQHandler ; FMC - DCD SDIO_IRQHandler ; SDIO - DCD TIM5_IRQHandler ; TIM5 - DCD SPI3_IRQHandler ; SPI3 - DCD UART4_IRQHandler ; UART4 - DCD UART5_IRQHandler ; UART5 - DCD TIM6_DAC_IRQHandler ; TIM6 and DAC1&2 underrun errors - DCD TIM7_IRQHandler ; TIM7 - DCD DMA2_Stream0_IRQHandler ; DMA2 Stream 0 - DCD DMA2_Stream1_IRQHandler ; DMA2 Stream 1 - DCD DMA2_Stream2_IRQHandler ; DMA2 Stream 2 - DCD DMA2_Stream3_IRQHandler ; DMA2 Stream 3 - DCD DMA2_Stream4_IRQHandler ; DMA2 Stream 4 - DCD ETH_IRQHandler ; Ethernet - DCD ETH_WKUP_IRQHandler ; Ethernet Wakeup through EXTI line - DCD CAN2_TX_IRQHandler ; CAN2 TX - DCD CAN2_RX0_IRQHandler ; CAN2 RX0 - DCD CAN2_RX1_IRQHandler ; CAN2 RX1 - DCD CAN2_SCE_IRQHandler ; CAN2 SCE - DCD OTG_FS_IRQHandler ; USB OTG FS - DCD DMA2_Stream5_IRQHandler ; DMA2 Stream 5 - DCD DMA2_Stream6_IRQHandler ; DMA2 Stream 6 - DCD DMA2_Stream7_IRQHandler ; DMA2 Stream 7 - DCD USART6_IRQHandler ; USART6 - DCD I2C3_EV_IRQHandler ; I2C3 event - DCD I2C3_ER_IRQHandler ; I2C3 error - DCD OTG_HS_EP1_OUT_IRQHandler ; USB OTG HS End Point 1 Out - DCD OTG_HS_EP1_IN_IRQHandler ; USB OTG HS End Point 1 In - DCD OTG_HS_WKUP_IRQHandler ; USB OTG HS Wakeup through EXTI - DCD OTG_HS_IRQHandler ; USB OTG HS - DCD DCMI_IRQHandler ; DCMI - DCD CRYP_IRQHandler ; CRYPTO - DCD HASH_RNG_IRQHandler ; Hash and Rng - DCD FPU_IRQHandler ; FPU - DCD UART7_IRQHandler ; UART7 - DCD UART8_IRQHandler ; UART8 - DCD SPI4_IRQHandler ; SPI4 - DCD SPI5_IRQHandler ; SPI5 - DCD SPI6_IRQHandler ; SPI6 - DCD SAI1_IRQHandler ; SAI1 - DCD LTDC_IRQHandler ; LTDC - DCD LTDC_ER_IRQHandler ; LTDC error - DCD DMA2D_IRQHandler ; DMA2D - DCD QUADSPI_IRQHandler ; QUADSPI - DCD DSI_IRQHandler ; DSI - -__Vectors_End - -__Vectors_Size EQU __Vectors_End - __Vectors - - AREA |.text|, CODE, READONLY - -; Reset handler -Reset_Handler PROC - EXPORT Reset_Handler [WEAK] - IMPORT SystemInit - IMPORT __main - - LDR R0, =SystemInit - BLX R0 - LDR R0, =__main - BX R0 - ENDP - -; Dummy Exception Handlers (infinite loops which can be modified) - -NMI_Handler PROC - EXPORT NMI_Handler [WEAK] - B . - ENDP -HardFault_Handler\ - PROC - EXPORT HardFault_Handler [WEAK] - B . - ENDP -MemManage_Handler\ - PROC - EXPORT MemManage_Handler [WEAK] - B . - ENDP -BusFault_Handler\ - PROC - EXPORT BusFault_Handler [WEAK] - B . - ENDP -UsageFault_Handler\ - PROC - EXPORT UsageFault_Handler [WEAK] - B . - ENDP -SVC_Handler PROC - EXPORT SVC_Handler [WEAK] - B . - ENDP -DebugMon_Handler\ - PROC - EXPORT DebugMon_Handler [WEAK] - B . - ENDP -PendSV_Handler PROC - EXPORT PendSV_Handler [WEAK] - B . - ENDP -SysTick_Handler PROC - EXPORT SysTick_Handler [WEAK] - B . - ENDP - -Default_Handler PROC - - EXPORT WWDG_IRQHandler [WEAK] - EXPORT PVD_IRQHandler [WEAK] - EXPORT TAMP_STAMP_IRQHandler [WEAK] - EXPORT RTC_WKUP_IRQHandler [WEAK] - EXPORT FLASH_IRQHandler [WEAK] - EXPORT RCC_IRQHandler [WEAK] - EXPORT EXTI0_IRQHandler [WEAK] - EXPORT EXTI1_IRQHandler [WEAK] - EXPORT EXTI2_IRQHandler [WEAK] - EXPORT EXTI3_IRQHandler [WEAK] - EXPORT EXTI4_IRQHandler [WEAK] - EXPORT DMA1_Stream0_IRQHandler [WEAK] - EXPORT DMA1_Stream1_IRQHandler [WEAK] - EXPORT DMA1_Stream2_IRQHandler [WEAK] - EXPORT DMA1_Stream3_IRQHandler [WEAK] - EXPORT DMA1_Stream4_IRQHandler [WEAK] - EXPORT DMA1_Stream5_IRQHandler [WEAK] - EXPORT DMA1_Stream6_IRQHandler [WEAK] - EXPORT ADC_IRQHandler [WEAK] - EXPORT CAN1_TX_IRQHandler [WEAK] - EXPORT CAN1_RX0_IRQHandler [WEAK] - EXPORT CAN1_RX1_IRQHandler [WEAK] - EXPORT CAN1_SCE_IRQHandler [WEAK] - EXPORT EXTI9_5_IRQHandler [WEAK] - EXPORT TIM1_BRK_TIM9_IRQHandler [WEAK] - EXPORT TIM1_UP_TIM10_IRQHandler [WEAK] - EXPORT TIM1_TRG_COM_TIM11_IRQHandler [WEAK] - EXPORT TIM1_CC_IRQHandler [WEAK] - EXPORT TIM2_IRQHandler [WEAK] - EXPORT TIM3_IRQHandler [WEAK] - EXPORT TIM4_IRQHandler [WEAK] - EXPORT I2C1_EV_IRQHandler [WEAK] - EXPORT I2C1_ER_IRQHandler [WEAK] - EXPORT I2C2_EV_IRQHandler [WEAK] - EXPORT I2C2_ER_IRQHandler [WEAK] - EXPORT SPI1_IRQHandler [WEAK] - EXPORT SPI2_IRQHandler [WEAK] - EXPORT USART1_IRQHandler [WEAK] - EXPORT USART2_IRQHandler [WEAK] - EXPORT USART3_IRQHandler [WEAK] - EXPORT EXTI15_10_IRQHandler [WEAK] - EXPORT RTC_Alarm_IRQHandler [WEAK] - EXPORT OTG_FS_WKUP_IRQHandler [WEAK] - EXPORT TIM8_BRK_TIM12_IRQHandler [WEAK] - EXPORT TIM8_UP_TIM13_IRQHandler [WEAK] - EXPORT TIM8_TRG_COM_TIM14_IRQHandler [WEAK] - EXPORT TIM8_CC_IRQHandler [WEAK] - EXPORT DMA1_Stream7_IRQHandler [WEAK] - EXPORT FMC_IRQHandler [WEAK] - EXPORT SDIO_IRQHandler [WEAK] - EXPORT TIM5_IRQHandler [WEAK] - EXPORT SPI3_IRQHandler [WEAK] - EXPORT UART4_IRQHandler [WEAK] - EXPORT UART5_IRQHandler [WEAK] - EXPORT TIM6_DAC_IRQHandler [WEAK] - EXPORT TIM7_IRQHandler [WEAK] - EXPORT DMA2_Stream0_IRQHandler [WEAK] - EXPORT DMA2_Stream1_IRQHandler [WEAK] - EXPORT DMA2_Stream2_IRQHandler [WEAK] - EXPORT DMA2_Stream3_IRQHandler [WEAK] - EXPORT DMA2_Stream4_IRQHandler [WEAK] - EXPORT ETH_IRQHandler [WEAK] - EXPORT ETH_WKUP_IRQHandler [WEAK] - EXPORT CAN2_TX_IRQHandler [WEAK] - EXPORT CAN2_RX0_IRQHandler [WEAK] - EXPORT CAN2_RX1_IRQHandler [WEAK] - EXPORT CAN2_SCE_IRQHandler [WEAK] - EXPORT OTG_FS_IRQHandler [WEAK] - EXPORT DMA2_Stream5_IRQHandler [WEAK] - EXPORT DMA2_Stream6_IRQHandler [WEAK] - EXPORT DMA2_Stream7_IRQHandler [WEAK] - EXPORT USART6_IRQHandler [WEAK] - EXPORT I2C3_EV_IRQHandler [WEAK] - EXPORT I2C3_ER_IRQHandler [WEAK] - EXPORT OTG_HS_EP1_OUT_IRQHandler [WEAK] - EXPORT OTG_HS_EP1_IN_IRQHandler [WEAK] - EXPORT OTG_HS_WKUP_IRQHandler [WEAK] - EXPORT OTG_HS_IRQHandler [WEAK] - EXPORT DCMI_IRQHandler [WEAK] - EXPORT CRYP_IRQHandler [WEAK] - EXPORT HASH_RNG_IRQHandler [WEAK] - EXPORT FPU_IRQHandler [WEAK] - EXPORT UART7_IRQHandler [WEAK] - EXPORT UART8_IRQHandler [WEAK] - EXPORT SPI4_IRQHandler [WEAK] - EXPORT SPI5_IRQHandler [WEAK] - EXPORT SPI6_IRQHandler [WEAK] - EXPORT SAI1_IRQHandler [WEAK] - EXPORT LTDC_IRQHandler [WEAK] - EXPORT LTDC_ER_IRQHandler [WEAK] - EXPORT DMA2D_IRQHandler [WEAK] - EXPORT QUADSPI_IRQHandler [WEAK] - EXPORT DSI_IRQHandler [WEAK] - -WWDG_IRQHandler -PVD_IRQHandler -TAMP_STAMP_IRQHandler -RTC_WKUP_IRQHandler -FLASH_IRQHandler -RCC_IRQHandler -EXTI0_IRQHandler -EXTI1_IRQHandler -EXTI2_IRQHandler -EXTI3_IRQHandler -EXTI4_IRQHandler -DMA1_Stream0_IRQHandler -DMA1_Stream1_IRQHandler -DMA1_Stream2_IRQHandler -DMA1_Stream3_IRQHandler -DMA1_Stream4_IRQHandler -DMA1_Stream5_IRQHandler -DMA1_Stream6_IRQHandler -ADC_IRQHandler -CAN1_TX_IRQHandler -CAN1_RX0_IRQHandler -CAN1_RX1_IRQHandler -CAN1_SCE_IRQHandler -EXTI9_5_IRQHandler -TIM1_BRK_TIM9_IRQHandler -TIM1_UP_TIM10_IRQHandler -TIM1_TRG_COM_TIM11_IRQHandler -TIM1_CC_IRQHandler -TIM2_IRQHandler -TIM3_IRQHandler -TIM4_IRQHandler -I2C1_EV_IRQHandler -I2C1_ER_IRQHandler -I2C2_EV_IRQHandler -I2C2_ER_IRQHandler -SPI1_IRQHandler -SPI2_IRQHandler -USART1_IRQHandler -USART2_IRQHandler -USART3_IRQHandler -EXTI15_10_IRQHandler -RTC_Alarm_IRQHandler -OTG_FS_WKUP_IRQHandler -TIM8_BRK_TIM12_IRQHandler -TIM8_UP_TIM13_IRQHandler -TIM8_TRG_COM_TIM14_IRQHandler -TIM8_CC_IRQHandler -DMA1_Stream7_IRQHandler -FMC_IRQHandler -SDIO_IRQHandler -TIM5_IRQHandler -SPI3_IRQHandler -UART4_IRQHandler -UART5_IRQHandler -TIM6_DAC_IRQHandler -TIM7_IRQHandler -DMA2_Stream0_IRQHandler -DMA2_Stream1_IRQHandler -DMA2_Stream2_IRQHandler -DMA2_Stream3_IRQHandler -DMA2_Stream4_IRQHandler -ETH_IRQHandler -ETH_WKUP_IRQHandler -CAN2_TX_IRQHandler -CAN2_RX0_IRQHandler -CAN2_RX1_IRQHandler -CAN2_SCE_IRQHandler -OTG_FS_IRQHandler -DMA2_Stream5_IRQHandler -DMA2_Stream6_IRQHandler -DMA2_Stream7_IRQHandler -USART6_IRQHandler -I2C3_EV_IRQHandler -I2C3_ER_IRQHandler -OTG_HS_EP1_OUT_IRQHandler -OTG_HS_EP1_IN_IRQHandler -OTG_HS_WKUP_IRQHandler -OTG_HS_IRQHandler -DCMI_IRQHandler -CRYP_IRQHandler -HASH_RNG_IRQHandler -FPU_IRQHandler -UART7_IRQHandler -UART8_IRQHandler -SPI4_IRQHandler -SPI5_IRQHandler -SPI6_IRQHandler -SAI1_IRQHandler -LTDC_IRQHandler -LTDC_ER_IRQHandler -DMA2D_IRQHandler -QUADSPI_IRQHandler -DSI_IRQHandler - B . - - ENDP - - ALIGN - -;******************************************************************************* -; User Stack and Heap initialization -;******************************************************************************* - IF :DEF:__MICROLIB - - EXPORT __initial_sp - EXPORT __heap_base - EXPORT __heap_limit - - ELSE - - IMPORT __use_two_region_memory - EXPORT __user_initial_stackheap - -__user_initial_stackheap - - LDR R0, = Heap_Mem - LDR R1, =(Stack_Mem + Stack_Size) - LDR R2, = (Heap_Mem + Heap_Size) - LDR R3, = Stack_Mem - BX LR - - ALIGN - - ENDIF - - END - -;************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE***** diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/gcc_ride7/startup_stm32f401xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/gcc_ride7/startup_stm32f401xx.s deleted file mode 100644 index 7d773b73a4..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/gcc_ride7/startup_stm32f401xx.s +++ /dev/null @@ -1,438 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f40xx.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F401xx Devices vector table for RIDE7 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 - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M4 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); - * You may not use this file except in compliance with the License. - * You may obtain a copy of the License at: - * - * http://www.st.com/software_license_agreement_liberty_v2 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - ****************************************************************************** - */ - - .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: - -/* 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 the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word 0 /* Reserved */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word 0 /* Reserved */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word FPU_IRQHandler /* FPU */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word SPI4_IRQHandler /* SPI4 */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak SPI4_IRQHandler - .thumb_set SPI4_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/gcc_ride7/startup_stm32f40_41xxx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/gcc_ride7/startup_stm32f40_41xxx.s deleted file mode 100644 index 48d8e42ae7..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/gcc_ride7/startup_stm32f40_41xxx.s +++ /dev/null @@ -1,516 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f40_41xxx.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F40xxx/41xxx Devices vector table for RIDE7 toolchain. - * Same as startup_stm32f40xx.s and maintained for legacy purpose - * 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 mounted on - * STM324xG-EVAL board 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. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); - * You may not use this file except in compliance with the License. - * You may obtain a copy of the License at: - * - * http://www.st.com/software_license_agreement_liberty_v2 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - ****************************************************************************** - */ - - .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: - -/* 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 the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word CAN1_TX_IRQHandler /* CAN1 TX */ - .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ - .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ - .word CAN1_SCE_IRQHandler /* CAN1 SCE */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FSMC_IRQHandler /* FSMC */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word ETH_IRQHandler /* Ethernet */ - .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */ - .word CAN2_TX_IRQHandler /* CAN2 TX */ - .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ - .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ - .word CAN2_SCE_IRQHandler /* CAN2 SCE */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ - .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ - .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ - .word OTG_HS_IRQHandler /* USB OTG HS */ - .word DCMI_IRQHandler /* DCMI */ - .word CRYP_IRQHandler /* CRYP crypto */ - .word HASH_RNG_IRQHandler /* Hash and Rng */ - .word FPU_IRQHandler /* FPU */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FSMC_IRQHandler - .thumb_set FSMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak ETH_IRQHandler - .thumb_set ETH_IRQHandler,Default_Handler - - .weak ETH_WKUP_IRQHandler - .thumb_set ETH_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_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_OUT_IRQHandler - .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_IN_IRQHandler - .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler - - .weak OTG_HS_WKUP_IRQHandler - .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler - - .weak OTG_HS_IRQHandler - .thumb_set OTG_HS_IRQHandler,Default_Handler - - .weak DCMI_IRQHandler - .thumb_set DCMI_IRQHandler,Default_Handler - - .weak CRYP_IRQHandler - .thumb_set CRYP_IRQHandler,Default_Handler - - .weak HASH_RNG_IRQHandler - .thumb_set HASH_RNG_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/gcc_ride7/startup_stm32f40xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/gcc_ride7/startup_stm32f40xx.s deleted file mode 100644 index 96976662db..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/gcc_ride7/startup_stm32f40xx.s +++ /dev/null @@ -1,515 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f40xx.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F40xxxx Devices vector table for RIDE7 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 mounted on - * STM324xG-EVAL board 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. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); - * You may not use this file except in compliance with the License. - * You may obtain a copy of the License at: - * - * http://www.st.com/software_license_agreement_liberty_v2 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - ****************************************************************************** - */ - - .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: - -/* 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 the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word CAN1_TX_IRQHandler /* CAN1 TX */ - .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ - .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ - .word CAN1_SCE_IRQHandler /* CAN1 SCE */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FSMC_IRQHandler /* FSMC */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word ETH_IRQHandler /* Ethernet */ - .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */ - .word CAN2_TX_IRQHandler /* CAN2 TX */ - .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ - .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ - .word CAN2_SCE_IRQHandler /* CAN2 SCE */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ - .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ - .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ - .word OTG_HS_IRQHandler /* USB OTG HS */ - .word DCMI_IRQHandler /* DCMI */ - .word CRYP_IRQHandler /* CRYP crypto */ - .word HASH_RNG_IRQHandler /* Hash and Rng */ - .word FPU_IRQHandler /* FPU */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FSMC_IRQHandler - .thumb_set FSMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak ETH_IRQHandler - .thumb_set ETH_IRQHandler,Default_Handler - - .weak ETH_WKUP_IRQHandler - .thumb_set ETH_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_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_OUT_IRQHandler - .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_IN_IRQHandler - .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler - - .weak OTG_HS_WKUP_IRQHandler - .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler - - .weak OTG_HS_IRQHandler - .thumb_set OTG_HS_IRQHandler,Default_Handler - - .weak DCMI_IRQHandler - .thumb_set DCMI_IRQHandler,Default_Handler - - .weak CRYP_IRQHandler - .thumb_set CRYP_IRQHandler,Default_Handler - - .weak HASH_RNG_IRQHandler - .thumb_set HASH_RNG_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/gcc_ride7/startup_stm32f427_437xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/gcc_ride7/startup_stm32f427_437xx.s deleted file mode 100644 index 4ec4179688..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/gcc_ride7/startup_stm32f427_437xx.s +++ /dev/null @@ -1,551 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f427_437xx.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F427xx/437xx Devices vector table for RIDE7 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 mounted on - * STM324x7I-EVAL board 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. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); - * You may not use this file except in compliance with the License. - * You may obtain a copy of the License at: - * - * http://www.st.com/software_license_agreement_liberty_v2 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - ****************************************************************************** - */ - - .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: - -/* 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 the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word CAN1_TX_IRQHandler /* CAN1 TX */ - .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ - .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ - .word CAN1_SCE_IRQHandler /* CAN1 SCE */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FSMC_IRQHandler /* FSMC */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word ETH_IRQHandler /* Ethernet */ - .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */ - .word CAN2_TX_IRQHandler /* CAN2 TX */ - .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ - .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ - .word CAN2_SCE_IRQHandler /* CAN2 SCE */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ - .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ - .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ - .word OTG_HS_IRQHandler /* USB OTG HS */ - .word DCMI_IRQHandler /* DCMI */ - .word CRYP_IRQHandler /* CRYP crypto */ - .word HASH_RNG_IRQHandler /* Hash and Rng */ - .word FPU_IRQHandler /* FPU */ - .word UART7_IRQHandler /* UART7 */ - .word UART8_IRQHandler /* UART8 */ - .word SPI4_IRQHandler /* SPI4 */ - .word SPI5_IRQHandler /* SPI5 */ - .word SPI6_IRQHandler /* SPI6 */ - .word SAI1_IRQHandler /* SAI1 */ - .word LTDC_IRQHandler /* LTDC */ - .word LTDC_ER_IRQHandler /* LTDC error */ - .word DMA2D_IRQHandler /* DMA2D */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FSMC_IRQHandler - .thumb_set FSMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak ETH_IRQHandler - .thumb_set ETH_IRQHandler,Default_Handler - - .weak ETH_WKUP_IRQHandler - .thumb_set ETH_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_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_OUT_IRQHandler - .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_IN_IRQHandler - .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler - - .weak OTG_HS_WKUP_IRQHandler - .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler - - .weak OTG_HS_IRQHandler - .thumb_set OTG_HS_IRQHandler,Default_Handler - - .weak DCMI_IRQHandler - .thumb_set DCMI_IRQHandler,Default_Handler - - .weak CRYP_IRQHandler - .thumb_set CRYP_IRQHandler,Default_Handler - - .weak HASH_RNG_IRQHandler - .thumb_set HASH_RNG_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak UART7_IRQHandler - .thumb_set UART7_IRQHandler,Default_Handler - - .weak UART8_IRQHandler - .thumb_set UART8_IRQHandler,Default_Handler - - .weak SPI4_IRQHandler - .thumb_set SPI4_IRQHandler,Default_Handler - - .weak SPI5_IRQHandler - .thumb_set SPI5_IRQHandler,Default_Handler - - .weak SPI6_IRQHandler - .thumb_set SPI6_IRQHandler,Default_Handler - - .weak SAI1_IRQHandler - .thumb_set SAI1_IRQHandler,Default_Handler - - .weak LTDC_IRQHandler - .thumb_set LTDC_IRQHandler,Default_Handler - - .weak LTDC_ER_IRQHandler - .thumb_set LTDC_ER_IRQHandler,Default_Handler - - .weak DMA2D_IRQHandler - .thumb_set DMA2D_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/gcc_ride7/startup_stm32f427x.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/gcc_ride7/startup_stm32f427x.s deleted file mode 100644 index c163041566..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/gcc_ride7/startup_stm32f427x.s +++ /dev/null @@ -1,552 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f427x.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F427xx/437xx Devices vector table for RIDE7 toolchain. - * Same as startup_stm32f427_437xx.s and maintained for legacy purpose - * 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 mounted on - * STM324x7I-EVAL board 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. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); - * You may not use this file except in compliance with the License. - * You may obtain a copy of the License at: - * - * http://www.st.com/software_license_agreement_liberty_v2 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - ****************************************************************************** - */ - - .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: - -/* 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 the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word CAN1_TX_IRQHandler /* CAN1 TX */ - .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ - .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ - .word CAN1_SCE_IRQHandler /* CAN1 SCE */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FSMC_IRQHandler /* FSMC */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word ETH_IRQHandler /* Ethernet */ - .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */ - .word CAN2_TX_IRQHandler /* CAN2 TX */ - .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ - .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ - .word CAN2_SCE_IRQHandler /* CAN2 SCE */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ - .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ - .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ - .word OTG_HS_IRQHandler /* USB OTG HS */ - .word DCMI_IRQHandler /* DCMI */ - .word CRYP_IRQHandler /* CRYP crypto */ - .word HASH_RNG_IRQHandler /* Hash and Rng */ - .word FPU_IRQHandler /* FPU */ - .word UART7_IRQHandler /* UART7 */ - .word UART8_IRQHandler /* UART8 */ - .word SPI4_IRQHandler /* SPI4 */ - .word SPI5_IRQHandler /* SPI5 */ - .word SPI6_IRQHandler /* SPI6 */ - .word SAI1_IRQHandler /* SAI1 */ - .word LTDC_IRQHandler /* LTDC */ - .word LTDC_ER_IRQHandler /* LTDC error */ - .word DMA2D_IRQHandler /* DMA2D */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FSMC_IRQHandler - .thumb_set FSMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak ETH_IRQHandler - .thumb_set ETH_IRQHandler,Default_Handler - - .weak ETH_WKUP_IRQHandler - .thumb_set ETH_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_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_OUT_IRQHandler - .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_IN_IRQHandler - .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler - - .weak OTG_HS_WKUP_IRQHandler - .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler - - .weak OTG_HS_IRQHandler - .thumb_set OTG_HS_IRQHandler,Default_Handler - - .weak DCMI_IRQHandler - .thumb_set DCMI_IRQHandler,Default_Handler - - .weak CRYP_IRQHandler - .thumb_set CRYP_IRQHandler,Default_Handler - - .weak HASH_RNG_IRQHandler - .thumb_set HASH_RNG_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak UART7_IRQHandler - .thumb_set UART7_IRQHandler,Default_Handler - - .weak UART8_IRQHandler - .thumb_set UART8_IRQHandler,Default_Handler - - .weak SPI4_IRQHandler - .thumb_set SPI4_IRQHandler,Default_Handler - - .weak SPI5_IRQHandler - .thumb_set SPI5_IRQHandler,Default_Handler - - .weak SPI6_IRQHandler - .thumb_set SPI6_IRQHandler,Default_Handler - - .weak SAI1_IRQHandler - .thumb_set SAI1_IRQHandler,Default_Handler - - .weak LTDC_IRQHandler - .thumb_set LTDC_IRQHandler,Default_Handler - - .weak LTDC_ER_IRQHandler - .thumb_set LTDC_ER_IRQHandler,Default_Handler - - .weak DMA2D_IRQHandler - .thumb_set DMA2D_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/gcc_ride7/startup_stm32f429_439xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/gcc_ride7/startup_stm32f429_439xx.s deleted file mode 100644 index 6d4693c9d8..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/gcc_ride7/startup_stm32f429_439xx.s +++ /dev/null @@ -1,551 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f429_439xx.s - * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief STM32F429xx/439xx Devices vector table for RIDE7 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 mounted on - * STM324x9I-EVAL board 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. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2015 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); - * You may not use this file except in compliance with the License. - * You may obtain a copy of the License at: - * - * http://www.st.com/software_license_agreement_liberty_v2 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - ****************************************************************************** - */ - - .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: - -/* 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 the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word CAN1_TX_IRQHandler /* CAN1 TX */ - .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ - .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ - .word CAN1_SCE_IRQHandler /* CAN1 SCE */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FSMC_IRQHandler /* FSMC */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word ETH_IRQHandler /* Ethernet */ - .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */ - .word CAN2_TX_IRQHandler /* CAN2 TX */ - .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ - .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ - .word CAN2_SCE_IRQHandler /* CAN2 SCE */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ - .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ - .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ - .word OTG_HS_IRQHandler /* USB OTG HS */ - .word DCMI_IRQHandler /* DCMI */ - .word CRYP_IRQHandler /* CRYP crypto */ - .word HASH_RNG_IRQHandler /* Hash and Rng */ - .word FPU_IRQHandler /* FPU */ - .word UART7_IRQHandler /* UART7 */ - .word UART8_IRQHandler /* UART8 */ - .word SPI4_IRQHandler /* SPI4 */ - .word SPI5_IRQHandler /* SPI5 */ - .word SPI6_IRQHandler /* SPI6 */ - .word SAI1_IRQHandler /* SAI1 */ - .word LTDC_IRQHandler /* LTDC */ - .word LTDC_ER_IRQHandler /* LTDC error */ - .word DMA2D_IRQHandler /* DMA2D */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FSMC_IRQHandler - .thumb_set FSMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak ETH_IRQHandler - .thumb_set ETH_IRQHandler,Default_Handler - - .weak ETH_WKUP_IRQHandler - .thumb_set ETH_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_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_OUT_IRQHandler - .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_IN_IRQHandler - .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler - - .weak OTG_HS_WKUP_IRQHandler - .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler - - .weak OTG_HS_IRQHandler - .thumb_set OTG_HS_IRQHandler,Default_Handler - - .weak DCMI_IRQHandler - .thumb_set DCMI_IRQHandler,Default_Handler - - .weak CRYP_IRQHandler - .thumb_set CRYP_IRQHandler,Default_Handler - - .weak HASH_RNG_IRQHandler - .thumb_set HASH_RNG_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak UART7_IRQHandler - .thumb_set UART7_IRQHandler,Default_Handler - - .weak UART8_IRQHandler - .thumb_set UART8_IRQHandler,Default_Handler - - .weak SPI4_IRQHandler - .thumb_set SPI4_IRQHandler,Default_Handler - - .weak SPI5_IRQHandler - .thumb_set SPI5_IRQHandler,Default_Handler - - .weak SPI6_IRQHandler - .thumb_set SPI6_IRQHandler,Default_Handler - - .weak SAI1_IRQHandler - .thumb_set SAI1_IRQHandler,Default_Handler - - .weak LTDC_IRQHandler - .thumb_set LTDC_IRQHandler,Default_Handler - - .weak LTDC_ER_IRQHandler - .thumb_set LTDC_ER_IRQHandler,Default_Handler - - .weak DMA2D_IRQHandler - .thumb_set DMA2D_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f401xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f401xx.s deleted file mode 100644 index fbcbd390b5..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f401xx.s +++ /dev/null @@ -1,507 +0,0 @@ -;/******************** (C) COPYRIGHT 2015 STMicroelectronics ******************** -;* File Name : startup_stm32f401x.s -;* Author : MCD Application Team -;* @version : V1.6.1 -;* @date : 21-October-2015 -;* Description : STM32F401xx devices vector table for EWARM toolchain. -;* This module performs: -;* - Set the initial SP -;* - Set the initial PC == _iar_program_start, -;* - Set the vector table entries with the exceptions ISR -;* address. -;* - Configure the system clock -;* - 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. -;******************************************************************************** -;* -;* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); -;* You may not use this file except in compliance with the License. -;* You may obtain a copy of the License at: -;* -;* http://www.st.com/software_license_agreement_liberty_v2 -;* -;* Unless required by applicable law or agreed to in writing, software -;* distributed under the License is distributed on an "AS IS" BASIS, -;* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -;* See the License for the specific language governing permissions and -;* limitations under the License. -;* -;*******************************************************************************/ -; -; -; The modules in this file are included in the libraries, and may be replaced -; by any user-defined modules that define the PUBLIC symbol _program_start or -; a user defined start symbol. -; To override the cstartup defined in the library, simply add your modified -; version to the workbench project. -; -; The vector table is normally located at address 0. -; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. -; The name "__vector_table" has special meaning for C-SPY: -; it is where the SP start value is found, and the NVIC vector -; table register (VTOR) is initialized to this address if != 0. -; -; Cortex-M version -; - - MODULE ?cstartup - - ;; Forward declaration of sections. - SECTION CSTACK:DATA:NOROOT(3) - - SECTION .intvec:CODE:NOROOT(2) - - EXTERN __iar_program_start - EXTERN SystemInit - PUBLIC __vector_table - - DATA -__vector_table - DCD sfe(CSTACK) - DCD Reset_Handler ; Reset Handler - - DCD NMI_Handler ; NMI Handler - DCD HardFault_Handler ; Hard Fault Handler - DCD MemManage_Handler ; MPU Fault Handler - DCD BusFault_Handler ; Bus Fault Handler - DCD UsageFault_Handler ; Usage Fault Handler - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SVC_Handler ; SVCall Handler - DCD DebugMon_Handler ; Debug Monitor Handler - DCD 0 ; Reserved - DCD PendSV_Handler ; PendSV Handler - DCD SysTick_Handler ; SysTick Handler - - ; External Interrupts - DCD WWDG_IRQHandler ; Window WatchDog - DCD PVD_IRQHandler ; PVD through EXTI Line detection - DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line - DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line - DCD FLASH_IRQHandler ; FLASH - DCD RCC_IRQHandler ; RCC - DCD EXTI0_IRQHandler ; EXTI Line0 - DCD EXTI1_IRQHandler ; EXTI Line1 - DCD EXTI2_IRQHandler ; EXTI Line2 - DCD EXTI3_IRQHandler ; EXTI Line3 - DCD EXTI4_IRQHandler ; EXTI Line4 - DCD DMA1_Stream0_IRQHandler ; DMA1 Stream 0 - DCD DMA1_Stream1_IRQHandler ; DMA1 Stream 1 - DCD DMA1_Stream2_IRQHandler ; DMA1 Stream 2 - DCD DMA1_Stream3_IRQHandler ; DMA1 Stream 3 - DCD DMA1_Stream4_IRQHandler ; DMA1 Stream 4 - DCD DMA1_Stream5_IRQHandler ; DMA1 Stream 5 - DCD DMA1_Stream6_IRQHandler ; DMA1 Stream 6 - DCD ADC_IRQHandler ; ADC1 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD EXTI9_5_IRQHandler ; External Line[9:5]s - DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 - DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 - DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 - DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare - DCD TIM2_IRQHandler ; TIM2 - DCD TIM3_IRQHandler ; TIM3 - DCD TIM4_IRQHandler ; TIM4 - DCD I2C1_EV_IRQHandler ; I2C1 Event - DCD I2C1_ER_IRQHandler ; I2C1 Error - DCD I2C2_EV_IRQHandler ; I2C2 Event - DCD I2C2_ER_IRQHandler ; I2C2 Error - DCD SPI1_IRQHandler ; SPI1 - DCD SPI2_IRQHandler ; SPI2 - DCD USART1_IRQHandler ; USART1 - DCD USART2_IRQHandler ; USART2 - DCD 0 ; Reserved - DCD EXTI15_10_IRQHandler ; External Line[15:10]s - DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line - DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD DMA1_Stream7_IRQHandler ; DMA1 Stream7 - DCD 0 ; Reserved - DCD SDIO_IRQHandler ; SDIO - DCD TIM5_IRQHandler ; TIM5 - DCD SPI3_IRQHandler ; SPI3 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD DMA2_Stream0_IRQHandler ; DMA2 Stream 0 - DCD DMA2_Stream1_IRQHandler ; DMA2 Stream 1 - DCD DMA2_Stream2_IRQHandler ; DMA2 Stream 2 - DCD DMA2_Stream3_IRQHandler ; DMA2 Stream 3 - DCD DMA2_Stream4_IRQHandler ; DMA2 Stream 4 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD OTG_FS_IRQHandler ; USB OTG FS - DCD DMA2_Stream5_IRQHandler ; DMA2 Stream 5 - DCD DMA2_Stream6_IRQHandler ; DMA2 Stream 6 - DCD DMA2_Stream7_IRQHandler ; DMA2 Stream 7 - DCD USART6_IRQHandler ; USART6 - DCD I2C3_EV_IRQHandler ; I2C3 event - DCD I2C3_ER_IRQHandler ; I2C3 error - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD FPU_IRQHandler ; FPU - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SPI4_IRQHandler ; SPI4 - -;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; -;; -;; Default interrupt handlers. -;; - THUMB - PUBWEAK Reset_Handler - SECTION .text:CODE:REORDER:NOROOT(2) -Reset_Handler - - LDR R0, =SystemInit - BLX R0 - LDR R0, =__iar_program_start - BX R0 - - PUBWEAK NMI_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -NMI_Handler - B NMI_Handler - - PUBWEAK HardFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -HardFault_Handler - B HardFault_Handler - - PUBWEAK MemManage_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -MemManage_Handler - B MemManage_Handler - - PUBWEAK BusFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -BusFault_Handler - B BusFault_Handler - - PUBWEAK UsageFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -UsageFault_Handler - B UsageFault_Handler - - PUBWEAK SVC_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -SVC_Handler - B SVC_Handler - - PUBWEAK DebugMon_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -DebugMon_Handler - B DebugMon_Handler - - PUBWEAK PendSV_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -PendSV_Handler - B PendSV_Handler - - PUBWEAK SysTick_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -SysTick_Handler - B SysTick_Handler - - PUBWEAK WWDG_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -WWDG_IRQHandler - B WWDG_IRQHandler - - PUBWEAK PVD_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -PVD_IRQHandler - B PVD_IRQHandler - - PUBWEAK TAMP_STAMP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TAMP_STAMP_IRQHandler - B TAMP_STAMP_IRQHandler - - PUBWEAK RTC_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RTC_WKUP_IRQHandler - B RTC_WKUP_IRQHandler - - PUBWEAK FLASH_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FLASH_IRQHandler - B FLASH_IRQHandler - - PUBWEAK RCC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RCC_IRQHandler - B RCC_IRQHandler - - PUBWEAK EXTI0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI0_IRQHandler - B EXTI0_IRQHandler - - PUBWEAK EXTI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI1_IRQHandler - B EXTI1_IRQHandler - - PUBWEAK EXTI2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI2_IRQHandler - B EXTI2_IRQHandler - - PUBWEAK EXTI3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI3_IRQHandler - B EXTI3_IRQHandler - - PUBWEAK EXTI4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI4_IRQHandler - B EXTI4_IRQHandler - - PUBWEAK DMA1_Stream0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream0_IRQHandler - B DMA1_Stream0_IRQHandler - - PUBWEAK DMA1_Stream1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream1_IRQHandler - B DMA1_Stream1_IRQHandler - - PUBWEAK DMA1_Stream2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream2_IRQHandler - B DMA1_Stream2_IRQHandler - - PUBWEAK DMA1_Stream3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream3_IRQHandler - B DMA1_Stream3_IRQHandler - - PUBWEAK DMA1_Stream4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream4_IRQHandler - B DMA1_Stream4_IRQHandler - - PUBWEAK DMA1_Stream5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream5_IRQHandler - B DMA1_Stream5_IRQHandler - - PUBWEAK DMA1_Stream6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream6_IRQHandler - B DMA1_Stream6_IRQHandler - - PUBWEAK ADC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -ADC_IRQHandler - B ADC_IRQHandler - - PUBWEAK EXTI9_5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI9_5_IRQHandler - B EXTI9_5_IRQHandler - - PUBWEAK TIM1_BRK_TIM9_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_BRK_TIM9_IRQHandler - B TIM1_BRK_TIM9_IRQHandler - - PUBWEAK TIM1_UP_TIM10_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_UP_TIM10_IRQHandler - B TIM1_UP_TIM10_IRQHandler - - PUBWEAK TIM1_TRG_COM_TIM11_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_TRG_COM_TIM11_IRQHandler - B TIM1_TRG_COM_TIM11_IRQHandler - - PUBWEAK TIM1_CC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_CC_IRQHandler - B TIM1_CC_IRQHandler - - PUBWEAK TIM2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM2_IRQHandler - B TIM2_IRQHandler - - PUBWEAK TIM3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM3_IRQHandler - B TIM3_IRQHandler - - PUBWEAK TIM4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM4_IRQHandler - B TIM4_IRQHandler - - PUBWEAK I2C1_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C1_EV_IRQHandler - B I2C1_EV_IRQHandler - - PUBWEAK I2C1_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C1_ER_IRQHandler - B I2C1_ER_IRQHandler - - PUBWEAK I2C2_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C2_EV_IRQHandler - B I2C2_EV_IRQHandler - - PUBWEAK I2C2_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C2_ER_IRQHandler - B I2C2_ER_IRQHandler - - PUBWEAK SPI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI1_IRQHandler - B SPI1_IRQHandler - - PUBWEAK SPI2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI2_IRQHandler - B SPI2_IRQHandler - - PUBWEAK USART1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART1_IRQHandler - B USART1_IRQHandler - - PUBWEAK USART2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART2_IRQHandler - B USART2_IRQHandler - - PUBWEAK EXTI15_10_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI15_10_IRQHandler - B EXTI15_10_IRQHandler - - PUBWEAK RTC_Alarm_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RTC_Alarm_IRQHandler - B RTC_Alarm_IRQHandler - - PUBWEAK OTG_FS_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_FS_WKUP_IRQHandler - B OTG_FS_WKUP_IRQHandler - - PUBWEAK DMA1_Stream7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream7_IRQHandler - B DMA1_Stream7_IRQHandler - - PUBWEAK SDIO_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SDIO_IRQHandler - B SDIO_IRQHandler - - PUBWEAK TIM5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM5_IRQHandler - B TIM5_IRQHandler - - PUBWEAK SPI3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI3_IRQHandler - B SPI3_IRQHandler - - PUBWEAK DMA2_Stream0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream0_IRQHandler - B DMA2_Stream0_IRQHandler - - PUBWEAK DMA2_Stream1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream1_IRQHandler - B DMA2_Stream1_IRQHandler - - PUBWEAK DMA2_Stream2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream2_IRQHandler - B DMA2_Stream2_IRQHandler - - PUBWEAK DMA2_Stream3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream3_IRQHandler - B DMA2_Stream3_IRQHandler - - PUBWEAK DMA2_Stream4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream4_IRQHandler - B DMA2_Stream4_IRQHandler - - PUBWEAK OTG_FS_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_FS_IRQHandler - B OTG_FS_IRQHandler - - PUBWEAK DMA2_Stream5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream5_IRQHandler - B DMA2_Stream5_IRQHandler - - PUBWEAK DMA2_Stream6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream6_IRQHandler - B DMA2_Stream6_IRQHandler - - PUBWEAK DMA2_Stream7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream7_IRQHandler - B DMA2_Stream7_IRQHandler - - PUBWEAK USART6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART6_IRQHandler - B USART6_IRQHandler - - PUBWEAK I2C3_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C3_EV_IRQHandler - B I2C3_EV_IRQHandler - - PUBWEAK I2C3_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C3_ER_IRQHandler - B I2C3_ER_IRQHandler - - PUBWEAK FPU_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FPU_IRQHandler - B FPU_IRQHandler - - PUBWEAK SPI4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI4_IRQHandler - B SPI4_IRQHandler - - END -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f40_41xxx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f40_41xxx.s deleted file mode 100644 index 8bbbe60183..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f40_41xxx.s +++ /dev/null @@ -1,636 +0,0 @@ -;/******************** (C) COPYRIGHT 2015 STMicroelectronics ******************** -;* File Name : startup_stm32f40_41xxx.s -;* Author : MCD Application Team -;* @version : V1.6.1 -;* @date : 21-October-2015 -;* Description : STM32F40xxx/41xxx devices vector table for EWARM toolchain. -;* This module performs: -;* - Set the initial SP -;* - Set the initial PC == _iar_program_start, -;* - Set the vector table entries with the exceptions ISR -;* address. -;* - Configure the system clock and the external SRAM mounted on -;* STM324xG-EVAL board 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. -;******************************************************************************** -;* -;* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); -;* You may not use this file except in compliance with the License. -;* You may obtain a copy of the License at: -;* -;* http://www.st.com/software_license_agreement_liberty_v2 -;* -;* Unless required by applicable law or agreed to in writing, software -;* distributed under the License is distributed on an "AS IS" BASIS, -;* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -;* See the License for the specific language governing permissions and -;* limitations under the License. -;* -;*******************************************************************************/ -; -; -; The modules in this file are included in the libraries, and may be replaced -; by any user-defined modules that define the PUBLIC symbol _program_start or -; a user defined start symbol. -; To override the cstartup defined in the library, simply add your modified -; version to the workbench project. -; -; The vector table is normally located at address 0. -; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. -; The name "__vector_table" has special meaning for C-SPY: -; it is where the SP start value is found, and the NVIC vector -; table register (VTOR) is initialized to this address if != 0. -; -; Cortex-M version -; - - MODULE ?cstartup - - ;; Forward declaration of sections. - SECTION CSTACK:DATA:NOROOT(3) - - SECTION .intvec:CODE:NOROOT(2) - - EXTERN __iar_program_start - EXTERN SystemInit - PUBLIC __vector_table - - DATA -__vector_table - DCD sfe(CSTACK) - DCD Reset_Handler ; Reset Handler - - DCD NMI_Handler ; NMI Handler - DCD HardFault_Handler ; Hard Fault Handler - DCD MemManage_Handler ; MPU Fault Handler - DCD BusFault_Handler ; Bus Fault Handler - DCD UsageFault_Handler ; Usage Fault Handler - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SVC_Handler ; SVCall Handler - DCD DebugMon_Handler ; Debug Monitor Handler - DCD 0 ; Reserved - DCD PendSV_Handler ; PendSV Handler - DCD SysTick_Handler ; SysTick Handler - - ; External Interrupts - DCD WWDG_IRQHandler ; Window WatchDog - DCD PVD_IRQHandler ; PVD through EXTI Line detection - DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line - DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line - DCD FLASH_IRQHandler ; FLASH - DCD RCC_IRQHandler ; RCC - DCD EXTI0_IRQHandler ; EXTI Line0 - DCD EXTI1_IRQHandler ; EXTI Line1 - DCD EXTI2_IRQHandler ; EXTI Line2 - DCD EXTI3_IRQHandler ; EXTI Line3 - DCD EXTI4_IRQHandler ; EXTI Line4 - DCD DMA1_Stream0_IRQHandler ; DMA1 Stream 0 - DCD DMA1_Stream1_IRQHandler ; DMA1 Stream 1 - DCD DMA1_Stream2_IRQHandler ; DMA1 Stream 2 - DCD DMA1_Stream3_IRQHandler ; DMA1 Stream 3 - DCD DMA1_Stream4_IRQHandler ; DMA1 Stream 4 - DCD DMA1_Stream5_IRQHandler ; DMA1 Stream 5 - DCD DMA1_Stream6_IRQHandler ; DMA1 Stream 6 - DCD ADC_IRQHandler ; ADC1, ADC2 and ADC3s - DCD CAN1_TX_IRQHandler ; CAN1 TX - DCD CAN1_RX0_IRQHandler ; CAN1 RX0 - DCD CAN1_RX1_IRQHandler ; CAN1 RX1 - DCD CAN1_SCE_IRQHandler ; CAN1 SCE - DCD EXTI9_5_IRQHandler ; External Line[9:5]s - DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 - DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 - DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 - DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare - DCD TIM2_IRQHandler ; TIM2 - DCD TIM3_IRQHandler ; TIM3 - DCD TIM4_IRQHandler ; TIM4 - DCD I2C1_EV_IRQHandler ; I2C1 Event - DCD I2C1_ER_IRQHandler ; I2C1 Error - DCD I2C2_EV_IRQHandler ; I2C2 Event - DCD I2C2_ER_IRQHandler ; I2C2 Error - DCD SPI1_IRQHandler ; SPI1 - DCD SPI2_IRQHandler ; SPI2 - DCD USART1_IRQHandler ; USART1 - DCD USART2_IRQHandler ; USART2 - DCD USART3_IRQHandler ; USART3 - DCD EXTI15_10_IRQHandler ; External Line[15:10]s - DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line - DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line - DCD TIM8_BRK_TIM12_IRQHandler ; TIM8 Break and TIM12 - DCD TIM8_UP_TIM13_IRQHandler ; TIM8 Update and TIM13 - DCD TIM8_TRG_COM_TIM14_IRQHandler ; TIM8 Trigger and Commutation and TIM14 - DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare - DCD DMA1_Stream7_IRQHandler ; DMA1 Stream7 - DCD FSMC_IRQHandler ; FSMC - DCD SDIO_IRQHandler ; SDIO - DCD TIM5_IRQHandler ; TIM5 - DCD SPI3_IRQHandler ; SPI3 - DCD UART4_IRQHandler ; UART4 - DCD UART5_IRQHandler ; UART5 - DCD TIM6_DAC_IRQHandler ; TIM6 and DAC1&2 underrun errors - DCD TIM7_IRQHandler ; TIM7 - DCD DMA2_Stream0_IRQHandler ; DMA2 Stream 0 - DCD DMA2_Stream1_IRQHandler ; DMA2 Stream 1 - DCD DMA2_Stream2_IRQHandler ; DMA2 Stream 2 - DCD DMA2_Stream3_IRQHandler ; DMA2 Stream 3 - DCD DMA2_Stream4_IRQHandler ; DMA2 Stream 4 - DCD ETH_IRQHandler ; Ethernet - DCD ETH_WKUP_IRQHandler ; Ethernet Wakeup through EXTI line - DCD CAN2_TX_IRQHandler ; CAN2 TX - DCD CAN2_RX0_IRQHandler ; CAN2 RX0 - DCD CAN2_RX1_IRQHandler ; CAN2 RX1 - DCD CAN2_SCE_IRQHandler ; CAN2 SCE - DCD OTG_FS_IRQHandler ; USB OTG FS - DCD DMA2_Stream5_IRQHandler ; DMA2 Stream 5 - DCD DMA2_Stream6_IRQHandler ; DMA2 Stream 6 - DCD DMA2_Stream7_IRQHandler ; DMA2 Stream 7 - DCD USART6_IRQHandler ; USART6 - DCD I2C3_EV_IRQHandler ; I2C3 event - DCD I2C3_ER_IRQHandler ; I2C3 error - DCD OTG_HS_EP1_OUT_IRQHandler ; USB OTG HS End Point 1 Out - DCD OTG_HS_EP1_IN_IRQHandler ; USB OTG HS End Point 1 In - DCD OTG_HS_WKUP_IRQHandler ; USB OTG HS Wakeup through EXTI - DCD OTG_HS_IRQHandler ; USB OTG HS - DCD DCMI_IRQHandler ; DCMI - DCD CRYP_IRQHandler ; CRYP crypto - DCD HASH_RNG_IRQHandler ; Hash and Rng - DCD FPU_IRQHandler ; FPU - -;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; -;; -;; Default interrupt handlers. -;; - THUMB - PUBWEAK Reset_Handler - SECTION .text:CODE:REORDER:NOROOT(2) -Reset_Handler - - LDR R0, =SystemInit - BLX R0 - LDR R0, =__iar_program_start - BX R0 - - PUBWEAK NMI_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -NMI_Handler - B NMI_Handler - - PUBWEAK HardFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -HardFault_Handler - B HardFault_Handler - - PUBWEAK MemManage_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -MemManage_Handler - B MemManage_Handler - - PUBWEAK BusFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -BusFault_Handler - B BusFault_Handler - - PUBWEAK UsageFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -UsageFault_Handler - B UsageFault_Handler - - PUBWEAK SVC_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -SVC_Handler - B SVC_Handler - - PUBWEAK DebugMon_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -DebugMon_Handler - B DebugMon_Handler - - PUBWEAK PendSV_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -PendSV_Handler - B PendSV_Handler - - PUBWEAK SysTick_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -SysTick_Handler - B SysTick_Handler - - PUBWEAK WWDG_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -WWDG_IRQHandler - B WWDG_IRQHandler - - PUBWEAK PVD_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -PVD_IRQHandler - B PVD_IRQHandler - - PUBWEAK TAMP_STAMP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TAMP_STAMP_IRQHandler - B TAMP_STAMP_IRQHandler - - PUBWEAK RTC_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RTC_WKUP_IRQHandler - B RTC_WKUP_IRQHandler - - PUBWEAK FLASH_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FLASH_IRQHandler - B FLASH_IRQHandler - - PUBWEAK RCC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RCC_IRQHandler - B RCC_IRQHandler - - PUBWEAK EXTI0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI0_IRQHandler - B EXTI0_IRQHandler - - PUBWEAK EXTI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI1_IRQHandler - B EXTI1_IRQHandler - - PUBWEAK EXTI2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI2_IRQHandler - B EXTI2_IRQHandler - - PUBWEAK EXTI3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI3_IRQHandler - B EXTI3_IRQHandler - - PUBWEAK EXTI4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI4_IRQHandler - B EXTI4_IRQHandler - - PUBWEAK DMA1_Stream0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream0_IRQHandler - B DMA1_Stream0_IRQHandler - - PUBWEAK DMA1_Stream1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream1_IRQHandler - B DMA1_Stream1_IRQHandler - - PUBWEAK DMA1_Stream2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream2_IRQHandler - B DMA1_Stream2_IRQHandler - - PUBWEAK DMA1_Stream3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream3_IRQHandler - B DMA1_Stream3_IRQHandler - - PUBWEAK DMA1_Stream4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream4_IRQHandler - B DMA1_Stream4_IRQHandler - - PUBWEAK DMA1_Stream5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream5_IRQHandler - B DMA1_Stream5_IRQHandler - - PUBWEAK DMA1_Stream6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream6_IRQHandler - B DMA1_Stream6_IRQHandler - - PUBWEAK ADC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -ADC_IRQHandler - B ADC_IRQHandler - - PUBWEAK CAN1_TX_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_TX_IRQHandler - B CAN1_TX_IRQHandler - - PUBWEAK CAN1_RX0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_RX0_IRQHandler - B CAN1_RX0_IRQHandler - - PUBWEAK CAN1_RX1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_RX1_IRQHandler - B CAN1_RX1_IRQHandler - - PUBWEAK CAN1_SCE_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_SCE_IRQHandler - B CAN1_SCE_IRQHandler - - PUBWEAK EXTI9_5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI9_5_IRQHandler - B EXTI9_5_IRQHandler - - PUBWEAK TIM1_BRK_TIM9_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_BRK_TIM9_IRQHandler - B TIM1_BRK_TIM9_IRQHandler - - PUBWEAK TIM1_UP_TIM10_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_UP_TIM10_IRQHandler - B TIM1_UP_TIM10_IRQHandler - - PUBWEAK TIM1_TRG_COM_TIM11_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_TRG_COM_TIM11_IRQHandler - B TIM1_TRG_COM_TIM11_IRQHandler - - PUBWEAK TIM1_CC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_CC_IRQHandler - B TIM1_CC_IRQHandler - - PUBWEAK TIM2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM2_IRQHandler - B TIM2_IRQHandler - - PUBWEAK TIM3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM3_IRQHandler - B TIM3_IRQHandler - - PUBWEAK TIM4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM4_IRQHandler - B TIM4_IRQHandler - - PUBWEAK I2C1_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C1_EV_IRQHandler - B I2C1_EV_IRQHandler - - PUBWEAK I2C1_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C1_ER_IRQHandler - B I2C1_ER_IRQHandler - - PUBWEAK I2C2_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C2_EV_IRQHandler - B I2C2_EV_IRQHandler - - PUBWEAK I2C2_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C2_ER_IRQHandler - B I2C2_ER_IRQHandler - - PUBWEAK SPI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI1_IRQHandler - B SPI1_IRQHandler - - PUBWEAK SPI2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI2_IRQHandler - B SPI2_IRQHandler - - PUBWEAK USART1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART1_IRQHandler - B USART1_IRQHandler - - PUBWEAK USART2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART2_IRQHandler - B USART2_IRQHandler - - PUBWEAK USART3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART3_IRQHandler - B USART3_IRQHandler - - PUBWEAK EXTI15_10_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI15_10_IRQHandler - B EXTI15_10_IRQHandler - - PUBWEAK RTC_Alarm_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RTC_Alarm_IRQHandler - B RTC_Alarm_IRQHandler - - PUBWEAK OTG_FS_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_FS_WKUP_IRQHandler - B OTG_FS_WKUP_IRQHandler - - PUBWEAK TIM8_BRK_TIM12_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_BRK_TIM12_IRQHandler - B TIM8_BRK_TIM12_IRQHandler - - PUBWEAK TIM8_UP_TIM13_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_UP_TIM13_IRQHandler - B TIM8_UP_TIM13_IRQHandler - - PUBWEAK TIM8_TRG_COM_TIM14_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_TRG_COM_TIM14_IRQHandler - B TIM8_TRG_COM_TIM14_IRQHandler - - PUBWEAK TIM8_CC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_CC_IRQHandler - B TIM8_CC_IRQHandler - - PUBWEAK DMA1_Stream7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream7_IRQHandler - B DMA1_Stream7_IRQHandler - - PUBWEAK FSMC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FSMC_IRQHandler - B FSMC_IRQHandler - - PUBWEAK SDIO_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SDIO_IRQHandler - B SDIO_IRQHandler - - PUBWEAK TIM5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM5_IRQHandler - B TIM5_IRQHandler - - PUBWEAK SPI3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI3_IRQHandler - B SPI3_IRQHandler - - PUBWEAK UART4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -UART4_IRQHandler - B UART4_IRQHandler - - PUBWEAK UART5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -UART5_IRQHandler - B UART5_IRQHandler - - PUBWEAK TIM6_DAC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM6_DAC_IRQHandler - B TIM6_DAC_IRQHandler - - PUBWEAK TIM7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM7_IRQHandler - B TIM7_IRQHandler - - PUBWEAK DMA2_Stream0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream0_IRQHandler - B DMA2_Stream0_IRQHandler - - PUBWEAK DMA2_Stream1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream1_IRQHandler - B DMA2_Stream1_IRQHandler - - PUBWEAK DMA2_Stream2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream2_IRQHandler - B DMA2_Stream2_IRQHandler - - PUBWEAK DMA2_Stream3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream3_IRQHandler - B DMA2_Stream3_IRQHandler - - PUBWEAK DMA2_Stream4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream4_IRQHandler - B DMA2_Stream4_IRQHandler - - PUBWEAK ETH_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -ETH_IRQHandler - B ETH_IRQHandler - - PUBWEAK ETH_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -ETH_WKUP_IRQHandler - B ETH_WKUP_IRQHandler - - PUBWEAK CAN2_TX_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_TX_IRQHandler - B CAN2_TX_IRQHandler - - PUBWEAK CAN2_RX0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_RX0_IRQHandler - B CAN2_RX0_IRQHandler - - PUBWEAK CAN2_RX1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_RX1_IRQHandler - B CAN2_RX1_IRQHandler - - PUBWEAK CAN2_SCE_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_SCE_IRQHandler - B CAN2_SCE_IRQHandler - - PUBWEAK OTG_FS_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_FS_IRQHandler - B OTG_FS_IRQHandler - - PUBWEAK DMA2_Stream5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream5_IRQHandler - B DMA2_Stream5_IRQHandler - - PUBWEAK DMA2_Stream6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream6_IRQHandler - B DMA2_Stream6_IRQHandler - - PUBWEAK DMA2_Stream7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream7_IRQHandler - B DMA2_Stream7_IRQHandler - - PUBWEAK USART6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART6_IRQHandler - B USART6_IRQHandler - - PUBWEAK I2C3_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C3_EV_IRQHandler - B I2C3_EV_IRQHandler - - PUBWEAK I2C3_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C3_ER_IRQHandler - B I2C3_ER_IRQHandler - - PUBWEAK OTG_HS_EP1_OUT_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_EP1_OUT_IRQHandler - B OTG_HS_EP1_OUT_IRQHandler - - PUBWEAK OTG_HS_EP1_IN_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_EP1_IN_IRQHandler - B OTG_HS_EP1_IN_IRQHandler - - PUBWEAK OTG_HS_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_WKUP_IRQHandler - B OTG_HS_WKUP_IRQHandler - - PUBWEAK OTG_HS_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_IRQHandler - B OTG_HS_IRQHandler - - PUBWEAK DCMI_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DCMI_IRQHandler - B DCMI_IRQHandler - - PUBWEAK CRYP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CRYP_IRQHandler - B CRYP_IRQHandler - - PUBWEAK HASH_RNG_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -HASH_RNG_IRQHandler - B HASH_RNG_IRQHandler - - PUBWEAK FPU_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FPU_IRQHandler - B FPU_IRQHandler - - END -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f40xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f40xx.s deleted file mode 100644 index ea52ca8458..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f40xx.s +++ /dev/null @@ -1,637 +0,0 @@ -;/******************** (C) COPYRIGHT 2015 STMicroelectronics ******************** -;* File Name : startup_stm32f40xx.s -;* Author : MCD Application Team -;* @version : V1.6.1 -;* @date : 21-October-2015 -;* Description : STM32F40xxx/41xxx devices vector table for EWARM toolchain. -;* Same as startup_stm32f40_41xxx.s and maintained for legacy purpose -;* This module performs: -;* - Set the initial SP -;* - Set the initial PC == _iar_program_start, -;* - Set the vector table entries with the exceptions ISR -;* address. -;* - Configure the system clock and the external SRAM mounted on -;* STM324xG-EVAL board 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. -;******************************************************************************** -;* -;* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); -;* You may not use this file except in compliance with the License. -;* You may obtain a copy of the License at: -;* -;* http://www.st.com/software_license_agreement_liberty_v2 -;* -;* Unless required by applicable law or agreed to in writing, software -;* distributed under the License is distributed on an "AS IS" BASIS, -;* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -;* See the License for the specific language governing permissions and -;* limitations under the License. -;* -;*******************************************************************************/ -; -; -; The modules in this file are included in the libraries, and may be replaced -; by any user-defined modules that define the PUBLIC symbol _program_start or -; a user defined start symbol. -; To override the cstartup defined in the library, simply add your modified -; version to the workbench project. -; -; The vector table is normally located at address 0. -; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. -; The name "__vector_table" has special meaning for C-SPY: -; it is where the SP start value is found, and the NVIC vector -; table register (VTOR) is initialized to this address if != 0. -; -; Cortex-M version -; - - MODULE ?cstartup - - ;; Forward declaration of sections. - SECTION CSTACK:DATA:NOROOT(3) - - SECTION .intvec:CODE:NOROOT(2) - - EXTERN __iar_program_start - EXTERN SystemInit - PUBLIC __vector_table - - DATA -__vector_table - DCD sfe(CSTACK) - DCD Reset_Handler ; Reset Handler - - DCD NMI_Handler ; NMI Handler - DCD HardFault_Handler ; Hard Fault Handler - DCD MemManage_Handler ; MPU Fault Handler - DCD BusFault_Handler ; Bus Fault Handler - DCD UsageFault_Handler ; Usage Fault Handler - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SVC_Handler ; SVCall Handler - DCD DebugMon_Handler ; Debug Monitor Handler - DCD 0 ; Reserved - DCD PendSV_Handler ; PendSV Handler - DCD SysTick_Handler ; SysTick Handler - - ; External Interrupts - DCD WWDG_IRQHandler ; Window WatchDog - DCD PVD_IRQHandler ; PVD through EXTI Line detection - DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line - DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line - DCD FLASH_IRQHandler ; FLASH - DCD RCC_IRQHandler ; RCC - DCD EXTI0_IRQHandler ; EXTI Line0 - DCD EXTI1_IRQHandler ; EXTI Line1 - DCD EXTI2_IRQHandler ; EXTI Line2 - DCD EXTI3_IRQHandler ; EXTI Line3 - DCD EXTI4_IRQHandler ; EXTI Line4 - DCD DMA1_Stream0_IRQHandler ; DMA1 Stream 0 - DCD DMA1_Stream1_IRQHandler ; DMA1 Stream 1 - DCD DMA1_Stream2_IRQHandler ; DMA1 Stream 2 - DCD DMA1_Stream3_IRQHandler ; DMA1 Stream 3 - DCD DMA1_Stream4_IRQHandler ; DMA1 Stream 4 - DCD DMA1_Stream5_IRQHandler ; DMA1 Stream 5 - DCD DMA1_Stream6_IRQHandler ; DMA1 Stream 6 - DCD ADC_IRQHandler ; ADC1, ADC2 and ADC3s - DCD CAN1_TX_IRQHandler ; CAN1 TX - DCD CAN1_RX0_IRQHandler ; CAN1 RX0 - DCD CAN1_RX1_IRQHandler ; CAN1 RX1 - DCD CAN1_SCE_IRQHandler ; CAN1 SCE - DCD EXTI9_5_IRQHandler ; External Line[9:5]s - DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 - DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 - DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 - DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare - DCD TIM2_IRQHandler ; TIM2 - DCD TIM3_IRQHandler ; TIM3 - DCD TIM4_IRQHandler ; TIM4 - DCD I2C1_EV_IRQHandler ; I2C1 Event - DCD I2C1_ER_IRQHandler ; I2C1 Error - DCD I2C2_EV_IRQHandler ; I2C2 Event - DCD I2C2_ER_IRQHandler ; I2C2 Error - DCD SPI1_IRQHandler ; SPI1 - DCD SPI2_IRQHandler ; SPI2 - DCD USART1_IRQHandler ; USART1 - DCD USART2_IRQHandler ; USART2 - DCD USART3_IRQHandler ; USART3 - DCD EXTI15_10_IRQHandler ; External Line[15:10]s - DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line - DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line - DCD TIM8_BRK_TIM12_IRQHandler ; TIM8 Break and TIM12 - DCD TIM8_UP_TIM13_IRQHandler ; TIM8 Update and TIM13 - DCD TIM8_TRG_COM_TIM14_IRQHandler ; TIM8 Trigger and Commutation and TIM14 - DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare - DCD DMA1_Stream7_IRQHandler ; DMA1 Stream7 - DCD FSMC_IRQHandler ; FSMC - DCD SDIO_IRQHandler ; SDIO - DCD TIM5_IRQHandler ; TIM5 - DCD SPI3_IRQHandler ; SPI3 - DCD UART4_IRQHandler ; UART4 - DCD UART5_IRQHandler ; UART5 - DCD TIM6_DAC_IRQHandler ; TIM6 and DAC1&2 underrun errors - DCD TIM7_IRQHandler ; TIM7 - DCD DMA2_Stream0_IRQHandler ; DMA2 Stream 0 - DCD DMA2_Stream1_IRQHandler ; DMA2 Stream 1 - DCD DMA2_Stream2_IRQHandler ; DMA2 Stream 2 - DCD DMA2_Stream3_IRQHandler ; DMA2 Stream 3 - DCD DMA2_Stream4_IRQHandler ; DMA2 Stream 4 - DCD ETH_IRQHandler ; Ethernet - DCD ETH_WKUP_IRQHandler ; Ethernet Wakeup through EXTI line - DCD CAN2_TX_IRQHandler ; CAN2 TX - DCD CAN2_RX0_IRQHandler ; CAN2 RX0 - DCD CAN2_RX1_IRQHandler ; CAN2 RX1 - DCD CAN2_SCE_IRQHandler ; CAN2 SCE - DCD OTG_FS_IRQHandler ; USB OTG FS - DCD DMA2_Stream5_IRQHandler ; DMA2 Stream 5 - DCD DMA2_Stream6_IRQHandler ; DMA2 Stream 6 - DCD DMA2_Stream7_IRQHandler ; DMA2 Stream 7 - DCD USART6_IRQHandler ; USART6 - DCD I2C3_EV_IRQHandler ; I2C3 event - DCD I2C3_ER_IRQHandler ; I2C3 error - DCD OTG_HS_EP1_OUT_IRQHandler ; USB OTG HS End Point 1 Out - DCD OTG_HS_EP1_IN_IRQHandler ; USB OTG HS End Point 1 In - DCD OTG_HS_WKUP_IRQHandler ; USB OTG HS Wakeup through EXTI - DCD OTG_HS_IRQHandler ; USB OTG HS - DCD DCMI_IRQHandler ; DCMI - DCD CRYP_IRQHandler ; CRYP crypto - DCD HASH_RNG_IRQHandler ; Hash and Rng - DCD FPU_IRQHandler ; FPU - -;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; -;; -;; Default interrupt handlers. -;; - THUMB - PUBWEAK Reset_Handler - SECTION .text:CODE:REORDER:NOROOT(2) -Reset_Handler - - LDR R0, =SystemInit - BLX R0 - LDR R0, =__iar_program_start - BX R0 - - PUBWEAK NMI_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -NMI_Handler - B NMI_Handler - - PUBWEAK HardFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -HardFault_Handler - B HardFault_Handler - - PUBWEAK MemManage_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -MemManage_Handler - B MemManage_Handler - - PUBWEAK BusFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -BusFault_Handler - B BusFault_Handler - - PUBWEAK UsageFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -UsageFault_Handler - B UsageFault_Handler - - PUBWEAK SVC_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -SVC_Handler - B SVC_Handler - - PUBWEAK DebugMon_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -DebugMon_Handler - B DebugMon_Handler - - PUBWEAK PendSV_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -PendSV_Handler - B PendSV_Handler - - PUBWEAK SysTick_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -SysTick_Handler - B SysTick_Handler - - PUBWEAK WWDG_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -WWDG_IRQHandler - B WWDG_IRQHandler - - PUBWEAK PVD_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -PVD_IRQHandler - B PVD_IRQHandler - - PUBWEAK TAMP_STAMP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TAMP_STAMP_IRQHandler - B TAMP_STAMP_IRQHandler - - PUBWEAK RTC_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RTC_WKUP_IRQHandler - B RTC_WKUP_IRQHandler - - PUBWEAK FLASH_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FLASH_IRQHandler - B FLASH_IRQHandler - - PUBWEAK RCC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RCC_IRQHandler - B RCC_IRQHandler - - PUBWEAK EXTI0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI0_IRQHandler - B EXTI0_IRQHandler - - PUBWEAK EXTI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI1_IRQHandler - B EXTI1_IRQHandler - - PUBWEAK EXTI2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI2_IRQHandler - B EXTI2_IRQHandler - - PUBWEAK EXTI3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI3_IRQHandler - B EXTI3_IRQHandler - - PUBWEAK EXTI4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI4_IRQHandler - B EXTI4_IRQHandler - - PUBWEAK DMA1_Stream0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream0_IRQHandler - B DMA1_Stream0_IRQHandler - - PUBWEAK DMA1_Stream1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream1_IRQHandler - B DMA1_Stream1_IRQHandler - - PUBWEAK DMA1_Stream2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream2_IRQHandler - B DMA1_Stream2_IRQHandler - - PUBWEAK DMA1_Stream3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream3_IRQHandler - B DMA1_Stream3_IRQHandler - - PUBWEAK DMA1_Stream4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream4_IRQHandler - B DMA1_Stream4_IRQHandler - - PUBWEAK DMA1_Stream5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream5_IRQHandler - B DMA1_Stream5_IRQHandler - - PUBWEAK DMA1_Stream6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream6_IRQHandler - B DMA1_Stream6_IRQHandler - - PUBWEAK ADC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -ADC_IRQHandler - B ADC_IRQHandler - - PUBWEAK CAN1_TX_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_TX_IRQHandler - B CAN1_TX_IRQHandler - - PUBWEAK CAN1_RX0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_RX0_IRQHandler - B CAN1_RX0_IRQHandler - - PUBWEAK CAN1_RX1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_RX1_IRQHandler - B CAN1_RX1_IRQHandler - - PUBWEAK CAN1_SCE_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_SCE_IRQHandler - B CAN1_SCE_IRQHandler - - PUBWEAK EXTI9_5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI9_5_IRQHandler - B EXTI9_5_IRQHandler - - PUBWEAK TIM1_BRK_TIM9_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_BRK_TIM9_IRQHandler - B TIM1_BRK_TIM9_IRQHandler - - PUBWEAK TIM1_UP_TIM10_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_UP_TIM10_IRQHandler - B TIM1_UP_TIM10_IRQHandler - - PUBWEAK TIM1_TRG_COM_TIM11_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_TRG_COM_TIM11_IRQHandler - B TIM1_TRG_COM_TIM11_IRQHandler - - PUBWEAK TIM1_CC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_CC_IRQHandler - B TIM1_CC_IRQHandler - - PUBWEAK TIM2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM2_IRQHandler - B TIM2_IRQHandler - - PUBWEAK TIM3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM3_IRQHandler - B TIM3_IRQHandler - - PUBWEAK TIM4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM4_IRQHandler - B TIM4_IRQHandler - - PUBWEAK I2C1_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C1_EV_IRQHandler - B I2C1_EV_IRQHandler - - PUBWEAK I2C1_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C1_ER_IRQHandler - B I2C1_ER_IRQHandler - - PUBWEAK I2C2_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C2_EV_IRQHandler - B I2C2_EV_IRQHandler - - PUBWEAK I2C2_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C2_ER_IRQHandler - B I2C2_ER_IRQHandler - - PUBWEAK SPI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI1_IRQHandler - B SPI1_IRQHandler - - PUBWEAK SPI2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI2_IRQHandler - B SPI2_IRQHandler - - PUBWEAK USART1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART1_IRQHandler - B USART1_IRQHandler - - PUBWEAK USART2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART2_IRQHandler - B USART2_IRQHandler - - PUBWEAK USART3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART3_IRQHandler - B USART3_IRQHandler - - PUBWEAK EXTI15_10_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI15_10_IRQHandler - B EXTI15_10_IRQHandler - - PUBWEAK RTC_Alarm_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RTC_Alarm_IRQHandler - B RTC_Alarm_IRQHandler - - PUBWEAK OTG_FS_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_FS_WKUP_IRQHandler - B OTG_FS_WKUP_IRQHandler - - PUBWEAK TIM8_BRK_TIM12_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_BRK_TIM12_IRQHandler - B TIM8_BRK_TIM12_IRQHandler - - PUBWEAK TIM8_UP_TIM13_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_UP_TIM13_IRQHandler - B TIM8_UP_TIM13_IRQHandler - - PUBWEAK TIM8_TRG_COM_TIM14_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_TRG_COM_TIM14_IRQHandler - B TIM8_TRG_COM_TIM14_IRQHandler - - PUBWEAK TIM8_CC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_CC_IRQHandler - B TIM8_CC_IRQHandler - - PUBWEAK DMA1_Stream7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream7_IRQHandler - B DMA1_Stream7_IRQHandler - - PUBWEAK FSMC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FSMC_IRQHandler - B FSMC_IRQHandler - - PUBWEAK SDIO_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SDIO_IRQHandler - B SDIO_IRQHandler - - PUBWEAK TIM5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM5_IRQHandler - B TIM5_IRQHandler - - PUBWEAK SPI3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI3_IRQHandler - B SPI3_IRQHandler - - PUBWEAK UART4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -UART4_IRQHandler - B UART4_IRQHandler - - PUBWEAK UART5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -UART5_IRQHandler - B UART5_IRQHandler - - PUBWEAK TIM6_DAC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM6_DAC_IRQHandler - B TIM6_DAC_IRQHandler - - PUBWEAK TIM7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM7_IRQHandler - B TIM7_IRQHandler - - PUBWEAK DMA2_Stream0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream0_IRQHandler - B DMA2_Stream0_IRQHandler - - PUBWEAK DMA2_Stream1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream1_IRQHandler - B DMA2_Stream1_IRQHandler - - PUBWEAK DMA2_Stream2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream2_IRQHandler - B DMA2_Stream2_IRQHandler - - PUBWEAK DMA2_Stream3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream3_IRQHandler - B DMA2_Stream3_IRQHandler - - PUBWEAK DMA2_Stream4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream4_IRQHandler - B DMA2_Stream4_IRQHandler - - PUBWEAK ETH_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -ETH_IRQHandler - B ETH_IRQHandler - - PUBWEAK ETH_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -ETH_WKUP_IRQHandler - B ETH_WKUP_IRQHandler - - PUBWEAK CAN2_TX_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_TX_IRQHandler - B CAN2_TX_IRQHandler - - PUBWEAK CAN2_RX0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_RX0_IRQHandler - B CAN2_RX0_IRQHandler - - PUBWEAK CAN2_RX1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_RX1_IRQHandler - B CAN2_RX1_IRQHandler - - PUBWEAK CAN2_SCE_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_SCE_IRQHandler - B CAN2_SCE_IRQHandler - - PUBWEAK OTG_FS_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_FS_IRQHandler - B OTG_FS_IRQHandler - - PUBWEAK DMA2_Stream5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream5_IRQHandler - B DMA2_Stream5_IRQHandler - - PUBWEAK DMA2_Stream6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream6_IRQHandler - B DMA2_Stream6_IRQHandler - - PUBWEAK DMA2_Stream7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream7_IRQHandler - B DMA2_Stream7_IRQHandler - - PUBWEAK USART6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART6_IRQHandler - B USART6_IRQHandler - - PUBWEAK I2C3_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C3_EV_IRQHandler - B I2C3_EV_IRQHandler - - PUBWEAK I2C3_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C3_ER_IRQHandler - B I2C3_ER_IRQHandler - - PUBWEAK OTG_HS_EP1_OUT_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_EP1_OUT_IRQHandler - B OTG_HS_EP1_OUT_IRQHandler - - PUBWEAK OTG_HS_EP1_IN_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_EP1_IN_IRQHandler - B OTG_HS_EP1_IN_IRQHandler - - PUBWEAK OTG_HS_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_WKUP_IRQHandler - B OTG_HS_WKUP_IRQHandler - - PUBWEAK OTG_HS_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_IRQHandler - B OTG_HS_IRQHandler - - PUBWEAK DCMI_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DCMI_IRQHandler - B DCMI_IRQHandler - - PUBWEAK CRYP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CRYP_IRQHandler - B CRYP_IRQHandler - - PUBWEAK HASH_RNG_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -HASH_RNG_IRQHandler - B HASH_RNG_IRQHandler - - PUBWEAK FPU_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FPU_IRQHandler - B FPU_IRQHandler - - END -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f410xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f410xx.s deleted file mode 100644 index 735e5dc96d..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f410xx.s +++ /dev/null @@ -1,510 +0,0 @@ -;/******************** (C) COPYRIGHT 2015 STMicroelectronics ******************** -;* File Name : startup_stm32f410xx.s -;* Author : MCD Application Team -;* @version : V1.6.1 -;* @date : 21-October-2015 -;* Description : STM32F410xx devices vector table for EWARM toolchain. -;* This module performs: -;* - Set the initial SP -;* - Set the initial PC == _iar_program_start, -;* - Set the vector table entries with the exceptions ISR -;* address. -;* - Configure the system clock -;* - 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. -;******************************************************************************** -;* -;* Redistribution and use in source and binary forms, with or without modification, -;* are permitted provided that the following conditions are met: -;* 1. Redistributions of source code must retain the above copyright notice, -;* this list of conditions and the following disclaimer. -;* 2. Redistributions in binary form must reproduce the above copyright notice, -;* this list of conditions and the following disclaimer in the documentation -;* and/or other materials provided with the distribution. -;* 3. Neither the name of STMicroelectronics nor the names of its contributors -;* may be used to endorse or promote products derived from this software -;* without specific prior written permission. -;* -;* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -;* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE -;* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL -;* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -;* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -;* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, -;* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE -;* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -;* -;******************************************************************************* -; -; -; The modules in this file are included in the libraries, and may be replaced -; by any user-defined modules that define the PUBLIC symbol _program_start or -; a user defined start symbol. -; To override the cstartup defined in the library, simply add your modified -; version to the workbench project. -; -; The vector table is normally located at address 0. -; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. -; The name "__vector_table" has special meaning for C-SPY: -; it is where the SP start value is found, and the NVIC vector -; table register (VTOR) is initialized to this address if != 0. -; -; Cortex-M version -; - - MODULE ?cstartup - - ;; Forward declaration of sections. - SECTION CSTACK:DATA:NOROOT(3) - - SECTION .intvec:CODE:NOROOT(2) - - EXTERN __iar_program_start - EXTERN SystemInit - PUBLIC __vector_table - - DATA -__vector_table - DCD sfe(CSTACK) - DCD Reset_Handler ; Reset Handler - - DCD NMI_Handler ; NMI Handler - DCD HardFault_Handler ; Hard Fault Handler - DCD MemManage_Handler ; MPU Fault Handler - DCD BusFault_Handler ; Bus Fault Handler - DCD UsageFault_Handler ; Usage Fault Handler - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SVC_Handler ; SVCall Handler - DCD DebugMon_Handler ; Debug Monitor Handler - DCD 0 ; Reserved - DCD PendSV_Handler ; PendSV Handler - DCD SysTick_Handler ; SysTick Handler - - ; External Interrupts - DCD WWDG_IRQHandler ; Window WatchDog - DCD PVD_IRQHandler ; PVD through EXTI Line detection - DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line - DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line - DCD FLASH_IRQHandler ; FLASH - DCD RCC_IRQHandler ; RCC - DCD EXTI0_IRQHandler ; EXTI Line0 - DCD EXTI1_IRQHandler ; EXTI Line1 - DCD EXTI2_IRQHandler ; EXTI Line2 - DCD EXTI3_IRQHandler ; EXTI Line3 - DCD EXTI4_IRQHandler ; EXTI Line4 - DCD DMA1_Stream0_IRQHandler ; DMA1 Stream 0 - DCD DMA1_Stream1_IRQHandler ; DMA1 Stream 1 - DCD DMA1_Stream2_IRQHandler ; DMA1 Stream 2 - DCD DMA1_Stream3_IRQHandler ; DMA1 Stream 3 - DCD DMA1_Stream4_IRQHandler ; DMA1 Stream 4 - DCD DMA1_Stream5_IRQHandler ; DMA1 Stream 5 - DCD DMA1_Stream6_IRQHandler ; DMA1 Stream 6 - DCD ADC_IRQHandler ; ADC1 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD EXTI9_5_IRQHandler ; External Line[9:5]s - DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 - DCD TIM1_UP_IRQHandler ; TIM1 Update - DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 - DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD I2C1_EV_IRQHandler ; I2C1 Event - DCD I2C1_ER_IRQHandler ; I2C1 Error - DCD I2C2_EV_IRQHandler ; I2C2 Event - DCD I2C2_ER_IRQHandler ; I2C2 Error - DCD SPI1_IRQHandler ; SPI1 - DCD SPI2_IRQHandler ; SPI2 - DCD USART1_IRQHandler ; USART1 - DCD USART2_IRQHandler ; USART2 - DCD 0 ; Reserved - DCD EXTI15_10_IRQHandler ; External Line[15:10]s - DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD DMA1_Stream7_IRQHandler ; DMA1 Stream7 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD TIM5_IRQHandler ; TIM5 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD TIM6_DAC_IRQHandler ; TIM6 and DAC - DCD 0 ; Reserved - DCD DMA2_Stream0_IRQHandler ; DMA2 Stream 0 - DCD DMA2_Stream1_IRQHandler ; DMA2 Stream 1 - DCD DMA2_Stream2_IRQHandler ; DMA2 Stream 2 - DCD DMA2_Stream3_IRQHandler ; DMA2 Stream 3 - DCD DMA2_Stream4_IRQHandler ; DMA2 Stream 4 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD DMA2_Stream5_IRQHandler ; DMA2 Stream 5 - DCD DMA2_Stream6_IRQHandler ; DMA2 Stream 6 - DCD DMA2_Stream7_IRQHandler ; DMA2 Stream 7 - DCD USART6_IRQHandler ; USART6 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD RNG_IRQHandler ; RNG - DCD FPU_IRQHandler ; FPU - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SPI5_IRQHandler ; SPI5 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD FMPI2C1_EV_IRQHandler ; FMPI2C1 Event - DCD FMPI2C1_ER_IRQHandler ; FMPI2C1 Error - DCD LPTIM1_IRQHandler ; LP TIM1 - -;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; -;; -;; Default interrupt handlers. -;; - THUMB - PUBWEAK Reset_Handler - SECTION .text:CODE:REORDER:NOROOT(2) -Reset_Handler - - LDR R0, =SystemInit - BLX R0 - LDR R0, =__iar_program_start - BX R0 - - PUBWEAK NMI_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -NMI_Handler - B NMI_Handler - - PUBWEAK HardFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -HardFault_Handler - B HardFault_Handler - - PUBWEAK MemManage_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -MemManage_Handler - B MemManage_Handler - - PUBWEAK BusFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -BusFault_Handler - B BusFault_Handler - - PUBWEAK UsageFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -UsageFault_Handler - B UsageFault_Handler - - PUBWEAK SVC_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -SVC_Handler - B SVC_Handler - - PUBWEAK DebugMon_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -DebugMon_Handler - B DebugMon_Handler - - PUBWEAK PendSV_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -PendSV_Handler - B PendSV_Handler - - PUBWEAK SysTick_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -SysTick_Handler - B SysTick_Handler - - PUBWEAK WWDG_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -WWDG_IRQHandler - B WWDG_IRQHandler - - PUBWEAK PVD_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -PVD_IRQHandler - B PVD_IRQHandler - - PUBWEAK TAMP_STAMP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TAMP_STAMP_IRQHandler - B TAMP_STAMP_IRQHandler - - PUBWEAK RTC_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RTC_WKUP_IRQHandler - B RTC_WKUP_IRQHandler - - PUBWEAK FLASH_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FLASH_IRQHandler - B FLASH_IRQHandler - - PUBWEAK RCC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RCC_IRQHandler - B RCC_IRQHandler - - PUBWEAK EXTI0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI0_IRQHandler - B EXTI0_IRQHandler - - PUBWEAK EXTI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI1_IRQHandler - B EXTI1_IRQHandler - - PUBWEAK EXTI2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI2_IRQHandler - B EXTI2_IRQHandler - - PUBWEAK EXTI3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI3_IRQHandler - B EXTI3_IRQHandler - - PUBWEAK EXTI4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI4_IRQHandler - B EXTI4_IRQHandler - - PUBWEAK DMA1_Stream0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream0_IRQHandler - B DMA1_Stream0_IRQHandler - - PUBWEAK DMA1_Stream1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream1_IRQHandler - B DMA1_Stream1_IRQHandler - - PUBWEAK DMA1_Stream2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream2_IRQHandler - B DMA1_Stream2_IRQHandler - - PUBWEAK DMA1_Stream3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream3_IRQHandler - B DMA1_Stream3_IRQHandler - - PUBWEAK DMA1_Stream4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream4_IRQHandler - B DMA1_Stream4_IRQHandler - - PUBWEAK DMA1_Stream5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream5_IRQHandler - B DMA1_Stream5_IRQHandler - - PUBWEAK DMA1_Stream6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream6_IRQHandler - B DMA1_Stream6_IRQHandler - - PUBWEAK ADC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -ADC_IRQHandler - B ADC_IRQHandler - - PUBWEAK EXTI9_5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI9_5_IRQHandler - B EXTI9_5_IRQHandler - - PUBWEAK TIM1_BRK_TIM9_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_BRK_TIM9_IRQHandler - B TIM1_BRK_TIM9_IRQHandler - - PUBWEAK TIM1_UP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_UP_IRQHandler - B TIM1_UP_IRQHandler - - PUBWEAK TIM1_TRG_COM_TIM11_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_TRG_COM_TIM11_IRQHandler - B TIM1_TRG_COM_TIM11_IRQHandler - - PUBWEAK TIM1_CC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_CC_IRQHandler - B TIM1_CC_IRQHandler - - PUBWEAK I2C1_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C1_EV_IRQHandler - B I2C1_EV_IRQHandler - - PUBWEAK I2C1_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C1_ER_IRQHandler - B I2C1_ER_IRQHandler - - PUBWEAK I2C2_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C2_EV_IRQHandler - B I2C2_EV_IRQHandler - - PUBWEAK I2C2_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C2_ER_IRQHandler - B I2C2_ER_IRQHandler - - PUBWEAK SPI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI1_IRQHandler - B SPI1_IRQHandler - - PUBWEAK SPI2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI2_IRQHandler - B SPI2_IRQHandler - - PUBWEAK USART1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART1_IRQHandler - B USART1_IRQHandler - - PUBWEAK USART2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART2_IRQHandler - B USART2_IRQHandler - - PUBWEAK EXTI15_10_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI15_10_IRQHandler - B EXTI15_10_IRQHandler - - PUBWEAK RTC_Alarm_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RTC_Alarm_IRQHandler - B RTC_Alarm_IRQHandler - - PUBWEAK DMA1_Stream7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream7_IRQHandler - B DMA1_Stream7_IRQHandler - - PUBWEAK TIM5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM5_IRQHandler - B TIM5_IRQHandler - - PUBWEAK TIM6_DAC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM6_DAC_IRQHandler - B TIM6_DAC_IRQHandler - - PUBWEAK DMA2_Stream0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream0_IRQHandler - B DMA2_Stream0_IRQHandler - - PUBWEAK DMA2_Stream1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream1_IRQHandler - B DMA2_Stream1_IRQHandler - - PUBWEAK DMA2_Stream2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream2_IRQHandler - B DMA2_Stream2_IRQHandler - - PUBWEAK DMA2_Stream3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream3_IRQHandler - B DMA2_Stream3_IRQHandler - - PUBWEAK DMA2_Stream4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream4_IRQHandler - B DMA2_Stream4_IRQHandler - - PUBWEAK DMA2_Stream5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream5_IRQHandler - B DMA2_Stream5_IRQHandler - - PUBWEAK DMA2_Stream6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream6_IRQHandler - B DMA2_Stream6_IRQHandler - - PUBWEAK DMA2_Stream7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream7_IRQHandler - B DMA2_Stream7_IRQHandler - - PUBWEAK USART6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART6_IRQHandler - B USART6_IRQHandler - - PUBWEAK RNG_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RNG_IRQHandler - B RNG_IRQHandler - - PUBWEAK FPU_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FPU_IRQHandler - B FPU_IRQHandler - - PUBWEAK SPI5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI5_IRQHandler - B SPI5_IRQHandler - - PUBWEAK FMPI2C1_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FMPI2C1_EV_IRQHandler - B FMPI2C1_EV_IRQHandler - - PUBWEAK FMPI2C1_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FMPI2C1_ER_IRQHandler - B FMPI2C1_ER_IRQHandler - - PUBWEAK LPTIM1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -LPTIM1_IRQHandler - B LPTIM1_IRQHandler - - END -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f411xe.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f411xe.s deleted file mode 100644 index aac0cf4cd9..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f411xe.s +++ /dev/null @@ -1,513 +0,0 @@ -;/******************** (C) COPYRIGHT 2015 STMicroelectronics ******************** -;* File Name : startup_stm32f411xe.s -;* Author : MCD Application Team -;* @version : V1.6.1 -;* @date : 21-October-2015 -;* Description : STM32F401xx devices vector table for EWARM toolchain. -;* This module performs: -;* - Set the initial SP -;* - Set the initial PC == _iar_program_start, -;* - Set the vector table entries with the exceptions ISR -;* address. -;* - Configure the system clock -;* - 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. -;******************************************************************************** -;* -;* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); -;* You may not use this file except in compliance with the License. -;* You may obtain a copy of the License at: -;* -;* http://www.st.com/software_license_agreement_liberty_v2 -;* -;* Unless required by applicable law or agreed to in writing, software -;* distributed under the License is distributed on an "AS IS" BASIS, -;* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -;* See the License for the specific language governing permissions and -;* limitations under the License. -;* -;*******************************************************************************/ -; -; -; The modules in this file are included in the libraries, and may be replaced -; by any user-defined modules that define the PUBLIC symbol _program_start or -; a user defined start symbol. -; To override the cstartup defined in the library, simply add your modified -; version to the workbench project. -; -; The vector table is normally located at address 0. -; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. -; The name "__vector_table" has special meaning for C-SPY: -; it is where the SP start value is found, and the NVIC vector -; table register (VTOR) is initialized to this address if != 0. -; -; Cortex-M version -; - - MODULE ?cstartup - - ;; Forward declaration of sections. - SECTION CSTACK:DATA:NOROOT(3) - - SECTION .intvec:CODE:NOROOT(2) - - EXTERN __iar_program_start - EXTERN SystemInit - PUBLIC __vector_table - - DATA -__vector_table - DCD sfe(CSTACK) - DCD Reset_Handler ; Reset Handler - - DCD NMI_Handler ; NMI Handler - DCD HardFault_Handler ; Hard Fault Handler - DCD MemManage_Handler ; MPU Fault Handler - DCD BusFault_Handler ; Bus Fault Handler - DCD UsageFault_Handler ; Usage Fault Handler - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SVC_Handler ; SVCall Handler - DCD DebugMon_Handler ; Debug Monitor Handler - DCD 0 ; Reserved - DCD PendSV_Handler ; PendSV Handler - DCD SysTick_Handler ; SysTick Handler - - ; External Interrupts - DCD WWDG_IRQHandler ; Window WatchDog - DCD PVD_IRQHandler ; PVD through EXTI Line detection - DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line - DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line - DCD FLASH_IRQHandler ; FLASH - DCD RCC_IRQHandler ; RCC - DCD EXTI0_IRQHandler ; EXTI Line0 - DCD EXTI1_IRQHandler ; EXTI Line1 - DCD EXTI2_IRQHandler ; EXTI Line2 - DCD EXTI3_IRQHandler ; EXTI Line3 - DCD EXTI4_IRQHandler ; EXTI Line4 - DCD DMA1_Stream0_IRQHandler ; DMA1 Stream 0 - DCD DMA1_Stream1_IRQHandler ; DMA1 Stream 1 - DCD DMA1_Stream2_IRQHandler ; DMA1 Stream 2 - DCD DMA1_Stream3_IRQHandler ; DMA1 Stream 3 - DCD DMA1_Stream4_IRQHandler ; DMA1 Stream 4 - DCD DMA1_Stream5_IRQHandler ; DMA1 Stream 5 - DCD DMA1_Stream6_IRQHandler ; DMA1 Stream 6 - DCD ADC_IRQHandler ; ADC1 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD EXTI9_5_IRQHandler ; External Line[9:5]s - DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 - DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 - DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 - DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare - DCD TIM2_IRQHandler ; TIM2 - DCD TIM3_IRQHandler ; TIM3 - DCD TIM4_IRQHandler ; TIM4 - DCD I2C1_EV_IRQHandler ; I2C1 Event - DCD I2C1_ER_IRQHandler ; I2C1 Error - DCD I2C2_EV_IRQHandler ; I2C2 Event - DCD I2C2_ER_IRQHandler ; I2C2 Error - DCD SPI1_IRQHandler ; SPI1 - DCD SPI2_IRQHandler ; SPI2 - DCD USART1_IRQHandler ; USART1 - DCD USART2_IRQHandler ; USART2 - DCD 0 ; Reserved - DCD EXTI15_10_IRQHandler ; External Line[15:10]s - DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line - DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD DMA1_Stream7_IRQHandler ; DMA1 Stream7 - DCD 0 ; Reserved - DCD SDIO_IRQHandler ; SDIO - DCD TIM5_IRQHandler ; TIM5 - DCD SPI3_IRQHandler ; SPI3 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD DMA2_Stream0_IRQHandler ; DMA2 Stream 0 - DCD DMA2_Stream1_IRQHandler ; DMA2 Stream 1 - DCD DMA2_Stream2_IRQHandler ; DMA2 Stream 2 - DCD DMA2_Stream3_IRQHandler ; DMA2 Stream 3 - DCD DMA2_Stream4_IRQHandler ; DMA2 Stream 4 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD OTG_FS_IRQHandler ; USB OTG FS - DCD DMA2_Stream5_IRQHandler ; DMA2 Stream 5 - DCD DMA2_Stream6_IRQHandler ; DMA2 Stream 6 - DCD DMA2_Stream7_IRQHandler ; DMA2 Stream 7 - DCD USART6_IRQHandler ; USART6 - DCD I2C3_EV_IRQHandler ; I2C3 event - DCD I2C3_ER_IRQHandler ; I2C3 error - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD FPU_IRQHandler ; FPU - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SPI4_IRQHandler ; SPI4 - DCD SPI5_IRQHandler ; SPI5 - -;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; -;; -;; Default interrupt handlers. -;; - THUMB - PUBWEAK Reset_Handler - SECTION .text:CODE:REORDER:NOROOT(2) -Reset_Handler - - LDR R0, =SystemInit - BLX R0 - LDR R0, =__iar_program_start - BX R0 - - PUBWEAK NMI_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -NMI_Handler - B NMI_Handler - - PUBWEAK HardFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -HardFault_Handler - B HardFault_Handler - - PUBWEAK MemManage_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -MemManage_Handler - B MemManage_Handler - - PUBWEAK BusFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -BusFault_Handler - B BusFault_Handler - - PUBWEAK UsageFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -UsageFault_Handler - B UsageFault_Handler - - PUBWEAK SVC_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -SVC_Handler - B SVC_Handler - - PUBWEAK DebugMon_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -DebugMon_Handler - B DebugMon_Handler - - PUBWEAK PendSV_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -PendSV_Handler - B PendSV_Handler - - PUBWEAK SysTick_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -SysTick_Handler - B SysTick_Handler - - PUBWEAK WWDG_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -WWDG_IRQHandler - B WWDG_IRQHandler - - PUBWEAK PVD_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -PVD_IRQHandler - B PVD_IRQHandler - - PUBWEAK TAMP_STAMP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TAMP_STAMP_IRQHandler - B TAMP_STAMP_IRQHandler - - PUBWEAK RTC_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RTC_WKUP_IRQHandler - B RTC_WKUP_IRQHandler - - PUBWEAK FLASH_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FLASH_IRQHandler - B FLASH_IRQHandler - - PUBWEAK RCC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RCC_IRQHandler - B RCC_IRQHandler - - PUBWEAK EXTI0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI0_IRQHandler - B EXTI0_IRQHandler - - PUBWEAK EXTI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI1_IRQHandler - B EXTI1_IRQHandler - - PUBWEAK EXTI2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI2_IRQHandler - B EXTI2_IRQHandler - - PUBWEAK EXTI3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI3_IRQHandler - B EXTI3_IRQHandler - - PUBWEAK EXTI4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI4_IRQHandler - B EXTI4_IRQHandler - - PUBWEAK DMA1_Stream0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream0_IRQHandler - B DMA1_Stream0_IRQHandler - - PUBWEAK DMA1_Stream1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream1_IRQHandler - B DMA1_Stream1_IRQHandler - - PUBWEAK DMA1_Stream2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream2_IRQHandler - B DMA1_Stream2_IRQHandler - - PUBWEAK DMA1_Stream3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream3_IRQHandler - B DMA1_Stream3_IRQHandler - - PUBWEAK DMA1_Stream4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream4_IRQHandler - B DMA1_Stream4_IRQHandler - - PUBWEAK DMA1_Stream5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream5_IRQHandler - B DMA1_Stream5_IRQHandler - - PUBWEAK DMA1_Stream6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream6_IRQHandler - B DMA1_Stream6_IRQHandler - - PUBWEAK ADC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -ADC_IRQHandler - B ADC_IRQHandler - - PUBWEAK EXTI9_5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI9_5_IRQHandler - B EXTI9_5_IRQHandler - - PUBWEAK TIM1_BRK_TIM9_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_BRK_TIM9_IRQHandler - B TIM1_BRK_TIM9_IRQHandler - - PUBWEAK TIM1_UP_TIM10_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_UP_TIM10_IRQHandler - B TIM1_UP_TIM10_IRQHandler - - PUBWEAK TIM1_TRG_COM_TIM11_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_TRG_COM_TIM11_IRQHandler - B TIM1_TRG_COM_TIM11_IRQHandler - - PUBWEAK TIM1_CC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_CC_IRQHandler - B TIM1_CC_IRQHandler - - PUBWEAK TIM2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM2_IRQHandler - B TIM2_IRQHandler - - PUBWEAK TIM3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM3_IRQHandler - B TIM3_IRQHandler - - PUBWEAK TIM4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM4_IRQHandler - B TIM4_IRQHandler - - PUBWEAK I2C1_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C1_EV_IRQHandler - B I2C1_EV_IRQHandler - - PUBWEAK I2C1_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C1_ER_IRQHandler - B I2C1_ER_IRQHandler - - PUBWEAK I2C2_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C2_EV_IRQHandler - B I2C2_EV_IRQHandler - - PUBWEAK I2C2_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C2_ER_IRQHandler - B I2C2_ER_IRQHandler - - PUBWEAK SPI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI1_IRQHandler - B SPI1_IRQHandler - - PUBWEAK SPI2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI2_IRQHandler - B SPI2_IRQHandler - - PUBWEAK USART1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART1_IRQHandler - B USART1_IRQHandler - - PUBWEAK USART2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART2_IRQHandler - B USART2_IRQHandler - - PUBWEAK EXTI15_10_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI15_10_IRQHandler - B EXTI15_10_IRQHandler - - PUBWEAK RTC_Alarm_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RTC_Alarm_IRQHandler - B RTC_Alarm_IRQHandler - - PUBWEAK OTG_FS_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_FS_WKUP_IRQHandler - B OTG_FS_WKUP_IRQHandler - - PUBWEAK DMA1_Stream7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream7_IRQHandler - B DMA1_Stream7_IRQHandler - - PUBWEAK SDIO_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SDIO_IRQHandler - B SDIO_IRQHandler - - PUBWEAK TIM5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM5_IRQHandler - B TIM5_IRQHandler - - PUBWEAK SPI3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI3_IRQHandler - B SPI3_IRQHandler - - PUBWEAK DMA2_Stream0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream0_IRQHandler - B DMA2_Stream0_IRQHandler - - PUBWEAK DMA2_Stream1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream1_IRQHandler - B DMA2_Stream1_IRQHandler - - PUBWEAK DMA2_Stream2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream2_IRQHandler - B DMA2_Stream2_IRQHandler - - PUBWEAK DMA2_Stream3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream3_IRQHandler - B DMA2_Stream3_IRQHandler - - PUBWEAK DMA2_Stream4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream4_IRQHandler - B DMA2_Stream4_IRQHandler - - PUBWEAK OTG_FS_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_FS_IRQHandler - B OTG_FS_IRQHandler - - PUBWEAK DMA2_Stream5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream5_IRQHandler - B DMA2_Stream5_IRQHandler - - PUBWEAK DMA2_Stream6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream6_IRQHandler - B DMA2_Stream6_IRQHandler - - PUBWEAK DMA2_Stream7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream7_IRQHandler - B DMA2_Stream7_IRQHandler - - PUBWEAK USART6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART6_IRQHandler - B USART6_IRQHandler - - PUBWEAK I2C3_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C3_EV_IRQHandler - B I2C3_EV_IRQHandler - - PUBWEAK I2C3_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C3_ER_IRQHandler - B I2C3_ER_IRQHandler - - PUBWEAK FPU_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FPU_IRQHandler - B FPU_IRQHandler - - PUBWEAK SPI4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI4_IRQHandler - B SPI4_IRQHandler - - PUBWEAK SPI5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI5_IRQHandler - B SPI5_IRQHandler - - END -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f427_437xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f427_437xx.s deleted file mode 100644 index b715333acd..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f427_437xx.s +++ /dev/null @@ -1,681 +0,0 @@ -;/******************** (C) COPYRIGHT 2015 STMicroelectronics ******************** -;* File Name : startup_stm32f427_437xx.s -;* Author : MCD Application Team -;* @version : V1.6.1 -;* @date : 21-October-2015 -;* Description : STM32F427xx/437xx devices vector table for EWARM toolchain. -;* This module performs: -;* - Set the initial SP -;* - Set the initial PC == _iar_program_start, -;* - Set the vector table entries with the exceptions ISR -;* address. -;* - Configure the system clock and the external SRAM/SDRAM mounted -;* on STM324x7I-EVAL board 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. -;******************************************************************************** -;* -;* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); -;* You may not use this file except in compliance with the License. -;* You may obtain a copy of the License at: -;* -;* http://www.st.com/software_license_agreement_liberty_v2 -;* -;* Unless required by applicable law or agreed to in writing, software -;* distributed under the License is distributed on an "AS IS" BASIS, -;* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -;* See the License for the specific language governing permissions and -;* limitations under the License. -;* -;*******************************************************************************/ -; -; -; The modules in this file are included in the libraries, and may be replaced -; by any user-defined modules that define the PUBLIC symbol _program_start or -; a user defined start symbol. -; To override the cstartup defined in the library, simply add your modified -; version to the workbench project. -; -; The vector table is normally located at address 0. -; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. -; The name "__vector_table" has special meaning for C-SPY: -; it is where the SP start value is found, and the NVIC vector -; table register (VTOR) is initialized to this address if != 0. -; -; Cortex-M version -; - - MODULE ?cstartup - - ;; Forward declaration of sections. - SECTION CSTACK:DATA:NOROOT(3) - - SECTION .intvec:CODE:NOROOT(2) - - EXTERN __iar_program_start - EXTERN SystemInit - PUBLIC __vector_table - - DATA -__vector_table - DCD sfe(CSTACK) - DCD Reset_Handler ; Reset Handler - - DCD NMI_Handler ; NMI Handler - DCD HardFault_Handler ; Hard Fault Handler - DCD MemManage_Handler ; MPU Fault Handler - DCD BusFault_Handler ; Bus Fault Handler - DCD UsageFault_Handler ; Usage Fault Handler - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SVC_Handler ; SVCall Handler - DCD DebugMon_Handler ; Debug Monitor Handler - DCD 0 ; Reserved - DCD PendSV_Handler ; PendSV Handler - DCD SysTick_Handler ; SysTick Handler - - ; External Interrupts - DCD WWDG_IRQHandler ; Window WatchDog - DCD PVD_IRQHandler ; PVD through EXTI Line detection - DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line - DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line - DCD FLASH_IRQHandler ; FLASH - DCD RCC_IRQHandler ; RCC - DCD EXTI0_IRQHandler ; EXTI Line0 - DCD EXTI1_IRQHandler ; EXTI Line1 - DCD EXTI2_IRQHandler ; EXTI Line2 - DCD EXTI3_IRQHandler ; EXTI Line3 - DCD EXTI4_IRQHandler ; EXTI Line4 - DCD DMA1_Stream0_IRQHandler ; DMA1 Stream 0 - DCD DMA1_Stream1_IRQHandler ; DMA1 Stream 1 - DCD DMA1_Stream2_IRQHandler ; DMA1 Stream 2 - DCD DMA1_Stream3_IRQHandler ; DMA1 Stream 3 - DCD DMA1_Stream4_IRQHandler ; DMA1 Stream 4 - DCD DMA1_Stream5_IRQHandler ; DMA1 Stream 5 - DCD DMA1_Stream6_IRQHandler ; DMA1 Stream 6 - DCD ADC_IRQHandler ; ADC1, ADC2 and ADC3s - DCD CAN1_TX_IRQHandler ; CAN1 TX - DCD CAN1_RX0_IRQHandler ; CAN1 RX0 - DCD CAN1_RX1_IRQHandler ; CAN1 RX1 - DCD CAN1_SCE_IRQHandler ; CAN1 SCE - DCD EXTI9_5_IRQHandler ; External Line[9:5]s - DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 - DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 - DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 - DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare - DCD TIM2_IRQHandler ; TIM2 - DCD TIM3_IRQHandler ; TIM3 - DCD TIM4_IRQHandler ; TIM4 - DCD I2C1_EV_IRQHandler ; I2C1 Event - DCD I2C1_ER_IRQHandler ; I2C1 Error - DCD I2C2_EV_IRQHandler ; I2C2 Event - DCD I2C2_ER_IRQHandler ; I2C2 Error - DCD SPI1_IRQHandler ; SPI1 - DCD SPI2_IRQHandler ; SPI2 - DCD USART1_IRQHandler ; USART1 - DCD USART2_IRQHandler ; USART2 - DCD USART3_IRQHandler ; USART3 - DCD EXTI15_10_IRQHandler ; External Line[15:10]s - DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line - DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line - DCD TIM8_BRK_TIM12_IRQHandler ; TIM8 Break and TIM12 - DCD TIM8_UP_TIM13_IRQHandler ; TIM8 Update and TIM13 - DCD TIM8_TRG_COM_TIM14_IRQHandler ; TIM8 Trigger and Commutation and TIM14 - DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare - DCD DMA1_Stream7_IRQHandler ; DMA1 Stream7 - DCD FMC_IRQHandler ; FMC - DCD SDIO_IRQHandler ; SDIO - DCD TIM5_IRQHandler ; TIM5 - DCD SPI3_IRQHandler ; SPI3 - DCD UART4_IRQHandler ; UART4 - DCD UART5_IRQHandler ; UART5 - DCD TIM6_DAC_IRQHandler ; TIM6 and DAC1&2 underrun errors - DCD TIM7_IRQHandler ; TIM7 - DCD DMA2_Stream0_IRQHandler ; DMA2 Stream 0 - DCD DMA2_Stream1_IRQHandler ; DMA2 Stream 1 - DCD DMA2_Stream2_IRQHandler ; DMA2 Stream 2 - DCD DMA2_Stream3_IRQHandler ; DMA2 Stream 3 - DCD DMA2_Stream4_IRQHandler ; DMA2 Stream 4 - DCD ETH_IRQHandler ; Ethernet - DCD ETH_WKUP_IRQHandler ; Ethernet Wakeup through EXTI line - DCD CAN2_TX_IRQHandler ; CAN2 TX - DCD CAN2_RX0_IRQHandler ; CAN2 RX0 - DCD CAN2_RX1_IRQHandler ; CAN2 RX1 - DCD CAN2_SCE_IRQHandler ; CAN2 SCE - DCD OTG_FS_IRQHandler ; USB OTG FS - DCD DMA2_Stream5_IRQHandler ; DMA2 Stream 5 - DCD DMA2_Stream6_IRQHandler ; DMA2 Stream 6 - DCD DMA2_Stream7_IRQHandler ; DMA2 Stream 7 - DCD USART6_IRQHandler ; USART6 - DCD I2C3_EV_IRQHandler ; I2C3 event - DCD I2C3_ER_IRQHandler ; I2C3 error - DCD OTG_HS_EP1_OUT_IRQHandler ; USB OTG HS End Point 1 Out - DCD OTG_HS_EP1_IN_IRQHandler ; USB OTG HS End Point 1 In - DCD OTG_HS_WKUP_IRQHandler ; USB OTG HS Wakeup through EXTI - DCD OTG_HS_IRQHandler ; USB OTG HS - DCD DCMI_IRQHandler ; DCMI - DCD CRYP_IRQHandler ; CRYP crypto - DCD HASH_RNG_IRQHandler ; Hash and Rng - DCD FPU_IRQHandler ; FPU - DCD UART7_IRQHandler ; UART7 - DCD UART8_IRQHandler ; UART8 - DCD SPI4_IRQHandler ; SPI4 - DCD SPI5_IRQHandler ; SPI5 - DCD SPI6_IRQHandler ; SPI6 - DCD SAI1_IRQHandler ; SAI1 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD DMA2D_IRQHandler ; DMA2D - -;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; -;; -;; Default interrupt handlers. -;; - THUMB - PUBWEAK Reset_Handler - SECTION .text:CODE:REORDER:NOROOT(2) -Reset_Handler - - LDR R0, =SystemInit - BLX R0 - LDR R0, =__iar_program_start - BX R0 - - PUBWEAK NMI_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -NMI_Handler - B NMI_Handler - - PUBWEAK HardFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -HardFault_Handler - B HardFault_Handler - - PUBWEAK MemManage_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -MemManage_Handler - B MemManage_Handler - - PUBWEAK BusFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -BusFault_Handler - B BusFault_Handler - - PUBWEAK UsageFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -UsageFault_Handler - B UsageFault_Handler - - PUBWEAK SVC_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -SVC_Handler - B SVC_Handler - - PUBWEAK DebugMon_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -DebugMon_Handler - B DebugMon_Handler - - PUBWEAK PendSV_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -PendSV_Handler - B PendSV_Handler - - PUBWEAK SysTick_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -SysTick_Handler - B SysTick_Handler - - PUBWEAK WWDG_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -WWDG_IRQHandler - B WWDG_IRQHandler - - PUBWEAK PVD_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -PVD_IRQHandler - B PVD_IRQHandler - - PUBWEAK TAMP_STAMP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TAMP_STAMP_IRQHandler - B TAMP_STAMP_IRQHandler - - PUBWEAK RTC_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RTC_WKUP_IRQHandler - B RTC_WKUP_IRQHandler - - PUBWEAK FLASH_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FLASH_IRQHandler - B FLASH_IRQHandler - - PUBWEAK RCC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RCC_IRQHandler - B RCC_IRQHandler - - PUBWEAK EXTI0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI0_IRQHandler - B EXTI0_IRQHandler - - PUBWEAK EXTI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI1_IRQHandler - B EXTI1_IRQHandler - - PUBWEAK EXTI2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI2_IRQHandler - B EXTI2_IRQHandler - - PUBWEAK EXTI3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI3_IRQHandler - B EXTI3_IRQHandler - - PUBWEAK EXTI4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI4_IRQHandler - B EXTI4_IRQHandler - - PUBWEAK DMA1_Stream0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream0_IRQHandler - B DMA1_Stream0_IRQHandler - - PUBWEAK DMA1_Stream1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream1_IRQHandler - B DMA1_Stream1_IRQHandler - - PUBWEAK DMA1_Stream2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream2_IRQHandler - B DMA1_Stream2_IRQHandler - - PUBWEAK DMA1_Stream3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream3_IRQHandler - B DMA1_Stream3_IRQHandler - - PUBWEAK DMA1_Stream4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream4_IRQHandler - B DMA1_Stream4_IRQHandler - - PUBWEAK DMA1_Stream5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream5_IRQHandler - B DMA1_Stream5_IRQHandler - - PUBWEAK DMA1_Stream6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream6_IRQHandler - B DMA1_Stream6_IRQHandler - - PUBWEAK ADC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -ADC_IRQHandler - B ADC_IRQHandler - - PUBWEAK CAN1_TX_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_TX_IRQHandler - B CAN1_TX_IRQHandler - - PUBWEAK CAN1_RX0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_RX0_IRQHandler - B CAN1_RX0_IRQHandler - - PUBWEAK CAN1_RX1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_RX1_IRQHandler - B CAN1_RX1_IRQHandler - - PUBWEAK CAN1_SCE_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_SCE_IRQHandler - B CAN1_SCE_IRQHandler - - PUBWEAK EXTI9_5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI9_5_IRQHandler - B EXTI9_5_IRQHandler - - PUBWEAK TIM1_BRK_TIM9_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_BRK_TIM9_IRQHandler - B TIM1_BRK_TIM9_IRQHandler - - PUBWEAK TIM1_UP_TIM10_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_UP_TIM10_IRQHandler - B TIM1_UP_TIM10_IRQHandler - - PUBWEAK TIM1_TRG_COM_TIM11_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_TRG_COM_TIM11_IRQHandler - B TIM1_TRG_COM_TIM11_IRQHandler - - PUBWEAK TIM1_CC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_CC_IRQHandler - B TIM1_CC_IRQHandler - - PUBWEAK TIM2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM2_IRQHandler - B TIM2_IRQHandler - - PUBWEAK TIM3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM3_IRQHandler - B TIM3_IRQHandler - - PUBWEAK TIM4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM4_IRQHandler - B TIM4_IRQHandler - - PUBWEAK I2C1_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C1_EV_IRQHandler - B I2C1_EV_IRQHandler - - PUBWEAK I2C1_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C1_ER_IRQHandler - B I2C1_ER_IRQHandler - - PUBWEAK I2C2_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C2_EV_IRQHandler - B I2C2_EV_IRQHandler - - PUBWEAK I2C2_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C2_ER_IRQHandler - B I2C2_ER_IRQHandler - - PUBWEAK SPI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI1_IRQHandler - B SPI1_IRQHandler - - PUBWEAK SPI2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI2_IRQHandler - B SPI2_IRQHandler - - PUBWEAK USART1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART1_IRQHandler - B USART1_IRQHandler - - PUBWEAK USART2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART2_IRQHandler - B USART2_IRQHandler - - PUBWEAK USART3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART3_IRQHandler - B USART3_IRQHandler - - PUBWEAK EXTI15_10_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI15_10_IRQHandler - B EXTI15_10_IRQHandler - - PUBWEAK RTC_Alarm_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RTC_Alarm_IRQHandler - B RTC_Alarm_IRQHandler - - PUBWEAK OTG_FS_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_FS_WKUP_IRQHandler - B OTG_FS_WKUP_IRQHandler - - PUBWEAK TIM8_BRK_TIM12_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_BRK_TIM12_IRQHandler - B TIM8_BRK_TIM12_IRQHandler - - PUBWEAK TIM8_UP_TIM13_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_UP_TIM13_IRQHandler - B TIM8_UP_TIM13_IRQHandler - - PUBWEAK TIM8_TRG_COM_TIM14_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_TRG_COM_TIM14_IRQHandler - B TIM8_TRG_COM_TIM14_IRQHandler - - PUBWEAK TIM8_CC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_CC_IRQHandler - B TIM8_CC_IRQHandler - - PUBWEAK DMA1_Stream7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream7_IRQHandler - B DMA1_Stream7_IRQHandler - - PUBWEAK FMC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FMC_IRQHandler - B FMC_IRQHandler - - PUBWEAK SDIO_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SDIO_IRQHandler - B SDIO_IRQHandler - - PUBWEAK TIM5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM5_IRQHandler - B TIM5_IRQHandler - - PUBWEAK SPI3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI3_IRQHandler - B SPI3_IRQHandler - - PUBWEAK UART4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -UART4_IRQHandler - B UART4_IRQHandler - - PUBWEAK UART5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -UART5_IRQHandler - B UART5_IRQHandler - - PUBWEAK TIM6_DAC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM6_DAC_IRQHandler - B TIM6_DAC_IRQHandler - - PUBWEAK TIM7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM7_IRQHandler - B TIM7_IRQHandler - - PUBWEAK DMA2_Stream0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream0_IRQHandler - B DMA2_Stream0_IRQHandler - - PUBWEAK DMA2_Stream1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream1_IRQHandler - B DMA2_Stream1_IRQHandler - - PUBWEAK DMA2_Stream2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream2_IRQHandler - B DMA2_Stream2_IRQHandler - - PUBWEAK DMA2_Stream3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream3_IRQHandler - B DMA2_Stream3_IRQHandler - - PUBWEAK DMA2_Stream4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream4_IRQHandler - B DMA2_Stream4_IRQHandler - - PUBWEAK ETH_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -ETH_IRQHandler - B ETH_IRQHandler - - PUBWEAK ETH_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -ETH_WKUP_IRQHandler - B ETH_WKUP_IRQHandler - - PUBWEAK CAN2_TX_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_TX_IRQHandler - B CAN2_TX_IRQHandler - - PUBWEAK CAN2_RX0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_RX0_IRQHandler - B CAN2_RX0_IRQHandler - - PUBWEAK CAN2_RX1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_RX1_IRQHandler - B CAN2_RX1_IRQHandler - - PUBWEAK CAN2_SCE_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_SCE_IRQHandler - B CAN2_SCE_IRQHandler - - PUBWEAK OTG_FS_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_FS_IRQHandler - B OTG_FS_IRQHandler - - PUBWEAK DMA2_Stream5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream5_IRQHandler - B DMA2_Stream5_IRQHandler - - PUBWEAK DMA2_Stream6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream6_IRQHandler - B DMA2_Stream6_IRQHandler - - PUBWEAK DMA2_Stream7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream7_IRQHandler - B DMA2_Stream7_IRQHandler - - PUBWEAK USART6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART6_IRQHandler - B USART6_IRQHandler - - PUBWEAK I2C3_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C3_EV_IRQHandler - B I2C3_EV_IRQHandler - - PUBWEAK I2C3_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C3_ER_IRQHandler - B I2C3_ER_IRQHandler - - PUBWEAK OTG_HS_EP1_OUT_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_EP1_OUT_IRQHandler - B OTG_HS_EP1_OUT_IRQHandler - - PUBWEAK OTG_HS_EP1_IN_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_EP1_IN_IRQHandler - B OTG_HS_EP1_IN_IRQHandler - - PUBWEAK OTG_HS_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_WKUP_IRQHandler - B OTG_HS_WKUP_IRQHandler - - PUBWEAK OTG_HS_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_IRQHandler - B OTG_HS_IRQHandler - - PUBWEAK DCMI_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DCMI_IRQHandler - B DCMI_IRQHandler - - PUBWEAK CRYP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CRYP_IRQHandler - B CRYP_IRQHandler - - PUBWEAK HASH_RNG_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -HASH_RNG_IRQHandler - B HASH_RNG_IRQHandler - - PUBWEAK FPU_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FPU_IRQHandler - B FPU_IRQHandler - - PUBWEAK UART7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -UART7_IRQHandler - B UART7_IRQHandler - - PUBWEAK UART8_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -UART8_IRQHandler - B UART8_IRQHandler - - PUBWEAK SPI4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI4_IRQHandler - B SPI4_IRQHandler - - PUBWEAK SPI5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI5_IRQHandler - B SPI5_IRQHandler - - PUBWEAK SPI6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI6_IRQHandler - B SPI6_IRQHandler - - PUBWEAK SAI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SAI1_IRQHandler - B SAI1_IRQHandler - - PUBWEAK DMA2D_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2D_IRQHandler - B DMA2D_IRQHandler - - - END -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f427x.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f427x.s deleted file mode 100644 index 3706b86618..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f427x.s +++ /dev/null @@ -1,692 +0,0 @@ -;/******************** (C) COPYRIGHT 2015 STMicroelectronics ******************** -;* File Name : startup_stm32f427x.s -;* Author : MCD Application Team -;* @version : V1.6.1 -;* @date : 21-October-2015 -;* Description : STM32F427xx/437xx devices vector table for EWARM toolchain. -;* Same as startup_stm32f42_43xxx.s and maintained for legacy purpose -;* This module performs: -;* - Set the initial SP -;* - Set the initial PC == _iar_program_start, -;* - Set the vector table entries with the exceptions ISR -;* address. -;* - Configure the system clock and the external SRAM/SDRAM mounted -;* on STM324x7I-EVAL boards 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. -;******************************************************************************** -;* -;* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); -;* You may not use this file except in compliance with the License. -;* You may obtain a copy of the License at: -;* -;* http://www.st.com/software_license_agreement_liberty_v2 -;* -;* Unless required by applicable law or agreed to in writing, software -;* distributed under the License is distributed on an "AS IS" BASIS, -;* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -;* See the License for the specific language governing permissions and -;* limitations under the License. -;* -;*******************************************************************************/ -; -; -; The modules in this file are included in the libraries, and may be replaced -; by any user-defined modules that define the PUBLIC symbol _program_start or -; a user defined start symbol. -; To override the cstartup defined in the library, simply add your modified -; version to the workbench project. -; -; The vector table is normally located at address 0. -; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. -; The name "__vector_table" has special meaning for C-SPY: -; it is where the SP start value is found, and the NVIC vector -; table register (VTOR) is initialized to this address if != 0. -; -; Cortex-M version -; - - MODULE ?cstartup - - ;; Forward declaration of sections. - SECTION CSTACK:DATA:NOROOT(3) - - SECTION .intvec:CODE:NOROOT(2) - - EXTERN __iar_program_start - EXTERN SystemInit - PUBLIC __vector_table - - DATA -__vector_table - DCD sfe(CSTACK) - DCD Reset_Handler ; Reset Handler - - DCD NMI_Handler ; NMI Handler - DCD HardFault_Handler ; Hard Fault Handler - DCD MemManage_Handler ; MPU Fault Handler - DCD BusFault_Handler ; Bus Fault Handler - DCD UsageFault_Handler ; Usage Fault Handler - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SVC_Handler ; SVCall Handler - DCD DebugMon_Handler ; Debug Monitor Handler - DCD 0 ; Reserved - DCD PendSV_Handler ; PendSV Handler - DCD SysTick_Handler ; SysTick Handler - - ; External Interrupts - DCD WWDG_IRQHandler ; Window WatchDog - DCD PVD_IRQHandler ; PVD through EXTI Line detection - DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line - DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line - DCD FLASH_IRQHandler ; FLASH - DCD RCC_IRQHandler ; RCC - DCD EXTI0_IRQHandler ; EXTI Line0 - DCD EXTI1_IRQHandler ; EXTI Line1 - DCD EXTI2_IRQHandler ; EXTI Line2 - DCD EXTI3_IRQHandler ; EXTI Line3 - DCD EXTI4_IRQHandler ; EXTI Line4 - DCD DMA1_Stream0_IRQHandler ; DMA1 Stream 0 - DCD DMA1_Stream1_IRQHandler ; DMA1 Stream 1 - DCD DMA1_Stream2_IRQHandler ; DMA1 Stream 2 - DCD DMA1_Stream3_IRQHandler ; DMA1 Stream 3 - DCD DMA1_Stream4_IRQHandler ; DMA1 Stream 4 - DCD DMA1_Stream5_IRQHandler ; DMA1 Stream 5 - DCD DMA1_Stream6_IRQHandler ; DMA1 Stream 6 - DCD ADC_IRQHandler ; ADC1, ADC2 and ADC3s - DCD CAN1_TX_IRQHandler ; CAN1 TX - DCD CAN1_RX0_IRQHandler ; CAN1 RX0 - DCD CAN1_RX1_IRQHandler ; CAN1 RX1 - DCD CAN1_SCE_IRQHandler ; CAN1 SCE - DCD EXTI9_5_IRQHandler ; External Line[9:5]s - DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 - DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 - DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 - DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare - DCD TIM2_IRQHandler ; TIM2 - DCD TIM3_IRQHandler ; TIM3 - DCD TIM4_IRQHandler ; TIM4 - DCD I2C1_EV_IRQHandler ; I2C1 Event - DCD I2C1_ER_IRQHandler ; I2C1 Error - DCD I2C2_EV_IRQHandler ; I2C2 Event - DCD I2C2_ER_IRQHandler ; I2C2 Error - DCD SPI1_IRQHandler ; SPI1 - DCD SPI2_IRQHandler ; SPI2 - DCD USART1_IRQHandler ; USART1 - DCD USART2_IRQHandler ; USART2 - DCD USART3_IRQHandler ; USART3 - DCD EXTI15_10_IRQHandler ; External Line[15:10]s - DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line - DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line - DCD TIM8_BRK_TIM12_IRQHandler ; TIM8 Break and TIM12 - DCD TIM8_UP_TIM13_IRQHandler ; TIM8 Update and TIM13 - DCD TIM8_TRG_COM_TIM14_IRQHandler ; TIM8 Trigger and Commutation and TIM14 - DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare - DCD DMA1_Stream7_IRQHandler ; DMA1 Stream7 - DCD FMC_IRQHandler ; FMC - DCD SDIO_IRQHandler ; SDIO - DCD TIM5_IRQHandler ; TIM5 - DCD SPI3_IRQHandler ; SPI3 - DCD UART4_IRQHandler ; UART4 - DCD UART5_IRQHandler ; UART5 - DCD TIM6_DAC_IRQHandler ; TIM6 and DAC1&2 underrun errors - DCD TIM7_IRQHandler ; TIM7 - DCD DMA2_Stream0_IRQHandler ; DMA2 Stream 0 - DCD DMA2_Stream1_IRQHandler ; DMA2 Stream 1 - DCD DMA2_Stream2_IRQHandler ; DMA2 Stream 2 - DCD DMA2_Stream3_IRQHandler ; DMA2 Stream 3 - DCD DMA2_Stream4_IRQHandler ; DMA2 Stream 4 - DCD ETH_IRQHandler ; Ethernet - DCD ETH_WKUP_IRQHandler ; Ethernet Wakeup through EXTI line - DCD CAN2_TX_IRQHandler ; CAN2 TX - DCD CAN2_RX0_IRQHandler ; CAN2 RX0 - DCD CAN2_RX1_IRQHandler ; CAN2 RX1 - DCD CAN2_SCE_IRQHandler ; CAN2 SCE - DCD OTG_FS_IRQHandler ; USB OTG FS - DCD DMA2_Stream5_IRQHandler ; DMA2 Stream 5 - DCD DMA2_Stream6_IRQHandler ; DMA2 Stream 6 - DCD DMA2_Stream7_IRQHandler ; DMA2 Stream 7 - DCD USART6_IRQHandler ; USART6 - DCD I2C3_EV_IRQHandler ; I2C3 event - DCD I2C3_ER_IRQHandler ; I2C3 error - DCD OTG_HS_EP1_OUT_IRQHandler ; USB OTG HS End Point 1 Out - DCD OTG_HS_EP1_IN_IRQHandler ; USB OTG HS End Point 1 In - DCD OTG_HS_WKUP_IRQHandler ; USB OTG HS Wakeup through EXTI - DCD OTG_HS_IRQHandler ; USB OTG HS - DCD DCMI_IRQHandler ; DCMI - DCD CRYP_IRQHandler ; CRYP crypto - DCD HASH_RNG_IRQHandler ; Hash and Rng - DCD FPU_IRQHandler ; FPU - DCD UART7_IRQHandler ; UART7 - DCD UART8_IRQHandler ; UART8 - DCD SPI4_IRQHandler ; SPI4 - DCD SPI5_IRQHandler ; SPI5 - DCD SPI6_IRQHandler ; SPI6 - DCD SAI1_IRQHandler ; SAI1 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD DMA2D_IRQHandler ; DMA2D - -;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; -;; -;; Default interrupt handlers. -;; - THUMB - PUBWEAK Reset_Handler - SECTION .text:CODE:REORDER:NOROOT(2) -Reset_Handler - - LDR R0, =SystemInit - BLX R0 - LDR R0, =__iar_program_start - BX R0 - - PUBWEAK NMI_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -NMI_Handler - B NMI_Handler - - PUBWEAK HardFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -HardFault_Handler - B HardFault_Handler - - PUBWEAK MemManage_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -MemManage_Handler - B MemManage_Handler - - PUBWEAK BusFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -BusFault_Handler - B BusFault_Handler - - PUBWEAK UsageFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -UsageFault_Handler - B UsageFault_Handler - - PUBWEAK SVC_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -SVC_Handler - B SVC_Handler - - PUBWEAK DebugMon_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -DebugMon_Handler - B DebugMon_Handler - - PUBWEAK PendSV_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -PendSV_Handler - B PendSV_Handler - - PUBWEAK SysTick_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -SysTick_Handler - B SysTick_Handler - - PUBWEAK WWDG_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -WWDG_IRQHandler - B WWDG_IRQHandler - - PUBWEAK PVD_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -PVD_IRQHandler - B PVD_IRQHandler - - PUBWEAK TAMP_STAMP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TAMP_STAMP_IRQHandler - B TAMP_STAMP_IRQHandler - - PUBWEAK RTC_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RTC_WKUP_IRQHandler - B RTC_WKUP_IRQHandler - - PUBWEAK FLASH_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FLASH_IRQHandler - B FLASH_IRQHandler - - PUBWEAK RCC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RCC_IRQHandler - B RCC_IRQHandler - - PUBWEAK EXTI0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI0_IRQHandler - B EXTI0_IRQHandler - - PUBWEAK EXTI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI1_IRQHandler - B EXTI1_IRQHandler - - PUBWEAK EXTI2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI2_IRQHandler - B EXTI2_IRQHandler - - PUBWEAK EXTI3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI3_IRQHandler - B EXTI3_IRQHandler - - PUBWEAK EXTI4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI4_IRQHandler - B EXTI4_IRQHandler - - PUBWEAK DMA1_Stream0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream0_IRQHandler - B DMA1_Stream0_IRQHandler - - PUBWEAK DMA1_Stream1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream1_IRQHandler - B DMA1_Stream1_IRQHandler - - PUBWEAK DMA1_Stream2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream2_IRQHandler - B DMA1_Stream2_IRQHandler - - PUBWEAK DMA1_Stream3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream3_IRQHandler - B DMA1_Stream3_IRQHandler - - PUBWEAK DMA1_Stream4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream4_IRQHandler - B DMA1_Stream4_IRQHandler - - PUBWEAK DMA1_Stream5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream5_IRQHandler - B DMA1_Stream5_IRQHandler - - PUBWEAK DMA1_Stream6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream6_IRQHandler - B DMA1_Stream6_IRQHandler - - PUBWEAK ADC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -ADC_IRQHandler - B ADC_IRQHandler - - PUBWEAK CAN1_TX_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_TX_IRQHandler - B CAN1_TX_IRQHandler - - PUBWEAK CAN1_RX0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_RX0_IRQHandler - B CAN1_RX0_IRQHandler - - PUBWEAK CAN1_RX1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_RX1_IRQHandler - B CAN1_RX1_IRQHandler - - PUBWEAK CAN1_SCE_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_SCE_IRQHandler - B CAN1_SCE_IRQHandler - - PUBWEAK EXTI9_5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI9_5_IRQHandler - B EXTI9_5_IRQHandler - - PUBWEAK TIM1_BRK_TIM9_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_BRK_TIM9_IRQHandler - B TIM1_BRK_TIM9_IRQHandler - - PUBWEAK TIM1_UP_TIM10_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_UP_TIM10_IRQHandler - B TIM1_UP_TIM10_IRQHandler - - PUBWEAK TIM1_TRG_COM_TIM11_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_TRG_COM_TIM11_IRQHandler - B TIM1_TRG_COM_TIM11_IRQHandler - - PUBWEAK TIM1_CC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_CC_IRQHandler - B TIM1_CC_IRQHandler - - PUBWEAK TIM2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM2_IRQHandler - B TIM2_IRQHandler - - PUBWEAK TIM3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM3_IRQHandler - B TIM3_IRQHandler - - PUBWEAK TIM4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM4_IRQHandler - B TIM4_IRQHandler - - PUBWEAK I2C1_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C1_EV_IRQHandler - B I2C1_EV_IRQHandler - - PUBWEAK I2C1_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C1_ER_IRQHandler - B I2C1_ER_IRQHandler - - PUBWEAK I2C2_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C2_EV_IRQHandler - B I2C2_EV_IRQHandler - - PUBWEAK I2C2_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C2_ER_IRQHandler - B I2C2_ER_IRQHandler - - PUBWEAK SPI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI1_IRQHandler - B SPI1_IRQHandler - - PUBWEAK SPI2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI2_IRQHandler - B SPI2_IRQHandler - - PUBWEAK USART1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART1_IRQHandler - B USART1_IRQHandler - - PUBWEAK USART2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART2_IRQHandler - B USART2_IRQHandler - - PUBWEAK USART3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART3_IRQHandler - B USART3_IRQHandler - - PUBWEAK EXTI15_10_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI15_10_IRQHandler - B EXTI15_10_IRQHandler - - PUBWEAK RTC_Alarm_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RTC_Alarm_IRQHandler - B RTC_Alarm_IRQHandler - - PUBWEAK OTG_FS_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_FS_WKUP_IRQHandler - B OTG_FS_WKUP_IRQHandler - - PUBWEAK TIM8_BRK_TIM12_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_BRK_TIM12_IRQHandler - B TIM8_BRK_TIM12_IRQHandler - - PUBWEAK TIM8_UP_TIM13_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_UP_TIM13_IRQHandler - B TIM8_UP_TIM13_IRQHandler - - PUBWEAK TIM8_TRG_COM_TIM14_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_TRG_COM_TIM14_IRQHandler - B TIM8_TRG_COM_TIM14_IRQHandler - - PUBWEAK TIM8_CC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_CC_IRQHandler - B TIM8_CC_IRQHandler - - PUBWEAK DMA1_Stream7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream7_IRQHandler - B DMA1_Stream7_IRQHandler - - PUBWEAK FMC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FMC_IRQHandler - B FMC_IRQHandler - - PUBWEAK SDIO_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SDIO_IRQHandler - B SDIO_IRQHandler - - PUBWEAK TIM5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM5_IRQHandler - B TIM5_IRQHandler - - PUBWEAK SPI3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI3_IRQHandler - B SPI3_IRQHandler - - PUBWEAK UART4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -UART4_IRQHandler - B UART4_IRQHandler - - PUBWEAK UART5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -UART5_IRQHandler - B UART5_IRQHandler - - PUBWEAK TIM6_DAC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM6_DAC_IRQHandler - B TIM6_DAC_IRQHandler - - PUBWEAK TIM7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM7_IRQHandler - B TIM7_IRQHandler - - PUBWEAK DMA2_Stream0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream0_IRQHandler - B DMA2_Stream0_IRQHandler - - PUBWEAK DMA2_Stream1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream1_IRQHandler - B DMA2_Stream1_IRQHandler - - PUBWEAK DMA2_Stream2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream2_IRQHandler - B DMA2_Stream2_IRQHandler - - PUBWEAK DMA2_Stream3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream3_IRQHandler - B DMA2_Stream3_IRQHandler - - PUBWEAK DMA2_Stream4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream4_IRQHandler - B DMA2_Stream4_IRQHandler - - PUBWEAK ETH_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -ETH_IRQHandler - B ETH_IRQHandler - - PUBWEAK ETH_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -ETH_WKUP_IRQHandler - B ETH_WKUP_IRQHandler - - PUBWEAK CAN2_TX_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_TX_IRQHandler - B CAN2_TX_IRQHandler - - PUBWEAK CAN2_RX0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_RX0_IRQHandler - B CAN2_RX0_IRQHandler - - PUBWEAK CAN2_RX1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_RX1_IRQHandler - B CAN2_RX1_IRQHandler - - PUBWEAK CAN2_SCE_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_SCE_IRQHandler - B CAN2_SCE_IRQHandler - - PUBWEAK OTG_FS_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_FS_IRQHandler - B OTG_FS_IRQHandler - - PUBWEAK DMA2_Stream5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream5_IRQHandler - B DMA2_Stream5_IRQHandler - - PUBWEAK DMA2_Stream6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream6_IRQHandler - B DMA2_Stream6_IRQHandler - - PUBWEAK DMA2_Stream7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream7_IRQHandler - B DMA2_Stream7_IRQHandler - - PUBWEAK USART6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART6_IRQHandler - B USART6_IRQHandler - - PUBWEAK I2C3_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C3_EV_IRQHandler - B I2C3_EV_IRQHandler - - PUBWEAK I2C3_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C3_ER_IRQHandler - B I2C3_ER_IRQHandler - - PUBWEAK OTG_HS_EP1_OUT_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_EP1_OUT_IRQHandler - B OTG_HS_EP1_OUT_IRQHandler - - PUBWEAK OTG_HS_EP1_IN_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_EP1_IN_IRQHandler - B OTG_HS_EP1_IN_IRQHandler - - PUBWEAK OTG_HS_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_WKUP_IRQHandler - B OTG_HS_WKUP_IRQHandler - - PUBWEAK OTG_HS_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_IRQHandler - B OTG_HS_IRQHandler - - PUBWEAK DCMI_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DCMI_IRQHandler - B DCMI_IRQHandler - - PUBWEAK CRYP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CRYP_IRQHandler - B CRYP_IRQHandler - - PUBWEAK HASH_RNG_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -HASH_RNG_IRQHandler - B HASH_RNG_IRQHandler - - PUBWEAK FPU_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FPU_IRQHandler - B FPU_IRQHandler - - PUBWEAK UART7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -UART7_IRQHandler - B UART7_IRQHandler - - PUBWEAK UART8_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -UART8_IRQHandler - B UART8_IRQHandler - - PUBWEAK SPI4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI4_IRQHandler - B SPI4_IRQHandler - - PUBWEAK SPI5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI5_IRQHandler - B SPI5_IRQHandler - - PUBWEAK SPI6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI6_IRQHandler - B SPI6_IRQHandler - - PUBWEAK SAI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SAI1_IRQHandler - B SAI1_IRQHandler - - PUBWEAK LTDC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -LTDC_IRQHandler - B LTDC_IRQHandler - - PUBWEAK LTDC_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -LTDC_ER_IRQHandler - B LTDC_ER_IRQHandler - - PUBWEAK DMA2D_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2D_IRQHandler - B DMA2D_IRQHandler - - - END -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f429_439xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f429_439xx.s deleted file mode 100644 index 9601b8c75e..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f429_439xx.s +++ /dev/null @@ -1,691 +0,0 @@ -/******************** (C) COPYRIGHT 2015 STMicroelectronics ******************** -;* File Name : startup_stm32f429_439xx.s -;* Author : MCD Application Team -;* @version : V1.6.1 -;* @date : 21-October-2015 -;* Description : STM32F429xx/439xx devices vector table for EWARM toolchain. -;* This module performs: -;* - Set the initial SP -;* - Set the initial PC == _iar_program_start, -;* - Set the vector table entries with the exceptions ISR -;* address. -;* - Configure the system clock and the external SRAM/SDRAM mounted -;* on STM324x9I-EVAL board 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. -;******************************************************************************** -;* -;* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); -;* You may not use this file except in compliance with the License. -;* You may obtain a copy of the License at: -;* -;* http://www.st.com/software_license_agreement_liberty_v2 -;* -;* Unless required by applicable law or agreed to in writing, software -;* distributed under the License is distributed on an "AS IS" BASIS, -;* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -;* See the License for the specific language governing permissions and -;* limitations under the License. -;* -;*******************************************************************************/ -; -; -; The modules in this file are included in the libraries, and may be replaced -; by any user-defined modules that define the PUBLIC symbol _program_start or -; a user defined start symbol. -; To override the cstartup defined in the library, simply add your modified -; version to the workbench project. -; -; The vector table is normally located at address 0. -; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. -; The name "__vector_table" has special meaning for C-SPY: -; it is where the SP start value is found, and the NVIC vector -; table register (VTOR) is initialized to this address if != 0. -; -; Cortex-M version -; - - MODULE ?cstartup - - ;; Forward declaration of sections. - SECTION CSTACK:DATA:NOROOT(3) - - SECTION .intvec:CODE:NOROOT(2) - - EXTERN __iar_program_start - EXTERN SystemInit - PUBLIC __vector_table - - DATA -__vector_table - DCD sfe(CSTACK) - DCD Reset_Handler ; Reset Handler - - DCD NMI_Handler ; NMI Handler - DCD HardFault_Handler ; Hard Fault Handler - DCD MemManage_Handler ; MPU Fault Handler - DCD BusFault_Handler ; Bus Fault Handler - DCD UsageFault_Handler ; Usage Fault Handler - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SVC_Handler ; SVCall Handler - DCD DebugMon_Handler ; Debug Monitor Handler - DCD 0 ; Reserved - DCD PendSV_Handler ; PendSV Handler - DCD SysTick_Handler ; SysTick Handler - - ; External Interrupts - DCD WWDG_IRQHandler ; Window WatchDog - DCD PVD_IRQHandler ; PVD through EXTI Line detection - DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line - DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line - DCD FLASH_IRQHandler ; FLASH - DCD RCC_IRQHandler ; RCC - DCD EXTI0_IRQHandler ; EXTI Line0 - DCD EXTI1_IRQHandler ; EXTI Line1 - DCD EXTI2_IRQHandler ; EXTI Line2 - DCD EXTI3_IRQHandler ; EXTI Line3 - DCD EXTI4_IRQHandler ; EXTI Line4 - DCD DMA1_Stream0_IRQHandler ; DMA1 Stream 0 - DCD DMA1_Stream1_IRQHandler ; DMA1 Stream 1 - DCD DMA1_Stream2_IRQHandler ; DMA1 Stream 2 - DCD DMA1_Stream3_IRQHandler ; DMA1 Stream 3 - DCD DMA1_Stream4_IRQHandler ; DMA1 Stream 4 - DCD DMA1_Stream5_IRQHandler ; DMA1 Stream 5 - DCD DMA1_Stream6_IRQHandler ; DMA1 Stream 6 - DCD ADC_IRQHandler ; ADC1, ADC2 and ADC3s - DCD CAN1_TX_IRQHandler ; CAN1 TX - DCD CAN1_RX0_IRQHandler ; CAN1 RX0 - DCD CAN1_RX1_IRQHandler ; CAN1 RX1 - DCD CAN1_SCE_IRQHandler ; CAN1 SCE - DCD EXTI9_5_IRQHandler ; External Line[9:5]s - DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 - DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 - DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 - DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare - DCD TIM2_IRQHandler ; TIM2 - DCD TIM3_IRQHandler ; TIM3 - DCD TIM4_IRQHandler ; TIM4 - DCD I2C1_EV_IRQHandler ; I2C1 Event - DCD I2C1_ER_IRQHandler ; I2C1 Error - DCD I2C2_EV_IRQHandler ; I2C2 Event - DCD I2C2_ER_IRQHandler ; I2C2 Error - DCD SPI1_IRQHandler ; SPI1 - DCD SPI2_IRQHandler ; SPI2 - DCD USART1_IRQHandler ; USART1 - DCD USART2_IRQHandler ; USART2 - DCD USART3_IRQHandler ; USART3 - DCD EXTI15_10_IRQHandler ; External Line[15:10]s - DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line - DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line - DCD TIM8_BRK_TIM12_IRQHandler ; TIM8 Break and TIM12 - DCD TIM8_UP_TIM13_IRQHandler ; TIM8 Update and TIM13 - DCD TIM8_TRG_COM_TIM14_IRQHandler ; TIM8 Trigger and Commutation and TIM14 - DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare - DCD DMA1_Stream7_IRQHandler ; DMA1 Stream7 - DCD FMC_IRQHandler ; FMC - DCD SDIO_IRQHandler ; SDIO - DCD TIM5_IRQHandler ; TIM5 - DCD SPI3_IRQHandler ; SPI3 - DCD UART4_IRQHandler ; UART4 - DCD UART5_IRQHandler ; UART5 - DCD TIM6_DAC_IRQHandler ; TIM6 and DAC1&2 underrun errors - DCD TIM7_IRQHandler ; TIM7 - DCD DMA2_Stream0_IRQHandler ; DMA2 Stream 0 - DCD DMA2_Stream1_IRQHandler ; DMA2 Stream 1 - DCD DMA2_Stream2_IRQHandler ; DMA2 Stream 2 - DCD DMA2_Stream3_IRQHandler ; DMA2 Stream 3 - DCD DMA2_Stream4_IRQHandler ; DMA2 Stream 4 - DCD ETH_IRQHandler ; Ethernet - DCD ETH_WKUP_IRQHandler ; Ethernet Wakeup through EXTI line - DCD CAN2_TX_IRQHandler ; CAN2 TX - DCD CAN2_RX0_IRQHandler ; CAN2 RX0 - DCD CAN2_RX1_IRQHandler ; CAN2 RX1 - DCD CAN2_SCE_IRQHandler ; CAN2 SCE - DCD OTG_FS_IRQHandler ; USB OTG FS - DCD DMA2_Stream5_IRQHandler ; DMA2 Stream 5 - DCD DMA2_Stream6_IRQHandler ; DMA2 Stream 6 - DCD DMA2_Stream7_IRQHandler ; DMA2 Stream 7 - DCD USART6_IRQHandler ; USART6 - DCD I2C3_EV_IRQHandler ; I2C3 event - DCD I2C3_ER_IRQHandler ; I2C3 error - DCD OTG_HS_EP1_OUT_IRQHandler ; USB OTG HS End Point 1 Out - DCD OTG_HS_EP1_IN_IRQHandler ; USB OTG HS End Point 1 In - DCD OTG_HS_WKUP_IRQHandler ; USB OTG HS Wakeup through EXTI - DCD OTG_HS_IRQHandler ; USB OTG HS - DCD DCMI_IRQHandler ; DCMI - DCD CRYP_IRQHandler ; CRYP crypto - DCD HASH_RNG_IRQHandler ; Hash and Rng - DCD FPU_IRQHandler ; FPU - DCD UART7_IRQHandler ; UART7 - DCD UART8_IRQHandler ; UART8 - DCD SPI4_IRQHandler ; SPI4 - DCD SPI5_IRQHandler ; SPI5 - DCD SPI6_IRQHandler ; SPI6 - DCD SAI1_IRQHandler ; SAI1 - DCD LTDC_IRQHandler ; LTDC - DCD LTDC_ER_IRQHandler ; LTDC error - DCD DMA2D_IRQHandler ; DMA2D - -;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; -;; -;; Default interrupt handlers. -;; - THUMB - PUBWEAK Reset_Handler - SECTION .text:CODE:REORDER:NOROOT(2) -Reset_Handler - - LDR R0, =SystemInit - BLX R0 - LDR R0, =__iar_program_start - BX R0 - - PUBWEAK NMI_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -NMI_Handler - B NMI_Handler - - PUBWEAK HardFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -HardFault_Handler - B HardFault_Handler - - PUBWEAK MemManage_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -MemManage_Handler - B MemManage_Handler - - PUBWEAK BusFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -BusFault_Handler - B BusFault_Handler - - PUBWEAK UsageFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -UsageFault_Handler - B UsageFault_Handler - - PUBWEAK SVC_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -SVC_Handler - B SVC_Handler - - PUBWEAK DebugMon_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -DebugMon_Handler - B DebugMon_Handler - - PUBWEAK PendSV_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -PendSV_Handler - B PendSV_Handler - - PUBWEAK SysTick_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -SysTick_Handler - B SysTick_Handler - - PUBWEAK WWDG_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -WWDG_IRQHandler - B WWDG_IRQHandler - - PUBWEAK PVD_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -PVD_IRQHandler - B PVD_IRQHandler - - PUBWEAK TAMP_STAMP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TAMP_STAMP_IRQHandler - B TAMP_STAMP_IRQHandler - - PUBWEAK RTC_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RTC_WKUP_IRQHandler - B RTC_WKUP_IRQHandler - - PUBWEAK FLASH_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FLASH_IRQHandler - B FLASH_IRQHandler - - PUBWEAK RCC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RCC_IRQHandler - B RCC_IRQHandler - - PUBWEAK EXTI0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI0_IRQHandler - B EXTI0_IRQHandler - - PUBWEAK EXTI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI1_IRQHandler - B EXTI1_IRQHandler - - PUBWEAK EXTI2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI2_IRQHandler - B EXTI2_IRQHandler - - PUBWEAK EXTI3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI3_IRQHandler - B EXTI3_IRQHandler - - PUBWEAK EXTI4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI4_IRQHandler - B EXTI4_IRQHandler - - PUBWEAK DMA1_Stream0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream0_IRQHandler - B DMA1_Stream0_IRQHandler - - PUBWEAK DMA1_Stream1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream1_IRQHandler - B DMA1_Stream1_IRQHandler - - PUBWEAK DMA1_Stream2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream2_IRQHandler - B DMA1_Stream2_IRQHandler - - PUBWEAK DMA1_Stream3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream3_IRQHandler - B DMA1_Stream3_IRQHandler - - PUBWEAK DMA1_Stream4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream4_IRQHandler - B DMA1_Stream4_IRQHandler - - PUBWEAK DMA1_Stream5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream5_IRQHandler - B DMA1_Stream5_IRQHandler - - PUBWEAK DMA1_Stream6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream6_IRQHandler - B DMA1_Stream6_IRQHandler - - PUBWEAK ADC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -ADC_IRQHandler - B ADC_IRQHandler - - PUBWEAK CAN1_TX_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_TX_IRQHandler - B CAN1_TX_IRQHandler - - PUBWEAK CAN1_RX0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_RX0_IRQHandler - B CAN1_RX0_IRQHandler - - PUBWEAK CAN1_RX1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_RX1_IRQHandler - B CAN1_RX1_IRQHandler - - PUBWEAK CAN1_SCE_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_SCE_IRQHandler - B CAN1_SCE_IRQHandler - - PUBWEAK EXTI9_5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI9_5_IRQHandler - B EXTI9_5_IRQHandler - - PUBWEAK TIM1_BRK_TIM9_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_BRK_TIM9_IRQHandler - B TIM1_BRK_TIM9_IRQHandler - - PUBWEAK TIM1_UP_TIM10_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_UP_TIM10_IRQHandler - B TIM1_UP_TIM10_IRQHandler - - PUBWEAK TIM1_TRG_COM_TIM11_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_TRG_COM_TIM11_IRQHandler - B TIM1_TRG_COM_TIM11_IRQHandler - - PUBWEAK TIM1_CC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_CC_IRQHandler - B TIM1_CC_IRQHandler - - PUBWEAK TIM2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM2_IRQHandler - B TIM2_IRQHandler - - PUBWEAK TIM3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM3_IRQHandler - B TIM3_IRQHandler - - PUBWEAK TIM4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM4_IRQHandler - B TIM4_IRQHandler - - PUBWEAK I2C1_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C1_EV_IRQHandler - B I2C1_EV_IRQHandler - - PUBWEAK I2C1_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C1_ER_IRQHandler - B I2C1_ER_IRQHandler - - PUBWEAK I2C2_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C2_EV_IRQHandler - B I2C2_EV_IRQHandler - - PUBWEAK I2C2_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C2_ER_IRQHandler - B I2C2_ER_IRQHandler - - PUBWEAK SPI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI1_IRQHandler - B SPI1_IRQHandler - - PUBWEAK SPI2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI2_IRQHandler - B SPI2_IRQHandler - - PUBWEAK USART1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART1_IRQHandler - B USART1_IRQHandler - - PUBWEAK USART2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART2_IRQHandler - B USART2_IRQHandler - - PUBWEAK USART3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART3_IRQHandler - B USART3_IRQHandler - - PUBWEAK EXTI15_10_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI15_10_IRQHandler - B EXTI15_10_IRQHandler - - PUBWEAK RTC_Alarm_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RTC_Alarm_IRQHandler - B RTC_Alarm_IRQHandler - - PUBWEAK OTG_FS_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_FS_WKUP_IRQHandler - B OTG_FS_WKUP_IRQHandler - - PUBWEAK TIM8_BRK_TIM12_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_BRK_TIM12_IRQHandler - B TIM8_BRK_TIM12_IRQHandler - - PUBWEAK TIM8_UP_TIM13_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_UP_TIM13_IRQHandler - B TIM8_UP_TIM13_IRQHandler - - PUBWEAK TIM8_TRG_COM_TIM14_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_TRG_COM_TIM14_IRQHandler - B TIM8_TRG_COM_TIM14_IRQHandler - - PUBWEAK TIM8_CC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_CC_IRQHandler - B TIM8_CC_IRQHandler - - PUBWEAK DMA1_Stream7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream7_IRQHandler - B DMA1_Stream7_IRQHandler - - PUBWEAK FMC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FMC_IRQHandler - B FMC_IRQHandler - - PUBWEAK SDIO_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SDIO_IRQHandler - B SDIO_IRQHandler - - PUBWEAK TIM5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM5_IRQHandler - B TIM5_IRQHandler - - PUBWEAK SPI3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI3_IRQHandler - B SPI3_IRQHandler - - PUBWEAK UART4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -UART4_IRQHandler - B UART4_IRQHandler - - PUBWEAK UART5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -UART5_IRQHandler - B UART5_IRQHandler - - PUBWEAK TIM6_DAC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM6_DAC_IRQHandler - B TIM6_DAC_IRQHandler - - PUBWEAK TIM7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM7_IRQHandler - B TIM7_IRQHandler - - PUBWEAK DMA2_Stream0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream0_IRQHandler - B DMA2_Stream0_IRQHandler - - PUBWEAK DMA2_Stream1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream1_IRQHandler - B DMA2_Stream1_IRQHandler - - PUBWEAK DMA2_Stream2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream2_IRQHandler - B DMA2_Stream2_IRQHandler - - PUBWEAK DMA2_Stream3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream3_IRQHandler - B DMA2_Stream3_IRQHandler - - PUBWEAK DMA2_Stream4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream4_IRQHandler - B DMA2_Stream4_IRQHandler - - PUBWEAK ETH_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -ETH_IRQHandler - B ETH_IRQHandler - - PUBWEAK ETH_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -ETH_WKUP_IRQHandler - B ETH_WKUP_IRQHandler - - PUBWEAK CAN2_TX_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_TX_IRQHandler - B CAN2_TX_IRQHandler - - PUBWEAK CAN2_RX0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_RX0_IRQHandler - B CAN2_RX0_IRQHandler - - PUBWEAK CAN2_RX1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_RX1_IRQHandler - B CAN2_RX1_IRQHandler - - PUBWEAK CAN2_SCE_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_SCE_IRQHandler - B CAN2_SCE_IRQHandler - - PUBWEAK OTG_FS_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_FS_IRQHandler - B OTG_FS_IRQHandler - - PUBWEAK DMA2_Stream5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream5_IRQHandler - B DMA2_Stream5_IRQHandler - - PUBWEAK DMA2_Stream6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream6_IRQHandler - B DMA2_Stream6_IRQHandler - - PUBWEAK DMA2_Stream7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream7_IRQHandler - B DMA2_Stream7_IRQHandler - - PUBWEAK USART6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART6_IRQHandler - B USART6_IRQHandler - - PUBWEAK I2C3_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C3_EV_IRQHandler - B I2C3_EV_IRQHandler - - PUBWEAK I2C3_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C3_ER_IRQHandler - B I2C3_ER_IRQHandler - - PUBWEAK OTG_HS_EP1_OUT_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_EP1_OUT_IRQHandler - B OTG_HS_EP1_OUT_IRQHandler - - PUBWEAK OTG_HS_EP1_IN_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_EP1_IN_IRQHandler - B OTG_HS_EP1_IN_IRQHandler - - PUBWEAK OTG_HS_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_WKUP_IRQHandler - B OTG_HS_WKUP_IRQHandler - - PUBWEAK OTG_HS_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_IRQHandler - B OTG_HS_IRQHandler - - PUBWEAK DCMI_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DCMI_IRQHandler - B DCMI_IRQHandler - - PUBWEAK CRYP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CRYP_IRQHandler - B CRYP_IRQHandler - - PUBWEAK HASH_RNG_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -HASH_RNG_IRQHandler - B HASH_RNG_IRQHandler - - PUBWEAK FPU_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FPU_IRQHandler - B FPU_IRQHandler - - PUBWEAK UART7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -UART7_IRQHandler - B UART7_IRQHandler - - PUBWEAK UART8_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -UART8_IRQHandler - B UART8_IRQHandler - - PUBWEAK SPI4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI4_IRQHandler - B SPI4_IRQHandler - - PUBWEAK SPI5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI5_IRQHandler - B SPI5_IRQHandler - - PUBWEAK SPI6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI6_IRQHandler - B SPI6_IRQHandler - - PUBWEAK SAI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SAI1_IRQHandler - B SAI1_IRQHandler - - PUBWEAK LTDC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -LTDC_IRQHandler - B LTDC_IRQHandler - - PUBWEAK LTDC_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -LTDC_ER_IRQHandler - B LTDC_ER_IRQHandler - - PUBWEAK DMA2D_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2D_IRQHandler - B DMA2D_IRQHandler - - - END -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f446xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f446xx.s deleted file mode 100644 index ac235adb57..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f446xx.s +++ /dev/null @@ -1,678 +0,0 @@ -;/******************** (C) COPYRIGHT 2015 STMicroelectronics ******************** -;* File Name : startup_stm32f446xx.s -;* Author : MCD Application Team -;* @version : V1.6.1 -;* @date : 21-October-2015 -;* Description : STM32F446xx devices vector table for EWARM toolchain. -;* This module performs: -;* - Set the initial SP -;* - Set the initial PC == _iar_program_start, -;* - Set the vector table entries with the exceptions ISR -;* address. -;* - Branches to main in the C library (which eventually -;* calls main()). -;* After Reset the Cortex-M4 processor is in Thread mode, -;* priority is Privileged, and the Stack is set to Main. -;******************************************************************************** -;* -;* Redistribution and use in source and binary forms, with or without modification, -;* are permitted provided that the following conditions are met: -;* 1. Redistributions of source code must retain the above copyright notice, -;* this list of conditions and the following disclaimer. -;* 2. Redistributions in binary form must reproduce the above copyright notice, -;* this list of conditions and the following disclaimer in the documentation -;* and/or other materials provided with the distribution. -;* 3. Neither the name of STMicroelectronics nor the names of its contributors -;* may be used to endorse or promote products derived from this software -;* without specific prior written permission. -;* -;* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -;* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE -;* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL -;* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -;* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -;* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, -;* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE -;* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -;* -;******************************************************************************* -; -; -; The modules in this file are included in the libraries, and may be replaced -; by any user-defined modules that define the PUBLIC symbol _program_start or -; a user defined start symbol. -; To override the cstartup defined in the library, simply add your modified -; version to the workbench project. -; -; The vector table is normally located at address 0. -; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. -; The name "__vector_table" has special meaning for C-SPY: -; it is where the SP start value is found, and the NVIC vector -; table register (VTOR) is initialized to this address if != 0. -; -; Cortex-M version -; - - MODULE ?cstartup - - ;; Forward declaration of sections. - SECTION CSTACK:DATA:NOROOT(3) - - SECTION .intvec:CODE:NOROOT(2) - - EXTERN __iar_program_start - EXTERN SystemInit - PUBLIC __vector_table - - DATA -__vector_table - DCD sfe(CSTACK) - DCD Reset_Handler ; Reset Handler - - DCD NMI_Handler ; NMI Handler - DCD HardFault_Handler ; Hard Fault Handler - DCD MemManage_Handler ; MPU Fault Handler - DCD BusFault_Handler ; Bus Fault Handler - DCD UsageFault_Handler ; Usage Fault Handler - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SVC_Handler ; SVCall Handler - DCD DebugMon_Handler ; Debug Monitor Handler - DCD 0 ; Reserved - DCD PendSV_Handler ; PendSV Handler - DCD SysTick_Handler ; SysTick Handler - - ; External Interrupts - DCD WWDG_IRQHandler ; Window WatchDog - DCD PVD_IRQHandler ; PVD through EXTI Line detection - DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line - DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line - DCD FLASH_IRQHandler ; FLASH - DCD RCC_IRQHandler ; RCC - DCD EXTI0_IRQHandler ; EXTI Line0 - DCD EXTI1_IRQHandler ; EXTI Line1 - DCD EXTI2_IRQHandler ; EXTI Line2 - DCD EXTI3_IRQHandler ; EXTI Line3 - DCD EXTI4_IRQHandler ; EXTI Line4 - DCD DMA1_Stream0_IRQHandler ; DMA1 Stream 0 - DCD DMA1_Stream1_IRQHandler ; DMA1 Stream 1 - DCD DMA1_Stream2_IRQHandler ; DMA1 Stream 2 - DCD DMA1_Stream3_IRQHandler ; DMA1 Stream 3 - DCD DMA1_Stream4_IRQHandler ; DMA1 Stream 4 - DCD DMA1_Stream5_IRQHandler ; DMA1 Stream 5 - DCD DMA1_Stream6_IRQHandler ; DMA1 Stream 6 - DCD ADC_IRQHandler ; ADC1, ADC2 and ADC3s - DCD CAN1_TX_IRQHandler ; CAN1 TX - DCD CAN1_RX0_IRQHandler ; CAN1 RX0 - DCD CAN1_RX1_IRQHandler ; CAN1 RX1 - DCD CAN1_SCE_IRQHandler ; CAN1 SCE - DCD EXTI9_5_IRQHandler ; External Line[9:5]s - DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 - DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 - DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 - DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare - DCD TIM2_IRQHandler ; TIM2 - DCD TIM3_IRQHandler ; TIM3 - DCD TIM4_IRQHandler ; TIM4 - DCD I2C1_EV_IRQHandler ; I2C1 Event - DCD I2C1_ER_IRQHandler ; I2C1 Error - DCD I2C2_EV_IRQHandler ; I2C2 Event - DCD I2C2_ER_IRQHandler ; I2C2 Error - DCD SPI1_IRQHandler ; SPI1 - DCD SPI2_IRQHandler ; SPI2 - DCD USART1_IRQHandler ; USART1 - DCD USART2_IRQHandler ; USART2 - DCD USART3_IRQHandler ; USART3 - DCD EXTI15_10_IRQHandler ; External Line[15:10]s - DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line - DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line - DCD TIM8_BRK_TIM12_IRQHandler ; TIM8 Break and TIM12 - DCD TIM8_UP_TIM13_IRQHandler ; TIM8 Update and TIM13 - DCD TIM8_TRG_COM_TIM14_IRQHandler ; TIM8 Trigger and Commutation and TIM14 - DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare - DCD DMA1_Stream7_IRQHandler ; DMA1 Stream7 - DCD FMC_IRQHandler ; FMC - DCD SDIO_IRQHandler ; SDIO - DCD TIM5_IRQHandler ; TIM5 - DCD SPI3_IRQHandler ; SPI3 - DCD UART4_IRQHandler ; UART4 - DCD UART5_IRQHandler ; UART5 - DCD TIM6_DAC_IRQHandler ; TIM6 and DAC1&2 underrun errors - DCD TIM7_IRQHandler ; TIM7 - DCD DMA2_Stream0_IRQHandler ; DMA2 Stream 0 - DCD DMA2_Stream1_IRQHandler ; DMA2 Stream 1 - DCD DMA2_Stream2_IRQHandler ; DMA2 Stream 2 - DCD DMA2_Stream3_IRQHandler ; DMA2 Stream 3 - DCD DMA2_Stream4_IRQHandler ; DMA2 Stream 4 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD CAN2_TX_IRQHandler ; CAN2 TX - DCD CAN2_RX0_IRQHandler ; CAN2 RX0 - DCD CAN2_RX1_IRQHandler ; CAN2 RX1 - DCD CAN2_SCE_IRQHandler ; CAN2 SCE - DCD OTG_FS_IRQHandler ; USB OTG FS - DCD DMA2_Stream5_IRQHandler ; DMA2 Stream 5 - DCD DMA2_Stream6_IRQHandler ; DMA2 Stream 6 - DCD DMA2_Stream7_IRQHandler ; DMA2 Stream 7 - DCD USART6_IRQHandler ; USART6 - DCD I2C3_EV_IRQHandler ; I2C3 event - DCD I2C3_ER_IRQHandler ; I2C3 error - DCD OTG_HS_EP1_OUT_IRQHandler ; USB OTG HS End Point 1 Out - DCD OTG_HS_EP1_IN_IRQHandler ; USB OTG HS End Point 1 In - DCD OTG_HS_WKUP_IRQHandler ; USB OTG HS Wakeup through EXTI - DCD OTG_HS_IRQHandler ; USB OTG HS - DCD DCMI_IRQHandler ; DCMI - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD FPU_IRQHandler ; FPU - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SPI4_IRQHandler ; SPI4 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SAI1_IRQHandler ; SAI1 - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SAI2_IRQHandler ; SAI2 - DCD QUADSPI_IRQHandler ; QUADSPI - DCD CEC_IRQHandler ; CEC - DCD SPDIF_RX_IRQHandler ; SPDIF RX - DCD FMPI2C1_Event_IRQHandler ; I2C 4 Event - DCD FMPI2C1_Error_IRQHandler ; I2C 4 Error - ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; -;; -;; Default interrupt handlers. -;; - THUMB - PUBWEAK Reset_Handler - SECTION .text:CODE:REORDER:NOROOT(2) -Reset_Handler - - LDR R0, =SystemInit - BLX R0 - LDR R0, =__iar_program_start - BX R0 - - PUBWEAK NMI_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -NMI_Handler - B NMI_Handler - - PUBWEAK HardFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -HardFault_Handler - B HardFault_Handler - - PUBWEAK MemManage_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -MemManage_Handler - B MemManage_Handler - - PUBWEAK BusFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -BusFault_Handler - B BusFault_Handler - - PUBWEAK UsageFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -UsageFault_Handler - B UsageFault_Handler - - PUBWEAK SVC_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -SVC_Handler - B SVC_Handler - - PUBWEAK DebugMon_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -DebugMon_Handler - B DebugMon_Handler - - PUBWEAK PendSV_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -PendSV_Handler - B PendSV_Handler - - PUBWEAK SysTick_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -SysTick_Handler - B SysTick_Handler - - PUBWEAK WWDG_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -WWDG_IRQHandler - B WWDG_IRQHandler - - PUBWEAK PVD_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -PVD_IRQHandler - B PVD_IRQHandler - - PUBWEAK TAMP_STAMP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TAMP_STAMP_IRQHandler - B TAMP_STAMP_IRQHandler - - PUBWEAK RTC_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RTC_WKUP_IRQHandler - B RTC_WKUP_IRQHandler - - PUBWEAK FLASH_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FLASH_IRQHandler - B FLASH_IRQHandler - - PUBWEAK RCC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RCC_IRQHandler - B RCC_IRQHandler - - PUBWEAK EXTI0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI0_IRQHandler - B EXTI0_IRQHandler - - PUBWEAK EXTI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI1_IRQHandler - B EXTI1_IRQHandler - - PUBWEAK EXTI2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI2_IRQHandler - B EXTI2_IRQHandler - - PUBWEAK EXTI3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI3_IRQHandler - B EXTI3_IRQHandler - - PUBWEAK EXTI4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI4_IRQHandler - B EXTI4_IRQHandler - - PUBWEAK DMA1_Stream0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream0_IRQHandler - B DMA1_Stream0_IRQHandler - - PUBWEAK DMA1_Stream1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream1_IRQHandler - B DMA1_Stream1_IRQHandler - - PUBWEAK DMA1_Stream2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream2_IRQHandler - B DMA1_Stream2_IRQHandler - - PUBWEAK DMA1_Stream3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream3_IRQHandler - B DMA1_Stream3_IRQHandler - - PUBWEAK DMA1_Stream4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream4_IRQHandler - B DMA1_Stream4_IRQHandler - - PUBWEAK DMA1_Stream5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream5_IRQHandler - B DMA1_Stream5_IRQHandler - - PUBWEAK DMA1_Stream6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream6_IRQHandler - B DMA1_Stream6_IRQHandler - - PUBWEAK ADC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -ADC_IRQHandler - B ADC_IRQHandler - - PUBWEAK CAN1_TX_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_TX_IRQHandler - B CAN1_TX_IRQHandler - - PUBWEAK CAN1_RX0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_RX0_IRQHandler - B CAN1_RX0_IRQHandler - - PUBWEAK CAN1_RX1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_RX1_IRQHandler - B CAN1_RX1_IRQHandler - - PUBWEAK CAN1_SCE_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_SCE_IRQHandler - B CAN1_SCE_IRQHandler - - PUBWEAK EXTI9_5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI9_5_IRQHandler - B EXTI9_5_IRQHandler - - PUBWEAK TIM1_BRK_TIM9_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_BRK_TIM9_IRQHandler - B TIM1_BRK_TIM9_IRQHandler - - PUBWEAK TIM1_UP_TIM10_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_UP_TIM10_IRQHandler - B TIM1_UP_TIM10_IRQHandler - - PUBWEAK TIM1_TRG_COM_TIM11_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_TRG_COM_TIM11_IRQHandler - B TIM1_TRG_COM_TIM11_IRQHandler - - PUBWEAK TIM1_CC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_CC_IRQHandler - B TIM1_CC_IRQHandler - - PUBWEAK TIM2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM2_IRQHandler - B TIM2_IRQHandler - - PUBWEAK TIM3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM3_IRQHandler - B TIM3_IRQHandler - - PUBWEAK TIM4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM4_IRQHandler - B TIM4_IRQHandler - - PUBWEAK I2C1_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C1_EV_IRQHandler - B I2C1_EV_IRQHandler - - PUBWEAK I2C1_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C1_ER_IRQHandler - B I2C1_ER_IRQHandler - - PUBWEAK I2C2_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C2_EV_IRQHandler - B I2C2_EV_IRQHandler - - PUBWEAK I2C2_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C2_ER_IRQHandler - B I2C2_ER_IRQHandler - - PUBWEAK SPI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI1_IRQHandler - B SPI1_IRQHandler - - PUBWEAK SPI2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI2_IRQHandler - B SPI2_IRQHandler - - PUBWEAK USART1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART1_IRQHandler - B USART1_IRQHandler - - PUBWEAK USART2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART2_IRQHandler - B USART2_IRQHandler - - PUBWEAK USART3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART3_IRQHandler - B USART3_IRQHandler - - PUBWEAK EXTI15_10_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI15_10_IRQHandler - B EXTI15_10_IRQHandler - - PUBWEAK RTC_Alarm_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RTC_Alarm_IRQHandler - B RTC_Alarm_IRQHandler - - PUBWEAK OTG_FS_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_FS_WKUP_IRQHandler - B OTG_FS_WKUP_IRQHandler - - PUBWEAK TIM8_BRK_TIM12_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_BRK_TIM12_IRQHandler - B TIM8_BRK_TIM12_IRQHandler - - PUBWEAK TIM8_UP_TIM13_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_UP_TIM13_IRQHandler - B TIM8_UP_TIM13_IRQHandler - - PUBWEAK TIM8_TRG_COM_TIM14_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_TRG_COM_TIM14_IRQHandler - B TIM8_TRG_COM_TIM14_IRQHandler - - PUBWEAK TIM8_CC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_CC_IRQHandler - B TIM8_CC_IRQHandler - - PUBWEAK DMA1_Stream7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream7_IRQHandler - B DMA1_Stream7_IRQHandler - - PUBWEAK FMC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FMC_IRQHandler - B FMC_IRQHandler - - PUBWEAK SDIO_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SDIO_IRQHandler - B SDIO_IRQHandler - - PUBWEAK TIM5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM5_IRQHandler - B TIM5_IRQHandler - - PUBWEAK SPI3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI3_IRQHandler - B SPI3_IRQHandler - - PUBWEAK UART4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -UART4_IRQHandler - B UART4_IRQHandler - - PUBWEAK UART5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -UART5_IRQHandler - B UART5_IRQHandler - - PUBWEAK TIM6_DAC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM6_DAC_IRQHandler - B TIM6_DAC_IRQHandler - - PUBWEAK TIM7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM7_IRQHandler - B TIM7_IRQHandler - - PUBWEAK DMA2_Stream0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream0_IRQHandler - B DMA2_Stream0_IRQHandler - - PUBWEAK DMA2_Stream1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream1_IRQHandler - B DMA2_Stream1_IRQHandler - - PUBWEAK DMA2_Stream2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream2_IRQHandler - B DMA2_Stream2_IRQHandler - - PUBWEAK DMA2_Stream3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream3_IRQHandler - B DMA2_Stream3_IRQHandler - - PUBWEAK DMA2_Stream4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream4_IRQHandler - B DMA2_Stream4_IRQHandler - - PUBWEAK CAN2_TX_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_TX_IRQHandler - B CAN2_TX_IRQHandler - - PUBWEAK CAN2_RX0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_RX0_IRQHandler - B CAN2_RX0_IRQHandler - - PUBWEAK CAN2_RX1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_RX1_IRQHandler - B CAN2_RX1_IRQHandler - - PUBWEAK CAN2_SCE_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_SCE_IRQHandler - B CAN2_SCE_IRQHandler - - PUBWEAK OTG_FS_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_FS_IRQHandler - B OTG_FS_IRQHandler - - PUBWEAK DMA2_Stream5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream5_IRQHandler - B DMA2_Stream5_IRQHandler - - PUBWEAK DMA2_Stream6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream6_IRQHandler - B DMA2_Stream6_IRQHandler - - PUBWEAK DMA2_Stream7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream7_IRQHandler - B DMA2_Stream7_IRQHandler - - PUBWEAK USART6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART6_IRQHandler - B USART6_IRQHandler - - PUBWEAK I2C3_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C3_EV_IRQHandler - B I2C3_EV_IRQHandler - - PUBWEAK I2C3_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C3_ER_IRQHandler - B I2C3_ER_IRQHandler - - PUBWEAK OTG_HS_EP1_OUT_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_EP1_OUT_IRQHandler - B OTG_HS_EP1_OUT_IRQHandler - - PUBWEAK OTG_HS_EP1_IN_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_EP1_IN_IRQHandler - B OTG_HS_EP1_IN_IRQHandler - - PUBWEAK OTG_HS_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_WKUP_IRQHandler - B OTG_HS_WKUP_IRQHandler - - PUBWEAK OTG_HS_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_IRQHandler - B OTG_HS_IRQHandler - - PUBWEAK DCMI_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DCMI_IRQHandler - B DCMI_IRQHandler - - PUBWEAK FPU_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FPU_IRQHandler - B FPU_IRQHandler - - PUBWEAK SPI4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI4_IRQHandler - B SPI4_IRQHandler - - PUBWEAK SAI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SAI1_IRQHandler - B SAI1_IRQHandler - - PUBWEAK SAI2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SAI2_IRQHandler - B SAI2_IRQHandler - - PUBWEAK QUADSPI_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -QUADSPI_IRQHandler - B QUADSPI_IRQHandler - - PUBWEAK CEC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CEC_IRQHandler - B CEC_IRQHandler - - PUBWEAK SPDIF_RX_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPDIF_RX_IRQHandler - B SPDIF_RX_IRQHandler - - PUBWEAK FMPI2C1_Event_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FMPI2C1_Event_IRQHandler - B FMPI2C1_Event_IRQHandler - - PUBWEAK FMPI2C1_Error_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FMPI2C1_Error_IRQHandler - B FMPI2C1_Error_IRQHandler - - - END -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f469_479xx.s b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f469_479xx.s deleted file mode 100644 index 7e5e887c20..0000000000 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/startup/iar/startup_stm32f469_479xx.s +++ /dev/null @@ -1,699 +0,0 @@ -;/******************** (C) COPYRIGHT 2015 STMicroelectronics ******************** -;* File Name : startup_stm32f469_479xx.s -;* Author : MCD Application Team -;* @version : V1.6.1 -;* @date : 21-October-2015 -;* Description : STM32F469xx/479xx devices vector table for EWARM toolchain. -;* This module performs: -;* - Set the initial SP -;* - Set the initial PC == _iar_program_start, -;* - Set the vector table entries with the exceptions ISR -;* address. -;* - Branches to main in the C library (which eventually -;* calls main()). -;* After Reset the Cortex-M4 processor is in Thread mode, -;* priority is Privileged, and the Stack is set to Main. -;******************************************************************************** -;* -;* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); -;* You may not use this file except in compliance with the License. -;* You may obtain a copy of the License at: -;* -;* http://www.st.com/software_license_agreement_liberty_v2 -;* -;* Unless required by applicable law or agreed to in writing, software -;* distributed under the License is distributed on an "AS IS" BASIS, -;* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -;* See the License for the specific language governing permissions and -;* limitations under the License. -;* -;*******************************************************************************/ -; -; -; The modules in this file are included in the libraries, and may be replaced -; by any user-defined modules that define the PUBLIC symbol _program_start or -; a user defined start symbol. -; To override the cstartup defined in the library, simply add your modified -; version to the workbench project. -; -; The vector table is normally located at address 0. -; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. -; The name "__vector_table" has special meaning for C-SPY: -; it is where the SP start value is found, and the NVIC vector -; table register (VTOR) is initialized to this address if != 0. -; -; Cortex-M version -; - - MODULE ?cstartup - - ;; Forward declaration of sections. - SECTION CSTACK:DATA:NOROOT(3) - - SECTION .intvec:CODE:NOROOT(2) - - EXTERN __iar_program_start - EXTERN SystemInit - PUBLIC __vector_table - - DATA -__vector_table - DCD sfe(CSTACK) - DCD Reset_Handler ; Reset Handler - - DCD NMI_Handler ; NMI Handler - DCD HardFault_Handler ; Hard Fault Handler - DCD MemManage_Handler ; MPU Fault Handler - DCD BusFault_Handler ; Bus Fault Handler - DCD UsageFault_Handler ; Usage Fault Handler - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD 0 ; Reserved - DCD SVC_Handler ; SVCall Handler - DCD DebugMon_Handler ; Debug Monitor Handler - DCD 0 ; Reserved - DCD PendSV_Handler ; PendSV Handler - DCD SysTick_Handler ; SysTick Handler - - ; External Interrupts - DCD WWDG_IRQHandler ; Window WatchDog - DCD PVD_IRQHandler ; PVD through EXTI Line detection - DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line - DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line - DCD FLASH_IRQHandler ; FLASH - DCD RCC_IRQHandler ; RCC - DCD EXTI0_IRQHandler ; EXTI Line0 - DCD EXTI1_IRQHandler ; EXTI Line1 - DCD EXTI2_IRQHandler ; EXTI Line2 - DCD EXTI3_IRQHandler ; EXTI Line3 - DCD EXTI4_IRQHandler ; EXTI Line4 - DCD DMA1_Stream0_IRQHandler ; DMA1 Stream 0 - DCD DMA1_Stream1_IRQHandler ; DMA1 Stream 1 - DCD DMA1_Stream2_IRQHandler ; DMA1 Stream 2 - DCD DMA1_Stream3_IRQHandler ; DMA1 Stream 3 - DCD DMA1_Stream4_IRQHandler ; DMA1 Stream 4 - DCD DMA1_Stream5_IRQHandler ; DMA1 Stream 5 - DCD DMA1_Stream6_IRQHandler ; DMA1 Stream 6 - DCD ADC_IRQHandler ; ADC1, ADC2 and ADC3s - DCD CAN1_TX_IRQHandler ; CAN1 TX - DCD CAN1_RX0_IRQHandler ; CAN1 RX0 - DCD CAN1_RX1_IRQHandler ; CAN1 RX1 - DCD CAN1_SCE_IRQHandler ; CAN1 SCE - DCD EXTI9_5_IRQHandler ; External Line[9:5]s - DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 - DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 - DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 - DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare - DCD TIM2_IRQHandler ; TIM2 - DCD TIM3_IRQHandler ; TIM3 - DCD TIM4_IRQHandler ; TIM4 - DCD I2C1_EV_IRQHandler ; I2C1 Event - DCD I2C1_ER_IRQHandler ; I2C1 Error - DCD I2C2_EV_IRQHandler ; I2C2 Event - DCD I2C2_ER_IRQHandler ; I2C2 Error - DCD SPI1_IRQHandler ; SPI1 - DCD SPI2_IRQHandler ; SPI2 - DCD USART1_IRQHandler ; USART1 - DCD USART2_IRQHandler ; USART2 - DCD USART3_IRQHandler ; USART3 - DCD EXTI15_10_IRQHandler ; External Line[15:10]s - DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line - DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line - DCD TIM8_BRK_TIM12_IRQHandler ; TIM8 Break and TIM12 - DCD TIM8_UP_TIM13_IRQHandler ; TIM8 Update and TIM13 - DCD TIM8_TRG_COM_TIM14_IRQHandler ; TIM8 Trigger and Commutation and TIM14 - DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare - DCD DMA1_Stream7_IRQHandler ; DMA1 Stream7 - DCD FMC_IRQHandler ; FMC - DCD SDIO_IRQHandler ; SDIO - DCD TIM5_IRQHandler ; TIM5 - DCD SPI3_IRQHandler ; SPI3 - DCD UART4_IRQHandler ; UART4 - DCD UART5_IRQHandler ; UART5 - DCD TIM6_DAC_IRQHandler ; TIM6 and DAC1&2 underrun errors - DCD TIM7_IRQHandler ; TIM7 - DCD DMA2_Stream0_IRQHandler ; DMA2 Stream 0 - DCD DMA2_Stream1_IRQHandler ; DMA2 Stream 1 - DCD DMA2_Stream2_IRQHandler ; DMA2 Stream 2 - DCD DMA2_Stream3_IRQHandler ; DMA2 Stream 3 - DCD DMA2_Stream4_IRQHandler ; DMA2 Stream 4 - DCD ETH_IRQHandler ; Ethernet - DCD ETH_WKUP_IRQHandler ; Ethernet Wakeup through EXTI line - DCD CAN2_TX_IRQHandler ; CAN2 TX - DCD CAN2_RX0_IRQHandler ; CAN2 RX0 - DCD CAN2_RX1_IRQHandler ; CAN2 RX1 - DCD CAN2_SCE_IRQHandler ; CAN2 SCE - DCD OTG_FS_IRQHandler ; USB OTG FS - DCD DMA2_Stream5_IRQHandler ; DMA2 Stream 5 - DCD DMA2_Stream6_IRQHandler ; DMA2 Stream 6 - DCD DMA2_Stream7_IRQHandler ; DMA2 Stream 7 - DCD USART6_IRQHandler ; USART6 - DCD I2C3_EV_IRQHandler ; I2C3 event - DCD I2C3_ER_IRQHandler ; I2C3 error - DCD OTG_HS_EP1_OUT_IRQHandler ; USB OTG HS End Point 1 Out - DCD OTG_HS_EP1_IN_IRQHandler ; USB OTG HS End Point 1 In - DCD OTG_HS_WKUP_IRQHandler ; USB OTG HS Wakeup through EXTI - DCD OTG_HS_IRQHandler ; USB OTG HS - DCD DCMI_IRQHandler ; DCMI - DCD CRYP_IRQHandler ; CRYP crypto - DCD HASH_RNG_IRQHandler ; Hash and Rng - DCD FPU_IRQHandler ; FPU - DCD UART7_IRQHandler ; UART7 - DCD UART8_IRQHandler ; UART8 - DCD SPI4_IRQHandler ; SPI4 - DCD SPI5_IRQHandler ; SPI5 - DCD SPI6_IRQHandler ; SPI6 - DCD SAI1_IRQHandler ; SAI1 - DCD LTDC_IRQHandler ; LTDC - DCD LTDC_ER_IRQHandler ; LTDC error - DCD DMA2D_IRQHandler ; DMA2D - DCD QUADSPI_IRQHandler ; QUADSPI - DCD DSI_IRQHandler ; DSI Controller - -;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; -;; -;; Default interrupt handlers. -;; - THUMB - PUBWEAK Reset_Handler - SECTION .text:CODE:REORDER:NOROOT(2) -Reset_Handler - - LDR R0, =SystemInit - BLX R0 - LDR R0, =__iar_program_start - BX R0 - - PUBWEAK NMI_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -NMI_Handler - B NMI_Handler - - PUBWEAK HardFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -HardFault_Handler - B HardFault_Handler - - PUBWEAK MemManage_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -MemManage_Handler - B MemManage_Handler - - PUBWEAK BusFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -BusFault_Handler - B BusFault_Handler - - PUBWEAK UsageFault_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -UsageFault_Handler - B UsageFault_Handler - - PUBWEAK SVC_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -SVC_Handler - B SVC_Handler - - PUBWEAK DebugMon_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -DebugMon_Handler - B DebugMon_Handler - - PUBWEAK PendSV_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -PendSV_Handler - B PendSV_Handler - - PUBWEAK SysTick_Handler - SECTION .text:CODE:REORDER:NOROOT(1) -SysTick_Handler - B SysTick_Handler - - PUBWEAK WWDG_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -WWDG_IRQHandler - B WWDG_IRQHandler - - PUBWEAK PVD_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -PVD_IRQHandler - B PVD_IRQHandler - - PUBWEAK TAMP_STAMP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TAMP_STAMP_IRQHandler - B TAMP_STAMP_IRQHandler - - PUBWEAK RTC_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RTC_WKUP_IRQHandler - B RTC_WKUP_IRQHandler - - PUBWEAK FLASH_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FLASH_IRQHandler - B FLASH_IRQHandler - - PUBWEAK RCC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RCC_IRQHandler - B RCC_IRQHandler - - PUBWEAK EXTI0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI0_IRQHandler - B EXTI0_IRQHandler - - PUBWEAK EXTI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI1_IRQHandler - B EXTI1_IRQHandler - - PUBWEAK EXTI2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI2_IRQHandler - B EXTI2_IRQHandler - - PUBWEAK EXTI3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI3_IRQHandler - B EXTI3_IRQHandler - - PUBWEAK EXTI4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI4_IRQHandler - B EXTI4_IRQHandler - - PUBWEAK DMA1_Stream0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream0_IRQHandler - B DMA1_Stream0_IRQHandler - - PUBWEAK DMA1_Stream1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream1_IRQHandler - B DMA1_Stream1_IRQHandler - - PUBWEAK DMA1_Stream2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream2_IRQHandler - B DMA1_Stream2_IRQHandler - - PUBWEAK DMA1_Stream3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream3_IRQHandler - B DMA1_Stream3_IRQHandler - - PUBWEAK DMA1_Stream4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream4_IRQHandler - B DMA1_Stream4_IRQHandler - - PUBWEAK DMA1_Stream5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream5_IRQHandler - B DMA1_Stream5_IRQHandler - - PUBWEAK DMA1_Stream6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream6_IRQHandler - B DMA1_Stream6_IRQHandler - - PUBWEAK ADC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -ADC_IRQHandler - B ADC_IRQHandler - - PUBWEAK CAN1_TX_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_TX_IRQHandler - B CAN1_TX_IRQHandler - - PUBWEAK CAN1_RX0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_RX0_IRQHandler - B CAN1_RX0_IRQHandler - - PUBWEAK CAN1_RX1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_RX1_IRQHandler - B CAN1_RX1_IRQHandler - - PUBWEAK CAN1_SCE_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN1_SCE_IRQHandler - B CAN1_SCE_IRQHandler - - PUBWEAK EXTI9_5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI9_5_IRQHandler - B EXTI9_5_IRQHandler - - PUBWEAK TIM1_BRK_TIM9_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_BRK_TIM9_IRQHandler - B TIM1_BRK_TIM9_IRQHandler - - PUBWEAK TIM1_UP_TIM10_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_UP_TIM10_IRQHandler - B TIM1_UP_TIM10_IRQHandler - - PUBWEAK TIM1_TRG_COM_TIM11_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_TRG_COM_TIM11_IRQHandler - B TIM1_TRG_COM_TIM11_IRQHandler - - PUBWEAK TIM1_CC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM1_CC_IRQHandler - B TIM1_CC_IRQHandler - - PUBWEAK TIM2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM2_IRQHandler - B TIM2_IRQHandler - - PUBWEAK TIM3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM3_IRQHandler - B TIM3_IRQHandler - - PUBWEAK TIM4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM4_IRQHandler - B TIM4_IRQHandler - - PUBWEAK I2C1_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C1_EV_IRQHandler - B I2C1_EV_IRQHandler - - PUBWEAK I2C1_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C1_ER_IRQHandler - B I2C1_ER_IRQHandler - - PUBWEAK I2C2_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C2_EV_IRQHandler - B I2C2_EV_IRQHandler - - PUBWEAK I2C2_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C2_ER_IRQHandler - B I2C2_ER_IRQHandler - - PUBWEAK SPI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI1_IRQHandler - B SPI1_IRQHandler - - PUBWEAK SPI2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI2_IRQHandler - B SPI2_IRQHandler - - PUBWEAK USART1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART1_IRQHandler - B USART1_IRQHandler - - PUBWEAK USART2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART2_IRQHandler - B USART2_IRQHandler - - PUBWEAK USART3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART3_IRQHandler - B USART3_IRQHandler - - PUBWEAK EXTI15_10_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -EXTI15_10_IRQHandler - B EXTI15_10_IRQHandler - - PUBWEAK RTC_Alarm_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -RTC_Alarm_IRQHandler - B RTC_Alarm_IRQHandler - - PUBWEAK OTG_FS_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_FS_WKUP_IRQHandler - B OTG_FS_WKUP_IRQHandler - - PUBWEAK TIM8_BRK_TIM12_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_BRK_TIM12_IRQHandler - B TIM8_BRK_TIM12_IRQHandler - - PUBWEAK TIM8_UP_TIM13_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_UP_TIM13_IRQHandler - B TIM8_UP_TIM13_IRQHandler - - PUBWEAK TIM8_TRG_COM_TIM14_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_TRG_COM_TIM14_IRQHandler - B TIM8_TRG_COM_TIM14_IRQHandler - - PUBWEAK TIM8_CC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM8_CC_IRQHandler - B TIM8_CC_IRQHandler - - PUBWEAK DMA1_Stream7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA1_Stream7_IRQHandler - B DMA1_Stream7_IRQHandler - - PUBWEAK FMC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FMC_IRQHandler - B FMC_IRQHandler - - PUBWEAK SDIO_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SDIO_IRQHandler - B SDIO_IRQHandler - - PUBWEAK TIM5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM5_IRQHandler - B TIM5_IRQHandler - - PUBWEAK SPI3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI3_IRQHandler - B SPI3_IRQHandler - - PUBWEAK UART4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -UART4_IRQHandler - B UART4_IRQHandler - - PUBWEAK UART5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -UART5_IRQHandler - B UART5_IRQHandler - - PUBWEAK TIM6_DAC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM6_DAC_IRQHandler - B TIM6_DAC_IRQHandler - - PUBWEAK TIM7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -TIM7_IRQHandler - B TIM7_IRQHandler - - PUBWEAK DMA2_Stream0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream0_IRQHandler - B DMA2_Stream0_IRQHandler - - PUBWEAK DMA2_Stream1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream1_IRQHandler - B DMA2_Stream1_IRQHandler - - PUBWEAK DMA2_Stream2_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream2_IRQHandler - B DMA2_Stream2_IRQHandler - - PUBWEAK DMA2_Stream3_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream3_IRQHandler - B DMA2_Stream3_IRQHandler - - PUBWEAK DMA2_Stream4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream4_IRQHandler - B DMA2_Stream4_IRQHandler - - PUBWEAK ETH_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -ETH_IRQHandler - B ETH_IRQHandler - - PUBWEAK ETH_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -ETH_WKUP_IRQHandler - B ETH_WKUP_IRQHandler - - PUBWEAK CAN2_TX_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_TX_IRQHandler - B CAN2_TX_IRQHandler - - PUBWEAK CAN2_RX0_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_RX0_IRQHandler - B CAN2_RX0_IRQHandler - - PUBWEAK CAN2_RX1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_RX1_IRQHandler - B CAN2_RX1_IRQHandler - - PUBWEAK CAN2_SCE_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CAN2_SCE_IRQHandler - B CAN2_SCE_IRQHandler - - PUBWEAK OTG_FS_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_FS_IRQHandler - B OTG_FS_IRQHandler - - PUBWEAK DMA2_Stream5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream5_IRQHandler - B DMA2_Stream5_IRQHandler - - PUBWEAK DMA2_Stream6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream6_IRQHandler - B DMA2_Stream6_IRQHandler - - PUBWEAK DMA2_Stream7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2_Stream7_IRQHandler - B DMA2_Stream7_IRQHandler - - PUBWEAK USART6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -USART6_IRQHandler - B USART6_IRQHandler - - PUBWEAK I2C3_EV_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C3_EV_IRQHandler - B I2C3_EV_IRQHandler - - PUBWEAK I2C3_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -I2C3_ER_IRQHandler - B I2C3_ER_IRQHandler - - PUBWEAK OTG_HS_EP1_OUT_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_EP1_OUT_IRQHandler - B OTG_HS_EP1_OUT_IRQHandler - - PUBWEAK OTG_HS_EP1_IN_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_EP1_IN_IRQHandler - B OTG_HS_EP1_IN_IRQHandler - - PUBWEAK OTG_HS_WKUP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_WKUP_IRQHandler - B OTG_HS_WKUP_IRQHandler - - PUBWEAK OTG_HS_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -OTG_HS_IRQHandler - B OTG_HS_IRQHandler - - PUBWEAK DCMI_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DCMI_IRQHandler - B DCMI_IRQHandler - - PUBWEAK CRYP_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -CRYP_IRQHandler - B CRYP_IRQHandler - - PUBWEAK HASH_RNG_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -HASH_RNG_IRQHandler - B HASH_RNG_IRQHandler - - PUBWEAK FPU_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -FPU_IRQHandler - B FPU_IRQHandler - - PUBWEAK UART7_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -UART7_IRQHandler - B UART7_IRQHandler - - PUBWEAK UART8_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -UART8_IRQHandler - B UART8_IRQHandler - - PUBWEAK SPI4_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI4_IRQHandler - B SPI4_IRQHandler - - PUBWEAK SPI5_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI5_IRQHandler - B SPI5_IRQHandler - - PUBWEAK SPI6_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SPI6_IRQHandler - B SPI6_IRQHandler - - PUBWEAK SAI1_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -SAI1_IRQHandler - B SAI1_IRQHandler - - PUBWEAK LTDC_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -LTDC_IRQHandler - B LTDC_IRQHandler - - PUBWEAK LTDC_ER_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -LTDC_ER_IRQHandler - B LTDC_ER_IRQHandler - - PUBWEAK DMA2D_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DMA2D_IRQHandler - B DMA2D_IRQHandler - - PUBWEAK QUADSPI_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -QUADSPI_IRQHandler - B QUADSPI_IRQHandler - - PUBWEAK DSI_IRQHandler - SECTION .text:CODE:REORDER:NOROOT(1) -DSI_IRQHandler - B DSI_IRQHandler - - END -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx.h b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx.h index 523730af2c..74e920403c 100644 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx.h +++ b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx.h @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.0 + * @date 22-April-2016 * @brief CMSIS Cortex-M4 Device Peripheral Access Layer Header File. * This file contains all the peripheral register's definitions, bits * definitions and memory mapping for STM32F4xx devices. @@ -19,13 +19,13 @@ * - To change few application-specific parameters such as the HSE * crystal frequency * - Data structures and the address mapping for all peripherals - * - Peripheral's registers declarations and bits definition + * - Peripherals registers declarations and bits definition * - Macros to access peripheral’s registers hardware * ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -39,7 +39,7 @@ * See the License for the specific language governing permissions and * limitations under the License. * - ****************************************************************************** + ****************************************************************************** */ /** @addtogroup CMSIS @@ -66,32 +66,37 @@ */ #if !defined(STM32F40_41xxx) && !defined(STM32F427_437xx) && !defined(STM32F429_439xx) && !defined(STM32F401xx) && !defined(STM32F410xx) && \ - !defined(STM32F411xE) && !defined(STM32F446xx) && !defined(STM32F469_479xx) - /* #define STM32F40_41xxx */ /*!< STM32F405RG, STM32F405VG, STM32F405ZG, STM32F415RG, STM32F415VG, STM32F415ZG, + !defined(STM32F411xE) && !defined(STM32F412xG) && !defined(STM32F446xx) && !defined(STM32F469_479xx) + /* #define STM32F40_41xxx */ /*!< STM32F405RG, STM32F405VG, STM32F405ZG, STM32F415RG, STM32F415VG, STM32F415ZG, STM32F407VG, STM32F407VE, STM32F407ZG, STM32F407ZE, STM32F407IG, STM32F407IE, STM32F417VG, STM32F417VE, STM32F417ZG, STM32F417ZE, STM32F417IG and STM32F417IE Devices */ - /* #define STM32F427_437xx */ /*!< STM32F427VG, STM32F427VI, STM32F427ZG, STM32F427ZI, STM32F427IG, STM32F427II, + /* #define STM32F427_437xx */ /*!< STM32F427VG, STM32F427VI, STM32F427ZG, STM32F427ZI, STM32F427IG, STM32F427II, STM32F437VG, STM32F437VI, STM32F437ZG, STM32F437ZI, STM32F437IG, STM32F437II Devices */ - /* #define STM32F429_439xx */ /*!< STM32F429VG, STM32F429VI, STM32F429ZG, STM32F429ZI, STM32F429BG, STM32F429BI, - STM32F429NG, STM32F439NI, STM32F429IG, STM32F429II, STM32F439VG, STM32F439VI, + /* #define STM32F429_439xx */ /*!< STM32F429VG, STM32F429VI, STM32F429ZG, STM32F429ZI, STM32F429BG, STM32F429BI, + STM32F429NG, STM32F439NI, STM32F429IG, STM32F429II, STM32F439VG, STM32F439VI, STM32F439ZG, STM32F439ZI, STM32F439BG, STM32F439BI, STM32F439NG, STM32F439NI, STM32F439IG and STM32F439II Devices */ - /* #define STM32F401xx */ /*!< STM32F401CB, STM32F401CC, STM32F401RB, STM32F401RC, STM32F401VB, STM32F401VC + /* #define STM32F401xx */ /*!< STM32F401CB, STM32F401CC, STM32F401RB, STM32F401RC, STM32F401VB, STM32F401VC, STM32F401CD, STM32F401RD, STM32F401VD, STM32F401CExx, STM32F401RE and STM32F401VE Devices */ - /* #define STM32F410xx */ /*!< STM32F410T8, STM32F410TB, STM32F410C8, STM32F410CB, STM32F410R8 and STM32F410RB */ + /* #define STM32F410xx */ /*!< STM32F410Tx, STM32F410Cx and STM32F410Rx */ + + /* #define STM32F411xE */ /*!< STM32F411CC, STM32F411RC, STM32F411VC, STM32F411CE, STM32F411RE and STM32F411VE Devices */ + + /* #define STM32F412xG */ /*!< STM32F412CEU, STM32F412CGU, STM32F412ZET, STM32F412ZGT, STM32F412ZEJ, STM32F412ZGJ, + STM32F412VET, STM32F412VGT, STM32F412VEH, STM32F412VGH, STM32F412RET, STM32F412RGT, + STM32F412REY and STM32F412RGY Devices */ - /* #define STM32F411xE */ /*!< STM32F411CD, STM32F411RD, STM32F411VD, STM32F411CE, STM32F411RE and STM32F411VE Devices */ - /* #define STM32F446xx */ /*!< STM32F446MC, STM32F446ME, STM32F446RC, STM32F446RE, STM32F446VC, STM32F446VE, STM32F446ZC and STM32F446ZE Devices */ - + /* #define STM32F469_479xx */ /*!< STM32F479AI, STM32F479II, STM32F479BI, STM32F479NI, STM32F479AG, STM32F479IG, STM32F479BG, STM32F479NG, STM32F479AE, STM32F479IE, STM32F479BE, STM32F479NE Devices */ -#endif /* STM32F40_41xxx && STM32F427_437xx && STM32F429_439xx && STM32F401xx && STM32F410xx && STM32F411xE && STM32F446xx && STM32F469_479xx */ + +#endif /* STM32F40_41xxx && STM32F427_437xx && STM32F429_439xx && STM32F401xx && STM32F410xx && STM32F411xE && STM32F412xG && STM32F446xx && STM32F469_479xx */ /* Old STM32F40XX definition, maintained for legacy purpose */ #ifdef STM32F40XX @@ -108,9 +113,9 @@ */ #if !defined(STM32F40_41xxx) && !defined(STM32F427_437xx) && !defined(STM32F429_439xx) && !defined(STM32F401xx) && !defined(STM32F410xx) && \ - !defined(STM32F411xE) && !defined(STM32F446xx) && !defined(STM32F469_479xx) + !defined(STM32F411xE) && !defined(STM32F412xG) && !defined(STM32F446xx) && !defined(STM32F469_479xx) #error "Please select first the target STM32F4xx device used in your application (in stm32f4xx.h file)" -#endif +#endif /* STM32F40_41xxx && STM32F427_437xx && STM32F429_439xx && STM32F401xx && STM32F410xx && STM32F411xE && STM32F412xG && STM32F446xx && STM32F469_479xx */ #if !defined (USE_STDPERIPH_DRIVER) /** @@ -133,7 +138,7 @@ #if !defined (HSE_VALUE) #define HSE_VALUE ((uint32_t)25000000) /*!< Value of the External oscillator in Hz */ #endif /* HSE_VALUE */ -#elif defined(STM32F446xx) +#elif defined (STM32F412xG) || defined(STM32F446xx) #if !defined (HSE_VALUE) #define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */ #endif /* HSE_VALUE */ @@ -151,11 +156,11 @@ #endif /* HSI_VALUE */ /** - * @brief STM32F4XX Standard Peripherals Library version number V1.6.1 + * @brief STM32F4XX Standard Peripherals Library version number V1.7.0 */ #define __STM32F4XX_STDPERIPH_VERSION_MAIN (0x01) /*!< [31:24] main version */ -#define __STM32F4XX_STDPERIPH_VERSION_SUB1 (0x06) /*!< [23:16] sub1 version */ -#define __STM32F4XX_STDPERIPH_VERSION_SUB2 (0x01) /*!< [15:8] sub2 version */ +#define __STM32F4XX_STDPERIPH_VERSION_SUB1 (0x07) /*!< [23:16] sub1 version */ +#define __STM32F4XX_STDPERIPH_VERSION_SUB2 (0x00) /*!< [15:8] sub2 version */ #define __STM32F4XX_STDPERIPH_VERSION_RC (0x00) /*!< [7:0] release candidate */ #define __STM32F4XX_STDPERIPH_VERSION ((__STM32F4XX_STDPERIPH_VERSION_MAIN << 24)\ |(__STM32F4XX_STDPERIPH_VERSION_SUB1 << 16)\ @@ -370,7 +375,7 @@ typedef enum IRQn I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ - I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ USART1_IRQn = 37, /*!< USART1 global Interrupt */ @@ -378,7 +383,7 @@ typedef enum IRQn USART3_IRQn = 39, /*!< USART3 global Interrupt */ EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ RTC_Alarm_IRQn = 41, /*!< RTC Alarm (A and B) through EXTI Line Interrupt */ - OTG_FS_WKUP_IRQn = 42, /*!< USB OTG FS Wakeup through EXTI line interrupt */ + OTG_FS_WKUP_IRQn = 42, /*!< USB OTG FS Wakeup through EXTI line interrupt */ TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global interrupt */ TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global interrupt */ TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ @@ -604,7 +609,7 @@ typedef enum IRQn I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ - I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ USART1_IRQn = 37, /*!< USART1 global Interrupt */ @@ -612,7 +617,7 @@ typedef enum IRQn USART3_IRQn = 39, /*!< USART3 global Interrupt */ EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ RTC_Alarm_IRQn = 41, /*!< RTC Alarm (A and B) through EXTI Line Interrupt */ - OTG_FS_WKUP_IRQn = 42, /*!< USB OTG FS Wakeup through EXTI line interrupt */ + OTG_FS_WKUP_IRQn = 42, /*!< USB OTG FS Wakeup through EXTI line interrupt */ TIM8_BRK_IRQn = 43, /*!< TIM8 Break Interrupt */ TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global interrupt */ TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global interrupt */ @@ -656,7 +661,70 @@ typedef enum IRQn SPDIF_RX_IRQn = 94, /*!< QuadSPI global Interrupt */ FMPI2C1_EV_IRQn = 95, /*!< FMPI2C Event Interrupt */ FMPI2C1_ER_IRQn = 96 /*!< FMPCI2C Error Interrupt */ -#endif /* STM32F446xx */ +#endif /* STM32F446xx */ + +#if defined(STM32F412xG) + CAN1_TX_IRQn = 19, /*!< CAN1 TX Interrupt */ + CAN1_RX0_IRQn = 20, /*!< CAN1 RX0 Interrupt */ + CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ + CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_TIM9_IRQn = 24, /*!< TIM1 Break interrupt and TIM9 global interrupt */ + TIM1_UP_TIM10_IRQn = 25, /*!< TIM1 Update Interrupt and TIM10 global interrupt */ + TIM1_TRG_COM_TIM11_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt and TIM11 global interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTC_Alarm_IRQn = 41, /*!< RTC Alarm (A and B) through EXTI Line Interrupt */ + OTG_FS_WKUP_IRQn = 42, /*!< USB OTG FS Wakeup through EXTI line interrupt */ + TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global interrupt */ + TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global interrupt */ + TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ + TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ + DMA1_Stream7_IRQn = 47, /*!< DMA1 Stream7 Interrupt */ + FSMC_IRQn = 48, /*!< FSMC global Interrupt */ + SDIO_IRQn = 49, /*!< SDIO global Interrupt */ + TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ + SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ + TIM6_IRQn = 54, /*!< TIM6 global interrupt */ + TIM7_IRQn = 55, /*!< TIM7 global interrupt */ + DMA2_Stream0_IRQn = 56, /*!< DMA2 Stream 0 global Interrupt */ + DMA2_Stream1_IRQn = 57, /*!< DMA2 Stream 1 global Interrupt */ + DMA2_Stream2_IRQn = 58, /*!< DMA2 Stream 2 global Interrupt */ + DMA2_Stream3_IRQn = 59, /*!< DMA2 Stream 3 global Interrupt */ + DMA2_Stream4_IRQn = 60, /*!< DMA2 Stream 4 global Interrupt */ + DFSDM1_FLT0_IRQn = 61, /*!< DFSDM1 Filter 0 global Interrupt */ + DFSDM1_FLT1_IRQn = 62, /*!< DFSDM1 Filter 1 global Interrupt */ + CAN2_TX_IRQn = 63, /*!< CAN2 TX Interrupt */ + CAN2_RX0_IRQn = 64, /*!< CAN2 RX0 Interrupt */ + CAN2_RX1_IRQn = 65, /*!< CAN2 RX1 Interrupt */ + CAN2_SCE_IRQn = 66, /*!< CAN2 SCE Interrupt */ + OTG_FS_IRQn = 67, /*!< USB OTG FS global Interrupt */ + DMA2_Stream5_IRQn = 68, /*!< DMA2 Stream 5 global interrupt */ + DMA2_Stream6_IRQn = 69, /*!< DMA2 Stream 6 global interrupt */ + DMA2_Stream7_IRQn = 70, /*!< DMA2 Stream 7 global interrupt */ + USART6_IRQn = 71, /*!< USART6 global interrupt */ + I2C3_EV_IRQn = 72, /*!< I2C3 event interrupt */ + I2C3_ER_IRQn = 73, /*!< I2C3 error interrupt */ + RNG_IRQn = 80, /*!< RNG global Interrupt */ + FPU_IRQn = 81, /*!< FPU global interrupt */ + SPI4_IRQn = 84, /*!< SPI4 global Interrupt */ + SPI5_IRQn = 85, /*!< SPI5 global Interrupt */ + QUADSPI_IRQn = 92, /*!< QuadSPI global Interrupt */ + FMPI2C1_EV_IRQn = 95, /*!< FMPI2C1 Event Interrupt */ + FMPI2C1_ER_IRQn = 96 /*!< FMPI2C1 Error Interrupt */ +#endif /* STM32F412xG */ } IRQn_Type; /** @@ -725,7 +793,7 @@ typedef enum {ERROR = 0, SUCCESS = !ERROR} ErrorStatus; typedef struct { __IO uint32_t SR; /*!< ADC status register, Address offset: 0x00 */ - __IO uint32_t CR1; /*!< ADC control register 1, Address offset: 0x04 */ + __IO uint32_t CR1; /*!< ADC control register 1, Address offset: 0x04 */ __IO uint32_t CR2; /*!< ADC control register 2, Address offset: 0x08 */ __IO uint32_t SMPR1; /*!< ADC sample time register 1, Address offset: 0x0C */ __IO uint32_t SMPR2; /*!< ADC sample time register 2, Address offset: 0x10 */ @@ -738,7 +806,7 @@ typedef struct __IO uint32_t SQR1; /*!< ADC regular sequence register 1, Address offset: 0x2C */ __IO uint32_t SQR2; /*!< ADC regular sequence register 2, Address offset: 0x30 */ __IO uint32_t SQR3; /*!< ADC regular sequence register 3, Address offset: 0x34 */ - __IO uint32_t JSQR; /*!< ADC injected sequence register, Address offset: 0x38*/ + __IO uint32_t JSQR; /*!< ADC injected sequence register, Address offset: 0x38 */ __IO uint32_t JDR1; /*!< ADC injected data register 1, Address offset: 0x3C */ __IO uint32_t JDR2; /*!< ADC injected data register 2, Address offset: 0x40 */ __IO uint32_t JDR3; /*!< ADC injected data register 3, Address offset: 0x44 */ @@ -869,6 +937,43 @@ typedef struct __IO uint32_t SR; /*!< DAC status register, Address offset: 0x34 */ } DAC_TypeDef; +#if defined(STM32F412xG) +/** + * @brief DFSDM module registers + */ +typedef struct +{ + __IO uint32_t FLTCR1; /*!< DFSDM control register1, Address offset: 0x100 */ + __IO uint32_t FLTCR2; /*!< DFSDM control register2, Address offset: 0x104 */ + __IO uint32_t FLTISR; /*!< DFSDM interrupt and status register, Address offset: 0x108 */ + __IO uint32_t FLTICR; /*!< DFSDM interrupt flag clear register, Address offset: 0x10C */ + __IO uint32_t FLTJCHGR; /*!< DFSDM injected channel group selection register, Address offset: 0x110 */ + __IO uint32_t FLTFCR; /*!< DFSDM filter control register, Address offset: 0x114 */ + __IO uint32_t FLTJDATAR; /*!< DFSDM data register for injected group, Address offset: 0x118 */ + __IO uint32_t FLTRDATAR; /*!< DFSDM data register for regular group, Address offset: 0x11C */ + __IO uint32_t FLTAWHTR; /*!< DFSDM analog watchdog high threshold register, Address offset: 0x120 */ + __IO uint32_t FLTAWLTR; /*!< DFSDM analog watchdog low threshold register, Address offset: 0x124 */ + __IO uint32_t FLTAWSR; /*!< DFSDM analog watchdog status register Address offset: 0x128 */ + __IO uint32_t FLTAWCFR; /*!< DFSDM analog watchdog clear flag register Address offset: 0x12C */ + __IO uint32_t FLTEXMAX; /*!< DFSDM extreme detector maximum register, Address offset: 0x130 */ + __IO uint32_t FLTEXMIN; /*!< DFSDM extreme detector minimum register Address offset: 0x134 */ + __IO uint32_t FLTCNVTIMR; /*!< DFSDM conversion timer, Address offset: 0x138 */ +} DFSDM_TypeDef; + +/** + * @brief DFSDM channel configuration registers + */ +typedef struct +{ + __IO uint32_t CHCFGR1; /*!< DFSDM channel configuration register1, Address offset: 0x00 */ + __IO uint32_t CHCFGR2; /*!< DFSDM channel configuration register2, Address offset: 0x04 */ + __IO uint32_t CHAWSCDR; /*!< DFSDM channel analog watchdog and + short circuit detector register, Address offset: 0x08 */ + __IO uint32_t CHWDATAR; /*!< DFSDM channel watchdog filter data register, Address offset: 0x0C */ + __IO uint32_t CHDATINR; /*!< DFSDM channel data input register, Address offset: 0x10 */ +} DFSDM_Channel_TypeDef; + +#endif /* STM32F412xG */ /** * @brief Debug MCU */ @@ -1139,14 +1244,14 @@ typedef struct __IO uint32_t OPTCR1; /*!< FLASH option control register 1, Address offset: 0x18 */ } FLASH_TypeDef; -#if defined(STM32F40_41xxx) +#if defined(STM32F40_41xxx) || defined(STM32F412xG) /** * @brief Flexible Static Memory Controller */ typedef struct { - __IO uint32_t BTCR[8]; /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */ + __IO uint32_t BTCR[8]; /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */ } FSMC_Bank1_TypeDef; /** @@ -1198,7 +1303,7 @@ typedef struct __IO uint32_t PATT4; /*!< PC Card Attribute memory space timing register 4, Address offset: 0xAC */ __IO uint32_t PIO4; /*!< PC Card I/O space timing register 4, Address offset: 0xB0 */ } FSMC_Bank4_TypeDef; -#endif /* STM32F40_41xxx */ +#endif /* STM32F40_41xxx || STM32F412xG */ #if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx) /** @@ -1207,7 +1312,7 @@ typedef struct typedef struct { - __IO uint32_t BTCR[8]; /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */ + __IO uint32_t BTCR[8]; /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */ } FMC_Bank1_TypeDef; /** @@ -1301,13 +1406,13 @@ typedef struct __IO uint32_t MEMRMP; /*!< SYSCFG memory remap register, Address offset: 0x00 */ __IO uint32_t PMC; /*!< SYSCFG peripheral mode configuration register, Address offset: 0x04 */ __IO uint32_t EXTICR[4]; /*!< SYSCFG external interrupt configuration registers, Address offset: 0x08-0x14 */ -#if defined (STM32F410xx) +#if defined (STM32F410xx) || defined(STM32F412xG) uint32_t RESERVED; /*!< Reserved, 0x18 */ uint32_t CFGR2; /*!< Reserved, 0x1C */ __IO uint32_t CMPCR; /*!< SYSCFG Compensation cell control register, Address offset: 0x20 */ uint32_t RESERVED1[2]; /*!< Reserved, 0x24-0x28 */ __IO uint32_t CFGR; /*!< SYSCFG Configuration register, Address offset: 0x2C */ -#else /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F411xE || STM32F446xx || STM32F469_479xx */ +#else /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F411xE || STM32F412xG || STM32F446xx || STM32F469_479xx */ uint32_t RESERVED[2]; /*!< Reserved, 0x18-0x1C */ __IO uint32_t CMPCR; /*!< SYSCFG Compensation cell control register, Address offset: 0x20 */ #endif /* STM32F410xx */ @@ -1341,7 +1446,7 @@ typedef struct uint16_t RESERVED9; /*!< Reserved, 0x26 */ } I2C_TypeDef; -#if defined(STM32F410xx) || defined(STM32F446xx) +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) /** * @brief Inter-integrated Circuit Interface */ @@ -1360,7 +1465,7 @@ typedef struct __IO uint32_t RXDR; /*!< FMPI2C Receive data register, Address offset: 0x24 */ __IO uint32_t TXDR; /*!< FMPI2C Transmit data register, Address offset: 0x28 */ }FMPI2C_TypeDef; -#endif /* STM32F410xx || STM32F446xx */ +#endif /* STM32F410xx || STM32F412xG || STM32F446xx */ /** * @brief Independent WATCHDOG @@ -1470,8 +1575,8 @@ typedef struct __IO uint32_t PLLI2SCFGR; /*!< RCC PLLI2S configuration register, Address offset: 0x84 */ __IO uint32_t PLLSAICFGR; /*!< RCC PLLSAI configuration register, Address offset: 0x88 */ __IO uint32_t DCKCFGR; /*!< RCC Dedicated Clocks configuration register, Address offset: 0x8C */ - __IO uint32_t CKGATENR; /*!< RCC Clocks Gated Enable Register, Address offset: 0x90 */ /* Only for STM32F446xx devices */ - __IO uint32_t DCKCFGR2; /*!< RCC Dedicated Clocks configuration register 2, Address offset: 0x94 */ /* Only for STM32F446xx devices and STM32F410xx devices */ + __IO uint32_t CKGATENR; /*!< RCC Clocks Gated Enable Register, Address offset: 0x90 */ /* Only for STM32F412xG and STM32F446xx devices */ + __IO uint32_t DCKCFGR2; /*!< RCC Dedicated Clocks configuration register 2, Address offset: 0x94 */ /* Only for STM32F410xx, STM32F412xG and STM32F446xx devices */ } RCC_TypeDef; @@ -1618,7 +1723,7 @@ typedef struct } SPDIFRX_TypeDef; #endif /* STM32F446xx */ -#if defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx) /** * @brief QUAD Serial Peripheral Interface */ @@ -1634,11 +1739,11 @@ typedef struct __IO uint32_t ABR; /*!< QUADSPI Alternate Bytes register, Address offset: 0x1C */ __IO uint32_t DR; /*!< QUADSPI Data register, Address offset: 0x20 */ __IO uint32_t PSMKR; /*!< QUADSPI Polling Status Mask register, Address offset: 0x24 */ - __IO uint32_t PSMAR; /*!< QUADSPI Polling Status Match register, Address offset: 0x28 */ + __IO uint32_t PSMAR; /*!< QUADSPI Polling Status Match register, Address offset: 0x28 */ __IO uint32_t PIR; /*!< QUADSPI Polling Interval register, Address offset: 0x2C */ - __IO uint32_t LPTR; /*!< QUADSPI Low Power Timeout register, Address offset: 0x30 */ + __IO uint32_t LPTR; /*!< QUADSPI Low Power Timeout register, Address offset: 0x30 */ } QUADSPI_TypeDef; -#endif /* STM32F446xx || STM32F469_479xx */ +#endif /* STM32F412xG || STM32F446xx || STM32F469_479xx */ #if defined(STM32F446xx) /** @@ -1848,24 +1953,24 @@ typedef struct #define PERIPH_BASE ((uint32_t)0x40000000) /*!< Peripheral base address in the alias region */ #define BKPSRAM_BASE ((uint32_t)0x40024000) /*!< Backup SRAM(4 KB) base address in the alias region */ -#if defined(STM32F40_41xxx) +#if defined(STM32F40_41xxx) || defined(STM32F412xG) #define FSMC_R_BASE ((uint32_t)0xA0000000) /*!< FSMC registers base address */ -#endif /* STM32F40_41xxx */ +#endif /* STM32F40_41xxx || STM32F412xG */ #if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx) #define FMC_R_BASE ((uint32_t)0xA0000000) /*!< FMC registers base address */ #endif /* STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */ -#if defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx) #define QSPI_R_BASE ((uint32_t)0xA0001000) /*!< QuadSPI registers base address */ -#endif /* STM32F446xx || STM32F469_479xx */ +#endif /* STM32F412xG || STM32F446xx || STM32F469_479xx */ #define CCMDATARAM_BB_BASE ((uint32_t)0x12000000) /*!< CCM(core coupled memory) data RAM(64 KB) base address in the bit-band region */ #define SRAM1_BB_BASE ((uint32_t)0x22000000) /*!< SRAM1(112 KB) base address in the bit-band region */ -#define SRAM2_BB_BASE ((uint32_t)0x2201C000) /*!< SRAM2(16 KB) base address in the bit-band region */ +#define SRAM2_BB_BASE ((uint32_t)0x22380000) /*!< SRAM2(16 KB) base address in the bit-band region */ #define SRAM3_BB_BASE ((uint32_t)0x22400000) /*!< SRAM3(64 KB) base address in the bit-band region */ #define PERIPH_BB_BASE ((uint32_t)0x42000000) /*!< Peripheral base address in the bit-band region */ -#define BKPSRAM_BB_BASE ((uint32_t)0x42024000) /*!< Backup SRAM(4 KB) base address in the bit-band region */ +#define BKPSRAM_BB_BASE ((uint32_t)0x42480000) /*!< Backup SRAM(4 KB) base address in the bit-band region */ /* Legacy defines */ #define SRAM_BASE SRAM1_BASE @@ -1908,9 +2013,9 @@ typedef struct #define I2C1_BASE (APB1PERIPH_BASE + 0x5400) #define I2C2_BASE (APB1PERIPH_BASE + 0x5800) #define I2C3_BASE (APB1PERIPH_BASE + 0x5C00) -#if defined(STM32F410xx) || defined(STM32F446xx) +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) #define FMPI2C1_BASE (APB1PERIPH_BASE + 0x6000) -#endif /* STM32F410xx || STM32F446xx */ +#endif /* STM32F410xx || STM32F412xG || STM32F446xx */ #define CAN1_BASE (APB1PERIPH_BASE + 0x6400) #define CAN2_BASE (APB1PERIPH_BASE + 0x6800) #if defined(STM32F446xx) @@ -1954,6 +2059,17 @@ typedef struct #if defined(STM32F469_479xx) #define DSI_BASE (APB2PERIPH_BASE + 0x6C00) #endif /* STM32F469_479xx */ +#if defined(STM32F412xG) +#define DFSDM1_BASE (APB2PERIPH_BASE + 0x6000) +#define DFSDM1_Channel0_BASE (DFSDM1_BASE + 0x00) +#define DFSDM1_Channel1_BASE (DFSDM1_BASE + 0x20) +#define DFSDM1_Channel2_BASE (DFSDM1_BASE + 0x40) +#define DFSDM1_Channel3_BASE (DFSDM1_BASE + 0x60) +#define DFSDM1_Filter0_BASE (DFSDM1_BASE + 0x100) +#define DFSDM1_Filter1_BASE (DFSDM1_BASE + 0x180) +#define DFSDM0 ((DFSDM_TypeDef *) DFSDM1_Filter0_BASE) +#define DFSDM1 ((DFSDM_TypeDef *) DFSDM1_Filter1_BASE) +#endif /* STM32F412xG */ /*!< AHB1 peripherals */ #define GPIOA_BASE (AHB1PERIPH_BASE + 0x0000) @@ -2002,14 +2118,14 @@ typedef struct #define HASH_DIGEST_BASE (AHB2PERIPH_BASE + 0x60710) #define RNG_BASE (AHB2PERIPH_BASE + 0x60800) -#if defined(STM32F40_41xxx) +#if defined(STM32F40_41xxx) || defined(STM32F412xG) /*!< FSMC Bankx registers base address */ #define FSMC_Bank1_R_BASE (FSMC_R_BASE + 0x0000) #define FSMC_Bank1E_R_BASE (FSMC_R_BASE + 0x0104) #define FSMC_Bank2_R_BASE (FSMC_R_BASE + 0x0060) #define FSMC_Bank3_R_BASE (FSMC_R_BASE + 0x0080) #define FSMC_Bank4_R_BASE (FSMC_R_BASE + 0x00A0) -#endif /* STM32F40_41xxx */ +#endif /* STM32F40_41xxx || STM32F412xG */ #if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx) /*!< FMC Bankx registers base address */ @@ -2031,9 +2147,9 @@ typedef struct /** @addtogroup Peripheral_declaration * @{ */ -#if defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx) #define QUADSPI ((QUADSPI_TypeDef *) QSPI_R_BASE) -#endif /* STM32F446xx || STM32F469_479xx */ +#endif /* STM32F412xG || STM32F446xx || STM32F469_479xx */ #define TIM2 ((TIM_TypeDef *) TIM2_BASE) #define TIM3 ((TIM_TypeDef *) TIM3_BASE) #define TIM4 ((TIM_TypeDef *) TIM4_BASE) @@ -2060,9 +2176,9 @@ typedef struct #define I2C1 ((I2C_TypeDef *) I2C1_BASE) #define I2C2 ((I2C_TypeDef *) I2C2_BASE) #define I2C3 ((I2C_TypeDef *) I2C3_BASE) -#if defined(STM32F410xx) || defined(STM32F446xx) +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) #define FMPI2C1 ((FMPI2C_TypeDef *) FMPI2C1_BASE) -#endif /* STM32F410xx || STM32F446xx */ +#endif /* STM32F410xx || STM32F412xG || STM32F446xx */ #if defined(STM32F410xx) #define LPTIM1 ((LPTIM_TypeDef *) LPTIM1_BASE) #endif /* STM32F410xx */ @@ -2107,6 +2223,14 @@ typedef struct #if defined(STM32F469_479xx) #define DSI ((DSI_TypeDef *)DSI_BASE) #endif /* STM32F469_479xx */ +#if defined(STM32F412xG) +#define DFSDM1_Channel0 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel0_BASE) +#define DFSDM1_Channel1 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel1_BASE) +#define DFSDM1_Channel2 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel2_BASE) +#define DFSDM1_Channel3 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel3_BASE) +#define DFSDM1_Filter0 ((DFSDM_TypeDef *) DFSDM_Filter0_BASE) +#define DFSDM1_Filter1 ((DFSDM_TypeDef *) DFSDM_Filter1_BASE) +#endif /* STM32F412xG */ #define GPIOA ((GPIO_TypeDef *) GPIOA_BASE) #define GPIOB ((GPIO_TypeDef *) GPIOB_BASE) #define GPIOC ((GPIO_TypeDef *) GPIOC_BASE) @@ -2147,13 +2271,13 @@ typedef struct #define HASH_DIGEST ((HASH_DIGEST_TypeDef *) HASH_DIGEST_BASE) #define RNG ((RNG_TypeDef *) RNG_BASE) -#if defined(STM32F40_41xxx) +#if defined(STM32F40_41xxx) || defined(STM32F412xG) #define FSMC_Bank1 ((FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE) #define FSMC_Bank1E ((FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE) #define FSMC_Bank2 ((FSMC_Bank2_TypeDef *) FSMC_Bank2_R_BASE) #define FSMC_Bank3 ((FSMC_Bank3_TypeDef *) FSMC_Bank3_R_BASE) #define FSMC_Bank4 ((FSMC_Bank4_TypeDef *) FSMC_Bank4_R_BASE) -#endif /* STM32F40_41xxx */ +#endif /* STM32F40_41xxx || STM32F412xG */ #if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx) #define FMC_Bank1 ((FMC_Bank1_TypeDef *) FMC_Bank1_R_BASE) @@ -2503,19 +2627,24 @@ typedef struct #define ADC_CSR_JEOC1 ((uint32_t)0x00000004) /*!
© COPYRIGHT 2015 STMicroelectronics
+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -116,6 +116,15 @@ #include "stm32f4xx_lptim.h" #endif /* STM32F410xx */ +#if defined(STM32F412xG) +#include "stm32f4xx_rng.h" +#include "stm32f4xx_can.h" +#include "stm32f4xx_qspi.h" +#include "stm32f4xx_rng.h" +#include "stm32f4xx_fsmc.h" +#include "stm32f4xx_dfsdm.h" +#endif /* STM32F412xG */ + /* Exported types ------------------------------------------------------------*/ /* Exported constants --------------------------------------------------------*/ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_gpio.c b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_gpio.c index 29a6d133db..f15d839cf6 100644 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_gpio.c +++ b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_gpio.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_gpio.c * @author MCD Application Team - * @version V1.5.1 - * @date 22-May-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the GPIO peripheral: * + Initialization and Configuration @@ -63,7 +63,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_gpio.h b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_gpio.h index a62e703568..57e1cea0b8 100644 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_gpio.h +++ b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_gpio.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_gpio.h * @author MCD Application Team - * @version V1.5.1 - * @date 22-May-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the GPIO firmware * library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -248,7 +248,7 @@ typedef struct #define GPIO_AF_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ #define GPIO_AF_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ #define GPIO_AF_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ -#if defined (STM32F446xx) +#if defined(STM32F446xx) #define GPIO_AF0_TIM2 ((uint8_t)0x00) /* TIM2 Alternate Function mapping */ #endif /* STM32F446xx */ @@ -257,7 +257,9 @@ typedef struct */ #define GPIO_AF_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ #define GPIO_AF_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - +#if defined(STM32F410xx) +#define GPIO_AF_LPTIM ((uint8_t)0x01) /* LPTIM Alternate Function mapping */ +#endif /* STM32F410xx */ /** * @brief AF 2 selection */ @@ -272,7 +274,7 @@ typedef struct #define GPIO_AF_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ #define GPIO_AF_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ #define GPIO_AF_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ -#if defined (STM32F446xx) +#if defined(STM32F446xx) #define GPIO_AF3_CEC ((uint8_t)0x03) /* CEC Alternate Function mapping */ #endif /* STM32F446xx */ /** @@ -281,10 +283,12 @@ typedef struct #define GPIO_AF_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ #define GPIO_AF_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ #define GPIO_AF_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ -#if defined (STM32F446xx) +#if defined(STM32F446xx) #define GPIO_AF4_CEC ((uint8_t)0x04) /* CEC Alternate Function mapping */ -#define GPIO_AF_FMPI2C ((uint8_t)0x04) /* FMPI2C Alternate Function mapping */ #endif /* STM32F446xx */ +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) +#define GPIO_AF_FMPI2C ((uint8_t)0x04) /* FMPI2C Alternate Function mapping */ +#endif /* STM32F410xx || STM32F446xx */ /** * @brief AF 5 selection @@ -300,10 +304,15 @@ typedef struct * @brief AF 6 selection */ #define GPIO_AF_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* SPI2 Alternate Function mapping (Only for STM32F411xE Devices) */ +#define GPIO_AF6_SPI1 ((uint8_t)0x06) /* SPI1 Alternate Function mapping (Only for STM32F410xx Devices) */ +#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* SPI2 Alternate Function mapping (Only for STM32F410xx/STM32F411xE Devices) */ #define GPIO_AF6_SPI4 ((uint8_t)0x06) /* SPI4 Alternate Function mapping (Only for STM32F411xE Devices) */ -#define GPIO_AF6_SPI5 ((uint8_t)0x06) /* SPI5 Alternate Function mapping (Only for STM32F411xE Devices) */ +#define GPIO_AF6_SPI5 ((uint8_t)0x06) /* SPI5 Alternate Function mapping (Only for STM32F410xx/STM32F411xE Devices) */ #define GPIO_AF_SAI1 ((uint8_t)0x06) /* SAI1 Alternate Function mapping */ +#define GPIO_AF_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping (only for STM32F412xG Devices) */ +#if defined(STM32F412xG) +#define GPIO_AF6_DFSDM1 ((uint8_t)0x06) /* DFSDM Alternate Function mapping */ +#endif /* STM32F412xG */ /** * @brief AF 7 selection @@ -326,7 +335,12 @@ typedef struct #define GPIO_AF_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ #define GPIO_AF_UART7 ((uint8_t)0x08) /* UART7 Alternate Function mapping */ #define GPIO_AF_UART8 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ -#if defined (STM32F446xx) +#if defined(STM32F412xG) +#define GPIO_AF8_USART3 ((uint8_t)0x08) /* USART3 Alternate Function mapping */ +#define GPIO_AF8_DFSDM1 ((uint8_t)0x08) /* DFSDM Alternate Function mapping */ +#define GPIO_AF8_CAN1 ((uint8_t)0x08) /* CAN1 Alternate Function mapping */ +#endif /* STM32F412xG */ +#if defined(STM32F446xx) #define GPIO_AF8_SAI2 ((uint8_t)0x08) /* SAI2 Alternate Function mapping */ #define GPIO_AF_SPDIF ((uint8_t)0x08) /* SPDIF Alternate Function mapping */ #endif /* STM32F446xx */ @@ -339,27 +353,34 @@ typedef struct #define GPIO_AF_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ #define GPIO_AF_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ #define GPIO_AF_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ - -#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping (Only for STM32F401xx/STM32F411xE Devices) */ -#define GPIO_AF9_I2C3 ((uint8_t)0x09) /* I2C3 Alternate Function mapping (Only for STM32F401xx/STM32F411xE Devices) */ -#if defined (STM32F446xx) +#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping (Only for STM32F401xx/STM32F410xx/STM32F411xE/STM32F412xG Devices) */ +#define GPIO_AF9_I2C3 ((uint8_t)0x09) /* I2C3 Alternate Function mapping (Only for STM32F401xx/STM32F411xE/STM32F412xG Devices) */ +#if defined(STM32F446xx) #define GPIO_AF9_SAI2 ((uint8_t)0x09) /* SAI2 Alternate Function mapping */ #endif /* STM32F446xx */ #define GPIO_AF9_LTDC ((uint8_t)0x09) /* LTDC Alternate Function mapping */ -#if defined (STM32F446xx) +#if defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx) #define GPIO_AF9_QUADSPI ((uint8_t)0x09) /* QuadSPI Alternate Function mapping */ -#endif /* STM32F446xx */ +#endif /* STM32F412xG || STM32F446xx || STM32F469_479xx */ +#if defined(STM32F410xx) || defined(STM32F412xG) +#define GPIO_AF9_FMPI2C ((uint8_t)0x09) /* FMPI2C Alternate Function mapping (Only for STM32F410xx Devices) */ +#endif /* STM32F410xx || STM32F412xG */ + /** * @brief AF 10 selection */ #define GPIO_AF_OTG_FS ((uint8_t)0xA) /* OTG_FS Alternate Function mapping */ #define GPIO_AF_OTG_HS ((uint8_t)0xA) /* OTG_HS Alternate Function mapping */ -#if defined (STM32F446xx) +#if defined(STM32F446xx) #define GPIO_AF10_SAI2 ((uint8_t)0x0A) /* SAI2 Alternate Function mapping */ #endif /* STM32F446xx */ -#if defined (STM32F446xx) +#if defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx) #define GPIO_AF10_QUADSPI ((uint8_t)0x0A) /* QuadSPI Alternate Function mapping */ -#endif /* STM32F446xx */ +#endif /* STM32F412xG || STM32F446xx || STM32F469_479xx */ +#if defined(STM32F412xG) +#define GPIO_AF10_FMC ((uint8_t)0xA) /* FMC Alternate Function mapping */ +#define GPIO_AF10_DFSDM ((uint8_t)0xA) /* DFSDM Alternate Function mapping */ +#endif /* STM32F412xG */ /** * @brief AF 11 selection */ @@ -368,13 +389,13 @@ typedef struct /** * @brief AF 12 selection */ -#if defined (STM32F40_41xxx) +#if defined(STM32F40_41xxx) || defined(STM32F412xG) #define GPIO_AF_FSMC ((uint8_t)0xC) /* FSMC Alternate Function mapping */ -#endif /* STM32F40_41xxx */ +#endif /* STM32F40_41xxx || STM32F412xG */ -#if defined (STM32F427_437xx) || defined (STM32F429_439xx) || defined (STM32F446xx) +#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx) #define GPIO_AF_FMC ((uint8_t)0xC) /* FMC Alternate Function mapping */ -#endif /* STM32F427_437xx || STM32F429_439xx || STM32F446xx */ +#endif /* STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */ #define GPIO_AF_OTG_HS_FS ((uint8_t)0xC) /* OTG HS configured in FS, Alternate Function mapping */ #define GPIO_AF_SDIO ((uint8_t)0xC) /* SDIO Alternate Function mapping */ @@ -383,7 +404,9 @@ typedef struct * @brief AF 13 selection */ #define GPIO_AF_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ - +#if defined(STM32F469_479xx) +#define GPIO_AF_DSI ((uint8_t)0x0D) /* DSI Alternate Function mapping */ +#endif /* STM32F469_479xx */ /** * @brief AF 14 selection */ @@ -394,7 +417,7 @@ typedef struct */ #define GPIO_AF_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#if defined (STM32F40_41xxx) +#if defined(STM32F40_41xxx) #define IS_GPIO_AF(AF) (((AF) == GPIO_AF_RTC_50Hz) || ((AF) == GPIO_AF_TIM14) || \ ((AF) == GPIO_AF_MCO) || ((AF) == GPIO_AF_TAMPER) || \ ((AF) == GPIO_AF_SWJ) || ((AF) == GPIO_AF_TRACE) || \ @@ -415,7 +438,7 @@ typedef struct ((AF) == GPIO_AF_EVENTOUT) || ((AF) == GPIO_AF_FSMC)) #endif /* STM32F40_41xxx */ -#if defined (STM32F401xx) +#if defined(STM32F401xx) #define IS_GPIO_AF(AF) (((AF) == GPIO_AF_RTC_50Hz) || ((AF) == GPIO_AF_TIM14) || \ ((AF) == GPIO_AF_MCO) || ((AF) == GPIO_AF_TAMPER) || \ ((AF) == GPIO_AF_SWJ) || ((AF) == GPIO_AF_TRACE) || \ @@ -432,11 +455,15 @@ typedef struct ((AF) == GPIO_AF_EVENTOUT) || ((AF) == GPIO_AF_SPI4)) #endif /* STM32F401xx */ -#if defined (STM32F411xE) +#if defined(STM32F411xE) #define IS_GPIO_AF(AF) (((AF) < 16) && ((AF) != 11) && ((AF) != 13) && ((AF) != 14)) #endif /* STM32F411xE */ -#if defined (STM32F427_437xx) || defined (STM32F429_439xx) +#if defined(STM32F410xx) +#define IS_GPIO_AF(AF) (((AF) < 10) || ((AF) == 15)) +#endif /* STM32F410xx */ + +#if defined(STM32F427_437xx) || defined(STM32F429_439xx) #define IS_GPIO_AF(AF) (((AF) == GPIO_AF_RTC_50Hz) || ((AF) == GPIO_AF_TIM14) || \ ((AF) == GPIO_AF_MCO) || ((AF) == GPIO_AF_TAMPER) || \ ((AF) == GPIO_AF_SWJ) || ((AF) == GPIO_AF_TRACE) || \ @@ -461,10 +488,18 @@ typedef struct ((AF) == GPIO_AF_LTDC)) #endif /* STM32F427_437xx || STM32F429_439xx */ -#if defined (STM32F446xx) +#if defined(STM32F412xG) +#define IS_GPIO_AF(AF) (((AF) < 16) && ((AF) != 11) && ((AF) != 14)) +#endif /* STM32F412xG */ + +#if defined(STM32F446xx) #define IS_GPIO_AF(AF) (((AF) < 16) && ((AF) != 11) && ((AF) != 14)) #endif /* STM32F446xx */ +#if defined(STM32F469_479xx) +#define IS_GPIO_AF(AF) ((AF) < 16) +#endif /* STM32F469_479xx */ + /** * @} */ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c index 224d448b03..330c776e8f 100644 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c +++ b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_rcc.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Reset and clock control (RCC) peripheral: * + Internal/external clocks, PLL, CSS and MCO configuration @@ -38,7 +38,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -116,7 +116,7 @@ #define DCKCFGR_OFFSET (RCC_OFFSET + 0x8C) #define TIMPRE_BitNumber 0x18 #define DCKCFGR_TIMPRE_BB (PERIPH_BB_BASE + (DCKCFGR_OFFSET * 32) + (TIMPRE_BitNumber * 4)) - + /* --- CFGR Register ---*/ #define RCC_CFGR_OFFSET (RCC_OFFSET + 0x08) #if defined(STM32F410xx) @@ -232,20 +232,20 @@ void RCC_DeInit(void) /* Reset HSEON, CSSON, PLLON, PLLI2S and PLLSAI(STM32F42xxx/43xxx/446xx/469xx/479xx devices) bits */ RCC->CR &= (uint32_t)0xEAF6FFFF; - + /* Reset PLLCFGR register */ RCC->PLLCFGR = 0x24003010; -#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469_479xx) /* Reset PLLI2SCFGR register */ RCC->PLLI2SCFGR = 0x20003000; #endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F411xE || STM32F446xx || STM32F469_479xx */ -#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx) /* Reset PLLSAICFGR register, only available for STM32F42xxx/43xxx/446xx/469xx/479xx devices */ RCC->PLLSAICFGR = 0x24003000; #endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */ - + /* Reset HSEBYP bit */ RCC->CR &= (uint32_t)0xFFFBFFFF; @@ -254,11 +254,11 @@ void RCC_DeInit(void) /* Disable Timers clock prescalers selection, only available for STM32F42/43xxx devices */ RCC->DCKCFGR = 0x00000000; - + #if defined(STM32F410xx) /* Disable LPTIM and FMPI2C clock prescalers selection, only available for STM32F410xx devices */ RCC->DCKCFGR2 = 0x00000000; -#endif /* STM32F410xx */ +#endif /* STM32F410xx */ } /** @@ -445,7 +445,7 @@ void RCC_LSICmd(FunctionalState NewState) *(__IO uint32_t *) CSR_LSION_BB = (uint32_t)NewState; } -#if defined(STM32F410xx) || defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx) /** * @brief Configures the main PLL clock source, multiplication and division factors. * @note This function must be used only when the main PLL is disabled. @@ -498,7 +498,7 @@ void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t PLLM, uint32_t PLLN, uint32_ RCC->PLLCFGR = PLLM | (PLLN << 6) | (((PLLP >> 1) -1) << 16) | (RCC_PLLSource) | (PLLQ << 24) | (PLLR << 28); } -#endif /* STM32F410xx || STM32F446xx || STM32F469_479xx */ +#endif /* STM32F410xx || STM32F412xG || STM32F446xx || STM32F469_479xx */ #if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F411xE) /** @@ -675,7 +675,7 @@ void RCC_PLLI2SConfig(uint32_t PLLI2SN, uint32_t PLLI2SQ, uint32_t PLLI2SR) } #endif /* STM32F427_437xx || STM32F429_439xx || STM32F469_479xx */ -#if defined(STM32F446xx) +#if defined(STM32F412xG ) || defined(STM32F446xx) /** * @brief Configures the PLLI2S clock multiplication and division factors. * @@ -721,7 +721,7 @@ void RCC_PLLI2SConfig(uint32_t PLLI2SM, uint32_t PLLI2SN, uint32_t PLLI2SP, uint RCC->PLLI2SCFGR = PLLI2SM | (PLLI2SN << 6) | (((PLLI2SP >> 1) -1) << 16) | (PLLI2SQ << 24) | (PLLI2SR << 28); } -#endif /* STM32F446xx */ +#endif /* STM32F412xG || STM32F446xx */ /** * @brief Enables or disables the PLLI2S. @@ -740,26 +740,26 @@ void RCC_PLLI2SCmd(FunctionalState NewState) /** * @brief Configures the PLLSAI clock multiplication and division factors. * - * @note This function can be used only for STM32F469_479xx devices - * + * @note This function can be used only for STM32F469_479xx devices + * * @note This function must be used only when the PLLSAI is disabled. - * @note PLLSAI clock source is common with the main PLL (configured in - * RCC_PLLConfig function ) + * @note PLLSAI clock source is common with the main PLL (configured in + * RCC_PLLConfig function ) * * @param PLLSAIN: specifies the multiplication factor for PLLSAI VCO output clock * This parameter must be a number between 50 and 432. - * @note You have to set the PLLSAIN parameter correctly to ensure that the VCO + * @note You have to set the PLLSAIN parameter correctly to ensure that the VCO * output frequency is between 100 and 432 MHz. * * @param PLLSAIP: specifies the division factor for PLL 48Mhz clock output * This parameter must be a number in the range {2, 4, 6, or 8}.. - * + * * @param PLLSAIQ: specifies the division factor for SAI1 clock * This parameter must be a number between 2 and 15. - * + * * @param PLLSAIR: specifies the division factor for LTDC clock * This parameter must be a number between 2 and 7. - * + * * @retval None */ void RCC_PLLSAIConfig(uint32_t PLLSAIN, uint32_t PLLSAIP, uint32_t PLLSAIQ, uint32_t PLLSAIR) @@ -770,7 +770,7 @@ void RCC_PLLSAIConfig(uint32_t PLLSAIN, uint32_t PLLSAIP, uint32_t PLLSAIQ, uint assert_param(IS_RCC_PLLSAIQ_VALUE(PLLSAIQ)); assert_param(IS_RCC_PLLSAIR_VALUE(PLLSAIR)); - RCC->PLLSAICFGR = (PLLSAIN << 6) | (PLLSAIP << 16) | (PLLSAIQ << 24) | (PLLSAIR << 28); + RCC->PLLSAICFGR = (PLLSAIN << 6) | (((PLLSAIP >> 1) -1) << 16) | (PLLSAIQ << 24) | (PLLSAIR << 28); } #endif /* STM32F469_479xx */ @@ -852,7 +852,7 @@ void RCC_PLLSAIConfig(uint32_t PLLSAIN, uint32_t PLLSAIQ, uint32_t PLLSAIR) /** * @brief Enables or disables the PLLSAI. * - * @note This function can be used only for STM32F42xxx/43xxx/446xx/469xx/479xx devices + * @note This function can be used only for STM32F42xxx/43xxx/446xx/469xx/479xx devices * * @note The PLLSAI is disabled by hardware when entering STOP and STANDBY modes. * @param NewState: new state of the PLLSAI. This parameter can be: ENABLE or DISABLE. @@ -916,13 +916,13 @@ void RCC_MCO1Config(uint32_t RCC_MCO1Source, uint32_t RCC_MCO1Div) /* Select MCO1 clock source and prescaler */ tmpreg |= RCC_MCO1Source | RCC_MCO1Div; - + /* Store the new value */ RCC->CFGR = tmpreg; #if defined(STM32F410xx) RCC_MCO1Cmd(ENABLE); -#endif /* STM32F410xx */ +#endif /* STM32F410xx */ } /** @@ -931,8 +931,8 @@ void RCC_MCO1Config(uint32_t RCC_MCO1Source, uint32_t RCC_MCO1Div) * @param RCC_MCO2Source: specifies the clock source to output. * This parameter can be one of the following values: * @arg RCC_MCO2Source_SYSCLK: System clock (SYSCLK) selected as MCO2 source - * @arg RCC_MCO2SOURCE_PLLI2SCLK: PLLI2S clock selected as MCO2 source, available for all STM32F4 devices except STM32F410xx - * @arg RCC_MCO2SOURCE_I2SCLK: I2SCLK clock selected as MCO2 source, available only for STM32F410xx devices + * @arg RCC_MCO2SOURCE_PLLI2SCLK: PLLI2S clock selected as MCO2 source, available for all STM32F4 devices except STM32F410xx + * @arg RCC_MCO2SOURCE_I2SCLK: I2SCLK clock selected as MCO2 source, available only for STM32F410xx devices * @arg RCC_MCO2Source_HSE: HSE clock selected as MCO2 source * @arg RCC_MCO2Source_PLLCLK: main PLL clock selected as MCO2 source * @param RCC_MCO2Div: specifies the MCO2 prescaler. @@ -961,13 +961,13 @@ void RCC_MCO2Config(uint32_t RCC_MCO2Source, uint32_t RCC_MCO2Div) /* Select MCO2 clock source and prescaler */ tmpreg |= RCC_MCO2Source | RCC_MCO2Div; - + /* Store the new value */ RCC->CFGR = tmpreg; #if defined(STM32F410xx) RCC_MCO2Cmd(ENABLE); -#endif /* STM32F410xx */ +#endif /* STM32F410xx */ } /** @@ -1031,7 +1031,7 @@ void RCC_MCO2Config(uint32_t RCC_MCO2Source, uint32_t RCC_MCO2Div) |---------------|----------------|----------------|-----------------|-----------------| |7WS(8CPU cycle)| NA | NA |154 < HCLK <= 168|140 < HCLK <= 160| +---------------|----------------|----------------|-----------------|-----------------+ - (#) For STM32F42xxx/43xxx/469xx/479xx devices, the maximum frequency of the SYSCLK and HCLK is 180 MHz, + (#) For STM32F42xxx/43xxx/469xx/479xx devices, the maximum frequency of the SYSCLK and HCLK is 180 MHz, PCLK2 90 MHz and PCLK1 45 MHz. Depending on the device voltage range, the maximum frequency should be adapted accordingly: +-------------------------------------------------------------------------------------+ @@ -1079,7 +1079,7 @@ void RCC_MCO2Config(uint32_t RCC_MCO2Source, uint32_t RCC_MCO2Div) |4WS(5CPU cycle)| NA | NA | NA |80 < HCLK <= 84 | +-------------------------------------------------------------------------------------+ - (#) For STM32F410xx/STM32F411xE devices, the maximum frequency of the SYSCLK and HCLK is 100 MHz, + (#) For STM32F410xx/STM32F411xE devices, the maximum frequency of the SYSCLK and HCLK is 100 MHz, PCLK2 100 MHz and PCLK1 50 MHz. Depending on the device voltage range, the maximum frequency should be adapted accordingly: +-------------------------------------------------------------------------------------+ @@ -1143,7 +1143,7 @@ void RCC_MCO2Config(uint32_t RCC_MCO2Source, uint32_t RCC_MCO2Div) * @arg RCC_SYSCLKSource_HSI: HSI selected as system clock source * @arg RCC_SYSCLKSource_HSE: HSE selected as system clock source * @arg RCC_SYSCLKSource_PLLCLK: PLL selected as system clock source (RCC_SYSCLKSource_PLLPCLK for STM32F446xx devices) - * @arg RCC_SYSCLKSource_PLLRCLK: PLL R selected as system clock source only for STM32F446xx devices + * @arg RCC_SYSCLKSource_PLLRCLK: PLL R selected as system clock source only for STM32F412xG and STM32F446xx devices * @retval None */ void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource) @@ -1173,7 +1173,7 @@ void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource) * - 0x00: HSI used as system clock * - 0x04: HSE used as system clock * - 0x08: PLL used as system clock (PLL P for STM32F446xx devices) - * - 0x0C: PLL R used as system clock (only for STM32F446xx devices) + * - 0x0C: PLL R used as system clock (only for STM32F412xG and STM32F446xx devices) */ uint8_t RCC_GetSYSCLKSource(void) { @@ -1317,9 +1317,9 @@ void RCC_PCLK2Config(uint32_t RCC_HCLK) void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks) { uint32_t tmp = 0, presc = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2; -#if defined(STM32F446xx) +#if defined(STM32F412xG) || defined(STM32F446xx) uint32_t pllr = 2; -#endif /* STM32F446xx */ +#endif /* STM32F412xG || STM32F446xx */ /* Get SYSCLK source -------------------------------------------------------*/ tmp = RCC->CFGR & RCC_CFGR_SWS; @@ -1348,14 +1348,14 @@ void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks) else { /* HSI used as PLL clock source */ - pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); + pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); } pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2; RCC_Clocks->SYSCLK_Frequency = pllvco/pllp; break; -#if defined(STM32F446xx) +#if defined(STM32F412xG) || defined(STM32F446xx) case 0x0C: /* PLL R used as system clock source */ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN SYSCLK = PLL_VCO / PLLR @@ -1371,13 +1371,13 @@ void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks) else { /* HSI used as PLL clock source */ - pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); + pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); } pllr = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >>28) + 1 ) *2; RCC_Clocks->SYSCLK_Frequency = pllvco/pllr; break; -#endif /* STM32F446xx */ +#endif /* STM32F412xG || STM32F446xx */ default: RCC_Clocks->SYSCLK_Frequency = HSI_VALUE; @@ -1523,7 +1523,7 @@ void RCC_BackupResetCmd(FunctionalState NewState) *(__IO uint32_t *) BDCR_BDRST_BB = (uint32_t)NewState; } -#if defined(STM32F446xx) +#if defined (STM32F412xG) || defined(STM32F446xx) /** * @brief Configures the I2S clock source (I2SCLK). * @note This function must be called before enabling the I2S APB clock. @@ -1563,7 +1563,7 @@ void RCC_I2SCLKConfig(uint32_t RCC_I2SAPBx, uint32_t RCC_I2SCLKSource) RCC->DCKCFGR |= (RCC_I2SCLKSource << 2); } } - +#if defined(STM32F446xx) /** * @brief Configures the SAIx clock source (SAIxCLK). * @note This function must be called before enabling the SAIx APB clock. @@ -1603,6 +1603,7 @@ void RCC_SAICLKConfig(uint32_t RCC_SAIInstance, uint32_t RCC_SAICLKSource) } } #endif /* STM32F446xx */ +#endif /* STM32F412xG || STM32F446xx */ #if defined(STM32F410xx) /** @@ -1620,7 +1621,7 @@ void RCC_I2SCLKConfig(uint32_t RCC_I2SCLKSource) { /* Check the parameters */ assert_param(IS_RCC_I2SCLK_SOURCE(RCC_I2SCLKSource)); - + /* Clear I2Sx clock source selection bits */ RCC->DCKCFGR &= ~RCC_DCKCFGR_I2SSRC; /* Set new I2Sx clock source*/ @@ -1822,6 +1823,66 @@ void RCC_LTDCCLKDivConfig(uint32_t RCC_PLLSAIDivR) RCC->DCKCFGR = tmpreg; } +#if defined(STM32F412xG) +/** + * @brief Configures the DFSDM clock source (DFSDMCLK). + * @note This function must be called before enabling the DFSDM APB clock. + * @param RCC_DFSDMCLKSource: specifies the DFSDM clock source. + * This parameter can be one of the following values: + * @arg RCC_DFSDM1CLKSource_APB: APB clock used as DFSDM clock source. + * @arg RCC_DFSDM1CLKSource_SYS: System clock used as DFSDM clock source. + * + * @retval None + */ +void RCC_DFSDM1CLKConfig(uint32_t RCC_DFSDM1CLKSource) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_DFSDM1CLK_SOURCE(RCC_DFSDM1CLKSource)); + + tmpreg = RCC->DCKCFGR; + + /* Clear CKDFSDM-SEL bit */ + tmpreg &= ~RCC_DCKCFGR_CKDFSDM1SEL; + + /* Set CKDFSDM-SEL bit according to RCC_DFSDMCLKSource value */ + tmpreg |= (RCC_DFSDM1CLKSource << 31) ; + + /* Store the new value */ + RCC->DCKCFGR = tmpreg; +} + +/** + * @brief Configures the DFSDM Audio clock source (DFSDMACLK). + * @note This function must be called before enabling the DFSDM APB clock. + * @param RCC_DFSDMACLKSource: specifies the DFSDM clock source. + * This parameter can be one of the following values: + * @arg RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB1: APB clock used as DFSDM clock source. + * @arg RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB2: System clock used as DFSDM clock source. + * + * @retval None + */ +void RCC_DFSDM1ACLKConfig(uint32_t RCC_DFSDMACLKSource) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_DFSDMACLK_SOURCE(RCC_DFSDMACLKSource)); + + tmpreg = RCC->DCKCFGR; + + /* Clear CKDFSDMA SEL bit */ + tmpreg &= ~RCC_DCKCFGR_CKDFSDM1ASEL; + + /* Set CKDFSDM-SEL bt according to RCC_DFSDMCLKSource value */ + tmpreg |= RCC_DFSDMACLKSource; + + /* Store the new value */ + RCC->DCKCFGR = tmpreg; +} +#endif /* STM32F412xG */ + /** * @brief Configures the Timers clocks prescalers selection. * @@ -1930,7 +1991,7 @@ void RCC_AHB2PeriphClockCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState) } } -#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F40_41xxx) || defined(STM32F412xG) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx) /** * @brief Enables or disables the AHB3 peripheral clock. * @note After reset, the peripheral clock (used for registers read/write access) @@ -1938,8 +1999,8 @@ void RCC_AHB2PeriphClockCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState) * using it. * @param RCC_AHBPeriph: specifies the AHB3 peripheral to gates its clock. * This parameter must be: - * - RCC_AHB3Periph_FSMC or RCC_AHB3Periph_FMC (STM32F429x/439x devices) - * - RCC_AHB3Periph_QSPI (STM32F446xx/STM32F469_479xx devices) + * - RCC_AHB3Periph_FSMC or RCC_AHB3Periph_FMC (STM32F412xG/STM32F429x/439x devices) + * - RCC_AHB3Periph_QSPI (STM32F412xG/STM32F446xx/STM32F469_479xx devices) * @param NewState: new state of the specified peripheral clock. * This parameter can be: ENABLE or DISABLE. * @retval None @@ -1959,7 +2020,7 @@ void RCC_AHB3PeriphClockCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState) RCC->AHB3ENR &= ~RCC_AHB3Periph; } } -#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */ +#endif /* STM32F40_41xxx || STM32F412xG || STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */ /** * @brief Enables or disables the Low Speed APB (APB1) peripheral clock. @@ -1977,7 +2038,7 @@ void RCC_AHB3PeriphClockCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState) * @arg RCC_APB1Periph_TIM12: TIM12 clock * @arg RCC_APB1Periph_TIM13: TIM13 clock * @arg RCC_APB1Periph_TIM14: TIM14 clock - * @arg RCC_APB1Periph_LPTIM1: LPTIM1 clock (STM32F410xx devices) + * @arg RCC_APB1Periph_LPTIM1: LPTIM1 clock (STM32F410xx devices) * @arg RCC_APB1Periph_WWDG: WWDG clock * @arg RCC_APB1Periph_SPI2: SPI2 clock * @arg RCC_APB1Periph_SPI3: SPI3 clock @@ -2044,6 +2105,7 @@ void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState) * @arg RCC_APB2Periph_SAI2: SAI2 clock (STM32F446xx devices) * @arg RCC_APB2Periph_LTDC: LTDC clock (STM32F429xx/439xx devices) * @arg RCC_APB2Periph_DSI: DSI clock (STM32F469_479xx devices) + * @arg RCC_APB2Periph_DFSDM: DFSDM Clock (STM32F412xG Devices) * @param NewState: new state of the specified peripheral clock. * This parameter can be: ENABLE or DISABLE. * @retval None @@ -2114,7 +2176,7 @@ void RCC_AHB1PeriphResetCmd(uint32_t RCC_AHB1Periph, FunctionalState NewState) * @arg RCC_AHB2Periph_DCMI: DCMI clock * @arg RCC_AHB2Periph_CRYP: CRYP clock * @arg RCC_AHB2Periph_HASH: HASH clock - * @arg RCC_AHB2Periph_RNG: RNG clock for STM32F40_41xxx/STM32F427_437xx/STM32F429_439xx/STM32F469_479xx devices + * @arg RCC_AHB2Periph_RNG: RNG clock for STM32F40_41xxx/STM32F412xG/STM32F427_437xx/STM32F429_439xx/STM32F469_479xx devices * @arg RCC_AHB2Periph_OTG_FS: USB OTG FS clock * @param NewState: new state of the specified peripheral reset. * This parameter can be: ENABLE or DISABLE. @@ -2136,13 +2198,13 @@ void RCC_AHB2PeriphResetCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState) } } -#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F40_41xxx) || defined(STM32F412xG) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx) /** * @brief Forces or releases AHB3 peripheral reset. * @param RCC_AHB3Periph: specifies the AHB3 peripheral to reset. * This parameter must be: - * - RCC_AHB3Periph_FSMC or RCC_AHB3Periph_FMC (STM32F429x/439x devices) - * - RCC_AHB3Periph_QSPI (STM32F446xx/STM32F469_479xx devices) + * - RCC_AHB3Periph_FSMC or RCC_AHB3Periph_FMC (STM32F412xG and STM32F429x/439x devices) + * - RCC_AHB3Periph_QSPI (STM32F412xG/STM32F446xx/STM32F469_479xx devices) * @param NewState: new state of the specified peripheral reset. * This parameter can be: ENABLE or DISABLE. * @retval None @@ -2162,7 +2224,7 @@ void RCC_AHB3PeriphResetCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState) RCC->AHB3RSTR &= ~RCC_AHB3Periph; } } -#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */ +#endif /* STM32F40_41xxx || STM32F412xG || STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */ /** * @brief Forces or releases Low Speed APB (APB1) peripheral reset. @@ -2177,7 +2239,7 @@ void RCC_AHB3PeriphResetCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState) * @arg RCC_APB1Periph_TIM12: TIM12 clock * @arg RCC_APB1Periph_TIM13: TIM13 clock * @arg RCC_APB1Periph_TIM14: TIM14 clock - * @arg RCC_APB1Periph_LPTIM1: LPTIM1 clock (STM32F410xx devices) + * @arg RCC_APB1Periph_LPTIM1: LPTIM1 clock (STM32F410xx devices) * @arg RCC_APB1Periph_WWDG: WWDG clock * @arg RCC_APB1Periph_SPI2: SPI2 clock * @arg RCC_APB1Periph_SPI3: SPI3 clock @@ -2239,7 +2301,7 @@ void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState) * @arg RCC_APB2Periph_SAI1: SAI1 clock (STM32F42xxx/43xxx/446xx/469xx/479xx devices) * @arg RCC_APB2Periph_SAI2: SAI2 clock (STM32F446xx devices) * @arg RCC_APB2Periph_LTDC: LTDC clock (STM32F429xx/439xx devices) - * @arg RCC_APB2Periph_DSI: DSI clock (STM32F469_479xx devices) + * @arg RCC_APB2Periph_DSI: DSI clock (STM32F469_479xx devices) * @param NewState: new state of the specified peripheral reset. * This parameter can be: ENABLE or DISABLE. * @retval None @@ -2340,7 +2402,7 @@ void RCC_AHB2PeriphClockLPModeCmd(uint32_t RCC_AHB2Periph, FunctionalState NewSt } } -#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F40_41xxx) || defined(STM32F412xG) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx) /** * @brief Enables or disables the AHB3 peripheral clock during Low Power (Sleep) mode. * @note Peripheral clock gating in SLEEP mode can be used to further reduce @@ -2349,8 +2411,8 @@ void RCC_AHB2PeriphClockLPModeCmd(uint32_t RCC_AHB2Periph, FunctionalState NewSt * @note By default, all peripheral clocks are enabled during SLEEP mode. * @param RCC_AHBPeriph: specifies the AHB3 peripheral to gates its clock. * This parameter must be: - * - RCC_AHB3Periph_FSMC or RCC_AHB3Periph_FMC (STM32F429x/439x devices) - * - RCC_AHB3Periph_QSPI (STM32F446xx/STM32F469_479xx devices) + * - RCC_AHB3Periph_FSMC or RCC_AHB3Periph_FMC (STM32F412xG/STM32F429x/439x devices) + * - RCC_AHB3Periph_QSPI (STM32F412xG/STM32F446xx/STM32F469_479xx devices) * @param NewState: new state of the specified peripheral clock. * This parameter can be: ENABLE or DISABLE. * @retval None @@ -2369,7 +2431,7 @@ void RCC_AHB3PeriphClockLPModeCmd(uint32_t RCC_AHB3Periph, FunctionalState NewSt RCC->AHB3LPENR &= ~RCC_AHB3Periph; } } -#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */ +#endif /* STM32F40_41xxx || STM32F412xG || STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */ /** * @brief Enables or disables the APB1 peripheral clock during Low Power (Sleep) mode. @@ -2388,7 +2450,7 @@ void RCC_AHB3PeriphClockLPModeCmd(uint32_t RCC_AHB3Periph, FunctionalState NewSt * @arg RCC_APB1Periph_TIM12: TIM12 clock * @arg RCC_APB1Periph_TIM13: TIM13 clock * @arg RCC_APB1Periph_TIM14: TIM14 clock - * @arg RCC_APB1Periph_LPTIM1: LPTIM1 clock (STM32F410xx devices) + * @arg RCC_APB1Periph_LPTIM1: LPTIM1 clock (STM32F410xx devices) * @arg RCC_APB1Periph_WWDG: WWDG clock * @arg RCC_APB1Periph_SPI2: SPI2 clock * @arg RCC_APB1Periph_SPI3: SPI3 clock @@ -2454,7 +2516,7 @@ void RCC_APB1PeriphClockLPModeCmd(uint32_t RCC_APB1Periph, FunctionalState NewSt * @arg RCC_APB2Periph_SAI1: SAI1 clock (STM32F42xxx/43xxx/446xx/469xx/479xx devices) * @arg RCC_APB2Periph_SAI2: SAI2 clock (STM32F446xx devices) * @arg RCC_APB2Periph_LTDC: LTDC clock (STM32F429xx/439xx devices) - * @arg RCC_APB2Periph_DSI: DSI clock (STM32F469_479xx devices) + * @arg RCC_APB2Periph_DSI: DSI clock (STM32F469_479xx devices) * @param NewState: new state of the specified peripheral clock. * This parameter can be: ENABLE or DISABLE. * @retval None @@ -2536,7 +2598,7 @@ void RCC_DSIClockSourceConfig(uint8_t RCC_ClockSource) { /* Check the parameters */ assert_param(IS_RCC_DSI_CLOCKSOURCE(RCC_ClockSource)); - + if(RCC_ClockSource == RCC_DSICLKSource_PLLR) { SET_BIT(RCC->DCKCFGR, RCC_DCKCFGR_DSISEL); @@ -2548,7 +2610,7 @@ void RCC_DSIClockSourceConfig(uint8_t RCC_ClockSource) } #endif /* STM32F469_479xx */ -#if defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx) /** * @brief Configures the 48MHz clock Source. * @note This feature is only available for STM32F446xx/STM32F469_479xx devices. @@ -2556,13 +2618,14 @@ void RCC_DSIClockSourceConfig(uint8_t RCC_ClockSource) * This parameter can be one of the following values: * @arg RCC_48MHZCLKSource_PLL: 48MHz from PLL selected. * @arg RCC_48MHZCLKSource_PLLSAI: 48MHz from PLLSAI selected. + * @arg RCC_CK48CLKSOURCE_PLLI2SQ : 48MHz from PLLI2SQ * @retval None */ void RCC_48MHzClockSourceConfig(uint8_t RCC_ClockSource) { /* Check the parameters */ assert_param(IS_RCC_48MHZ_CLOCKSOURCE(RCC_ClockSource)); -#if defined(STM32F469_479xx) +#if defined(STM32F469_479xx) if(RCC_ClockSource == RCC_48MHZCLKSource_PLLSAI) { SET_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL); @@ -2571,7 +2634,7 @@ void RCC_48MHzClockSourceConfig(uint8_t RCC_ClockSource) { CLEAR_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL); } -#elif defined(STM32F446xx) +#elif defined(STM32F446xx) if(RCC_ClockSource == RCC_48MHZCLKSource_PLLSAI) { SET_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL); @@ -2580,8 +2643,17 @@ void RCC_48MHzClockSourceConfig(uint8_t RCC_ClockSource) { CLEAR_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL); } +#elif defined(STM32F412xG) + if(RCC_ClockSource == RCC_CK48CLKSOURCE_PLLI2SQ) + { + SET_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL); + } + else + { + CLEAR_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL); + } #else -#endif /* STM32F469_479xx */ +#endif /* STM32F469_479xx */ } /** @@ -2597,7 +2669,7 @@ void RCC_SDIOClockSourceConfig(uint8_t RCC_ClockSource) { /* Check the parameters */ assert_param(IS_RCC_SDIO_CLOCKSOURCE(RCC_ClockSource)); -#if defined(STM32F469_479xx) +#if defined(STM32F469_479xx) if(RCC_ClockSource == RCC_SDIOCLKSource_SYSCLK) { SET_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SDIOSEL); @@ -2606,7 +2678,7 @@ void RCC_SDIOClockSourceConfig(uint8_t RCC_ClockSource) { CLEAR_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SDIOSEL); } -#elif defined(STM32F446xx) +#elif defined(STM32F412xG) || defined(STM32F446xx) if(RCC_ClockSource == RCC_SDIOCLKSource_SYSCLK) { SET_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL); @@ -2616,9 +2688,9 @@ void RCC_SDIOClockSourceConfig(uint8_t RCC_ClockSource) CLEAR_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL); } #else -#endif /* STM32F469_479xx */ +#endif /* STM32F469_479xx */ } -#endif /* STM32F446xx || STM32F469_479xx */ +#endif /* STM32F412xG || STM32F446xx || STM32F469_479xx */ #if defined(STM32F446xx) /** @@ -2702,7 +2774,7 @@ void RCC_CECClockSourceConfig(uint8_t RCC_ClockSource) } #endif /* STM32F446xx */ -#if defined(STM32F410xx) || defined(STM32F446xx) +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) /** * @brief Configures the FMPI2C1 clock Source. * @note This feature is only available for STM32F446xx devices. @@ -2723,7 +2795,7 @@ void RCC_FMPI2C1ClockSourceConfig(uint32_t RCC_ClockSource) /* Set new FMPI2C1 clock source */ RCC->DCKCFGR2 |= RCC_ClockSource; } -#endif /* STM32F410xx || STM32F446xx */ +#endif /* STM32F410xx || STM32F412xG || STM32F446xx */ /** * @} */ @@ -2917,7 +2989,7 @@ ITStatus RCC_GetITStatus(uint8_t RCC_IT) * @arg RCC_IT_HSERDY: HSE ready interrupt * @arg RCC_IT_PLLRDY: main PLL ready interrupt * @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt - * @arg RCC_IT_PLLSAIRDY: PLLSAI ready interrupt (only for STM32F42xxx/43xxx/446xx/469xx/479xx devices) + * @arg RCC_IT_PLLSAIRDY: PLLSAI ready interrupt (only for STM32F42xxx/43xxx/446xx/469xx/479xx devices) * @arg RCC_IT_CSS: Clock Security System interrupt * @retval None */ diff --git a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.h b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.h index b43aec4145..06ddee1470 100644 --- a/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.h +++ b/lib/main/CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.h @@ -2,13 +2,13 @@ ****************************************************************************** * @file stm32f4xx_rcc.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief This file contains all the functions prototypes for the RCC firmware library. + * @version V1.7.1 + * @date 20-May-2016 + * @brief This file contains all the functions prototypes for the RCC firmware library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -108,17 +108,20 @@ typedef struct #define IS_RCC_PLLN_VALUE(VALUE) ((50 <= (VALUE)) && ((VALUE) <= 432)) #define IS_RCC_PLLP_VALUE(VALUE) (((VALUE) == 2) || ((VALUE) == 4) || ((VALUE) == 6) || ((VALUE) == 8)) #define IS_RCC_PLLQ_VALUE(VALUE) ((4 <= (VALUE)) && ((VALUE) <= 15)) -#if defined(STM32F410xx) || defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx) #define IS_RCC_PLLR_VALUE(VALUE) ((2 <= (VALUE)) && ((VALUE) <= 7)) -#endif /* STM32F410xx || STM32F446xx || STM32F469_479xx */ +#endif /* STM32F410xx || STM32F412xG || STM32F446xx || STM32F469_479xx */ #define IS_RCC_PLLI2SN_VALUE(VALUE) ((50 <= (VALUE)) && ((VALUE) <= 432)) #define IS_RCC_PLLI2SR_VALUE(VALUE) ((2 <= (VALUE)) && ((VALUE) <= 7)) #define IS_RCC_PLLI2SM_VALUE(VALUE) ((VALUE) <= 63) #define IS_RCC_PLLI2SQ_VALUE(VALUE) ((2 <= (VALUE)) && ((VALUE) <= 15)) -#if defined(STM32F446xx) +#if defined(STM32F446xx) #define IS_RCC_PLLI2SP_VALUE(VALUE) (((VALUE) == 2) || ((VALUE) == 4) || ((VALUE) == 6) || ((VALUE) == 8)) #define IS_RCC_PLLSAIM_VALUE(VALUE) ((VALUE) <= 63) +#elif defined(STM32F412xG) +#define IS_RCC_PLLI2SP_VALUE(VALUE) (((VALUE) == 2) || ((VALUE) == 4) || ((VALUE) == 6) || ((VALUE) == 8)) +#else #endif /* STM32F446xx */ #define IS_RCC_PLLSAIN_VALUE(VALUE) ((50 <= (VALUE)) && ((VALUE) <= 432)) #if defined(STM32F446xx) || defined(STM32F469_479xx) @@ -137,7 +140,7 @@ typedef struct * @{ */ -#if defined(STM32F446xx) +#if defined(STM32F412xG) || defined(STM32F446xx) #define RCC_SYSCLKSource_HSI ((uint32_t)0x00000000) #define RCC_SYSCLKSource_HSE ((uint32_t)0x00000001) #define RCC_SYSCLKSource_PLLPCLK ((uint32_t)0x00000002) @@ -157,7 +160,7 @@ typedef struct #define IS_RCC_SYSCLK_SOURCE(SOURCE) (((SOURCE) == RCC_SYSCLKSource_HSI) || \ ((SOURCE) == RCC_SYSCLKSource_HSE) || \ ((SOURCE) == RCC_SYSCLKSource_PLLCLK)) -#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F410xx || STM32F411xE || STM32F469_479xx */ +#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F410xx || STM32F411xE || STM32F469_479xx */ /** * @} */ @@ -313,8 +316,10 @@ typedef struct #define RCC_LPTIM1CLKSOURCE_LSI ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_1) #define RCC_LPTIM1CLKSOURCE_LSE ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_0 | RCC_DCKCFGR2_LPTIM1SEL_1) -#define IS_RCC_LPTIM1_SOURCE(SOURCE) (((SOURCE) == RCC_LPTIM1CLKSOURCE_PCLK) || ((SOURCE) == RCC_LPTIM1CLKSOURCE_HSI) || \ - ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSI) || ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSE)) +#define IS_RCC_LPTIM1_CLOCKSOURCE(SOURCE) (((SOURCE) == RCC_LPTIM1CLKSOURCE_PCLK) || ((SOURCE) == RCC_LPTIM1CLKSOURCE_HSI) || \ + ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSI) || ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSE)) +/* Legacy Defines */ +#define IS_RCC_LPTIM1_SOURCE IS_RCC_LPTIM1_CLOCKSOURCE /** * @} */ @@ -325,13 +330,15 @@ typedef struct #define RCC_I2SAPBCLKSOURCE_PLLR ((uint32_t)0x00000000) #define RCC_I2SAPBCLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_I2SSRC_0) #define RCC_I2SAPBCLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_I2SSRC_1) +#define IS_RCC_I2SCLK_SOURCE(SOURCE) (((SOURCE) == RCC_I2SAPBCLKSOURCE_PLLR) || ((SOURCE) == RCC_I2SAPBCLKSOURCE_EXT) || \ + ((SOURCE) == RCC_I2SAPBCLKSOURCE_PLLSRC)) /** * @} */ #endif /* STM32F410xx */ -#if defined(STM32F446xx) +#if defined(STM32F412xG) || defined(STM32F446xx) /** @defgroup RCC_I2S_Clock_Source * @{ */ @@ -355,7 +362,7 @@ typedef struct /** * @} */ - +#if defined(STM32F446xx) /** @defgroup RCC_SAI_Clock_Source * @{ */ @@ -380,6 +387,7 @@ typedef struct * @} */ #endif /* STM32F446xx */ +#endif /* STM32F412xG || STM32F446xx */ #if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F411xE) || defined(STM32F469_479xx) /** @defgroup RCC_I2S_Clock_Source @@ -446,7 +454,7 @@ typedef struct */ #endif /* STM32F469_479xx */ -#if defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx) /** @defgroup RCC_SDIO_Clock_Source_Selection * @{ */ @@ -462,14 +470,22 @@ typedef struct /** @defgroup RCC_48MHZ_Clock_Source_Selection * @{ */ +#if defined(STM32F446xx) || defined(STM32F469_479xx) #define RCC_48MHZCLKSource_PLL ((uint8_t)0x00) #define RCC_48MHZCLKSource_PLLSAI ((uint8_t)0x01) #define IS_RCC_48MHZ_CLOCKSOURCE(CLKSOURCE) (((CLKSOURCE) == RCC_48MHZCLKSource_PLL) || \ ((CLKSOURCE) == RCC_48MHZCLKSource_PLLSAI)) +#endif /* STM32F446xx || STM32F469_479xx */ +#if defined(STM32F412xG) +#define RCC_CK48CLKSOURCE_PLLQ ((uint8_t)0x00) +#define RCC_CK48CLKSOURCE_PLLI2SQ ((uint8_t)0x01) /* Only for STM32F412xG Devices */ +#define IS_RCC_48MHZ_CLOCKSOURCE(CLKSOURCE) (((CLKSOURCE) == RCC_CK48CLKSOURCE_PLLQ) || \ + ((CLKSOURCE) == RCC_CK48CLKSOURCE_PLLI2SQ)) +#endif /* STM32F412xG */ /** * @} */ -#endif /* STM32F446xx || STM32F469_479xx */ +#endif /* STM32F412xG || STM32F446xx || STM32F469_479xx */ #if defined(STM32F446xx) /** @defgroup RCC_SPDIFRX_Clock_Source_Selection @@ -512,20 +528,42 @@ typedef struct */ #endif /* STM32F446xx */ -#if defined(STM32F410xx) || defined(STM32F4446xx) +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) /** @defgroup RCC_FMPI2C1_Clock_Source * @{ */ #define RCC_FMPI2C1CLKSource_APB1 ((uint32_t)0x00) #define RCC_FMPI2C1CLKSource_SYSCLK ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_0) #define RCC_FMPI2C1CLKSource_HSI ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_1) - + #define IS_RCC_FMPI2C1_CLOCKSOURCE(SOURCE) (((SOURCE) == RCC_FMPI2C1CLKSource_APB1) || ((SOURCE) == RCC_FMPI2C1CLKSource_SYSCLK) || \ - ((SOURCE) == RCC_FMPI2C1CLKSource_HSI)) + ((SOURCE) == RCC_FMPI2C1CLKSource_HSI)) /** * @} */ -#endif /* STM32F410xx || STM32F4446xx */ +#endif /* STM32F410xx || STM32F412xG || STM32F446xx */ + +#if defined(STM32F412xG) +/** @defgroup RCC_DFSDM_Clock_Source + * @{ + */ +#define RCC_DFSDM1CLKSource_APB ((uint8_t)0x00) +#define RCC_DFSDM1CLKSource_SYS ((uint8_t)0x01) +#define IS_RCC_DFSDM1CLK_SOURCE(SOURCE) (((SOURCE) == RCC_DFSDM1CLKSource_APB) || ((SOURCE) == RCC_DFSDM1CLKSource_SYS)) +/** + * @} + */ + +/** @defgroup RCC_DFSDM_Audio_Clock_Source RCC DFSDM Audio Clock Source + * @{ + */ +#define RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB1 ((uint32_t)0x00000000) +#define RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB2 ((uint32_t)RCC_DCKCFGR_CKDFSDM1ASEL) +#define IS_RCC_DFSDMACLK_SOURCE(SOURCE) (((SOURCE) == RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB1) || ((SOURCE) == RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB2)) +/** + * @} + */ +#endif /* STM32F412xG */ /** @defgroup RCC_AHB1_Peripherals * @{ @@ -574,7 +612,7 @@ typedef struct #define RCC_AHB2Periph_DCMI ((uint32_t)0x00000001) #define RCC_AHB2Periph_CRYP ((uint32_t)0x00000010) #define RCC_AHB2Periph_HASH ((uint32_t)0x00000020) -#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx) +#if defined(STM32F40_41xxx) || defined(STM32F412xG) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx) #define RCC_AHB2Periph_RNG ((uint32_t)0x00000040) #endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F469_479xx */ #define RCC_AHB2Periph_OTG_FS ((uint32_t)0x00000080) @@ -596,12 +634,18 @@ typedef struct #define IS_RCC_AHB3_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFFFE) == 0x00) && ((PERIPH) != 0x00)) #endif /* STM32F427_437xx || STM32F429_439xx */ -#if defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F446xx) || defined(STM32F469_479xx) #define RCC_AHB3Periph_FMC ((uint32_t)0x00000001) #define RCC_AHB3Periph_QSPI ((uint32_t)0x00000002) #define IS_RCC_AHB3_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFFFC) == 0x00) && ((PERIPH) != 0x00)) #endif /* STM32F446xx || STM32F469_479xx */ +#if defined(STM32F412xG) +#define RCC_AHB3Periph_FSMC ((uint32_t)0x00000001) +#define RCC_AHB3Periph_QSPI ((uint32_t)0x00000002) +#define IS_RCC_AHB3_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFFFC) == 0x00) && ((PERIPH) != 0x00)) +#endif /* STM32F412xG */ + /** * @} */ @@ -634,9 +678,9 @@ typedef struct #define RCC_APB1Periph_I2C1 ((uint32_t)0x00200000) #define RCC_APB1Periph_I2C2 ((uint32_t)0x00400000) #define RCC_APB1Periph_I2C3 ((uint32_t)0x00800000) -#if defined(STM32F410xx) || defined(STM32F446xx) +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) #define RCC_APB1Periph_FMPI2C1 ((uint32_t)0x01000000) -#endif /* STM32F410xx || STM32F446xx */ +#endif /* STM32F410xx || STM32F446xx */ #define RCC_APB1Periph_CAN1 ((uint32_t)0x02000000) #define RCC_APB1Periph_CAN2 ((uint32_t)0x04000000) #if defined(STM32F446xx) @@ -679,9 +723,12 @@ typedef struct #if defined(STM32F469_479xx) #define RCC_APB2Periph_DSI ((uint32_t)0x08000000) #endif /* STM32F469_479xx */ +#if defined(STM32F412xG) +#define RCC_APB2Periph_DFSDM ((uint32_t)0x01000000) +#endif /* STM32F412xG */ -#define IS_RCC_APB2_PERIPH(PERIPH) ((((PERIPH) & 0xF30880CC) == 0x00) && ((PERIPH) != 0x00)) -#define IS_RCC_APB2_RESET_PERIPH(PERIPH) ((((PERIPH) & 0xF30886CC) == 0x00) && ((PERIPH) != 0x00)) +#define IS_RCC_APB2_PERIPH(PERIPH) ((((PERIPH) & 0xF20880CC) == 0x00) && ((PERIPH) != 0x00)) +#define IS_RCC_APB2_RESET_PERIPH(PERIPH) ((((PERIPH) & 0xF20886CC) == 0x00) && ((PERIPH) != 0x00)) /** * @} @@ -782,9 +829,9 @@ void RCC_LSICmd(FunctionalState NewState); void RCC_PLLCmd(FunctionalState NewState); -#if defined(STM32F410xx) || defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx) void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP, uint32_t PLLQ, uint32_t PLLR); -#endif /* STM32F410xx || STM32F446xx || STM32F469_479xx */ +#endif /* STM32F410xx || STM32F412xG || STM32F446xx || STM32F469_479xx */ #if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F411xE) void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP, uint32_t PLLQ); @@ -801,9 +848,9 @@ void RCC_PLLI2SConfig(uint32_t PLLI2SN, uint32_t PLLI2SR, uint32_t PLLI2S #if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx) void RCC_PLLI2SConfig(uint32_t PLLI2SN, uint32_t PLLI2SQ, uint32_t PLLI2SR); #endif /* STM32F427_437xx || STM32F429_439xx || STM32F469_479xx */ -#if defined(STM32F446xx) +#if defined(STM32F412xG) || defined(STM32F446xx) void RCC_PLLI2SConfig(uint32_t PLLI2SM, uint32_t PLLI2SN, uint32_t PLLI2SP, uint32_t PLLI2SQ, uint32_t PLLI2SR); -#endif /* STM32F446xx */ +#endif /* STM32F412xG || STM32F446xx */ void RCC_PLLSAICmd(FunctionalState NewState); #if defined(STM32F469_479xx) @@ -833,10 +880,12 @@ void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource); void RCC_RTCCLKCmd(FunctionalState NewState); void RCC_BackupResetCmd(FunctionalState NewState); -#if defined(STM32F446xx) +#if defined(STM32F412xG) || defined(STM32F446xx) void RCC_I2SCLKConfig(uint32_t RCC_I2SAPBx, uint32_t RCC_I2SCLKSource); +#if defined(STM32F446xx) void RCC_SAICLKConfig(uint32_t RCC_SAIInstance, uint32_t RCC_SAICLKSource); #endif /* STM32F446xx */ +#endif /* STM32F412xG || STM32F446xx */ #if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE) || defined(STM32F469_479xx) void RCC_I2SCLKConfig(uint32_t RCC_I2SCLKSource); @@ -879,11 +928,11 @@ void RCC_LSEModeConfig(uint8_t RCC_Mode); void RCC_DSIClockSourceConfig(uint8_t RCC_ClockSource); #endif /* STM32F469_479xx */ -/* Features available only for STM32F446xx/STM32F469_479xx devices */ -#if defined(STM32F446xx) || defined(STM32F469_479xx) +/* Features available only for STM32F412xG/STM32F446xx/STM32F469_479xx devices */ +#if defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx) void RCC_48MHzClockSourceConfig(uint8_t RCC_ClockSource); void RCC_SDIOClockSourceConfig(uint8_t RCC_ClockSource); -#endif /* STM32F446xx || STM32F469_479xx */ +#endif /* STM32F412xG || STM32F446xx || STM32F469_479xx */ /* Features available only for STM32F446xx devices */ #if defined(STM32F446xx) @@ -892,10 +941,10 @@ void RCC_SPDIFRXClockSourceConfig(uint8_t RCC_ClockSource); void RCC_CECClockSourceConfig(uint8_t RCC_ClockSource); #endif /* STM32F446xx */ -/* Features available only for STM32F410xx/STM32F446xx devices */ -#if defined(STM32F410xx) || defined(STM32F446xx) +/* Features available only for STM32F410xx/STM32F412xG/STM32F446xx devices */ +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) void RCC_FMPI2C1ClockSourceConfig(uint32_t RCC_ClockSource); -#endif /* STM32F410xx || STM32F446xx */ +#endif /* STM32F410xx || STM32F412xG || STM32F446xx */ /* Features available only for STM32F410xx devices */ #if defined(STM32F410xx) @@ -905,6 +954,10 @@ void RCC_MCO1Cmd(FunctionalState NewState); void RCC_MCO2Cmd(FunctionalState NewState); #endif /* STM32F410xx */ +#if defined(STM32F412xG) +void RCC_DFSDM1CLKConfig(uint32_t RCC_DFSDM1CLKSource); +void RCC_DFSDM1ACLKConfig(uint32_t RCC_DFSDM1ACLKSource); +#endif /* STM32F412xG */ /* Interrupts and flags management functions **********************************/ void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState); FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG); diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/misc.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/misc.h index ec05278694..36eada9a17 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/misc.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/misc.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file misc.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the miscellaneous * firmware library functions (add-on to CMSIS functions). ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_adc.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_adc.h index ea2a2faea2..398eed36d4 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_adc.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_adc.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_adc.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the ADC firmware * library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -325,9 +325,9 @@ typedef struct #define ADC_Channel_17 ((uint8_t)0x11) #define ADC_Channel_18 ((uint8_t)0x12) -#if defined (STM32F40_41xxx) +#if defined (STM32F40_41xxx) || defined(STM32F412xG) #define ADC_Channel_TempSensor ((uint8_t)ADC_Channel_16) -#endif /* STM32F40_41xxx */ +#endif /* STM32F40_41xxx || STM32F412xG */ #if defined (STM32F427_437xx) || defined (STM32F429_439xx) || defined (STM32F401xx) || defined (STM32F410xx) || defined (STM32F411xE) #define ADC_Channel_TempSensor ((uint8_t)ADC_Channel_18) diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_can.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_can.h index 8b859a5570..902024fa86 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_can.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_can.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_can.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the CAN firmware * library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_cec.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_cec.h index e4116ab1b5..9f9d285f37 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_cec.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_cec.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_cec.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the CEC firmware * library, applicable only for STM32F466xx devices. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_crc.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_crc.h index 7a8274bd63..b026a163c1 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_crc.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_crc.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_crc.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the CRC firmware * library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_cryp.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_cryp.h index 45548f443f..edb19e59cf 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_cryp.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_cryp.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_cryp.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the Cryptographic * processor(CRYP) firmware library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dac.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dac.h index bd8c090ec1..b603173908 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dac.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dac.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_dac.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the DAC firmware * library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dbgmcu.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dbgmcu.h index a87611fe36..a8e89b9f77 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dbgmcu.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dbgmcu.h @@ -2,13 +2,13 @@ ****************************************************************************** * @file stm32f4xx_dbgmcu.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the DBGMCU firmware library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dcmi.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dcmi.h index d46aee4f8b..5716dcc392 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dcmi.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dcmi.h @@ -2,13 +2,13 @@ ****************************************************************************** * @file stm32f4xx_dcmi.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the DCMI firmware library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dfsdm.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dfsdm.h new file mode 100644 index 0000000000..585efa6180 --- /dev/null +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dfsdm.h @@ -0,0 +1,764 @@ +/** + ****************************************************************************** + * @file stm32f4xx_dfsdm.h + * @author MCD Application Team + * @version V1.7.1 + * @date 20-May-2016 + * @brief This file contains all the functions prototypes for the DFSDM + * firmware library + ****************************************************************************** + * @attention + * + *

© COPYRIGHT 2016 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4XX_DFSDM_H +#define __STM32F4XX_DFSDM_H + +#ifdef __cplusplus + extern "C" { +#endif + +#if defined(STM32F412xG) +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup DFSDM + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief DFSDM Transceiver init structure definition + */ +typedef struct +{ + uint32_t DFSDM_Interface; /*!< Selects the serial interface type and input clock phase. + This parameter can be a value of @ref DFSDM_Interface_Selection */ + + uint32_t DFSDM_Clock; /*!< Specifies the clock source for the serial interface transceiver. + This parameter can be a value of @ref DFSDM_Clock_Selection */ + + uint32_t DFSDM_Input; /*!< Specifies the Input mode for the serial interface transceiver. + This parameter can be a value of @ref DFSDM_Input_Selection */ + + uint32_t DFSDM_Redirection; /*!< Specifies if the channel input is redirected from channel channel (y+1). + This parameter can be a value of @ref DFSDM_Redirection_Selection */ + + uint32_t DFSDM_PackingMode; /*!< Specifies the packing mode for the serial interface transceiver. + This parameter can be a value of @ref DFSDM_Pack_Selection */ + + uint32_t DFSDM_DataRightShift; /*!< Defines the final data right bit shift. + This parameter can be a value between 0 and 31 */ + + uint32_t DFSDM_Offset; /*!< Sets the calibration offset. + This parameter can be a value between 0 and 0xFFFFFF */ + + uint32_t DFSDM_CLKAbsenceDetector; /*!< Enables or disables the Clock Absence Detector. + This parameter can be a value of @ref DFSDM_Clock_Absence_Detector_state */ + + uint32_t DFSDM_ShortCircuitDetector; /*!< Enables or disables the Short Circuit Detector. + This parameter can be a value of @ref DFSDM_Short_Circuit_Detector_state */ +}DFSDM_TransceiverInitTypeDef; + +/** + * @brief DFSDM filter analog parameters structure definition + */ +typedef struct +{ + uint32_t DFSDM_SincOrder; /*!< Sets the Sinc Filter Order . + This parameter can be a value of @ref DFSDM_Sinc_Order */ + + uint32_t DFSDM_FilterOversamplingRatio; /*!< Sets the Sinc Filter Oversampling Ratio. + This parameter can be a value between 1 and 1024 */ + + uint32_t DFSDM_IntegratorOversamplingRatio;/*!< Sets the Integrator Oversampling Ratio. + This parameter can be a value between 1 and 256 */ +}DFSDM_FilterInitTypeDef; + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup DFSDM_Interface_Selection + * @{ + */ +#define DFSDM_Interface_SPI_RisingEdge ((uint32_t)0x00000000) /*!< DFSDM SPI interface with rising edge to strobe data */ +#define DFSDM_Interface_SPI_FallingEdge ((uint32_t)0x00000001) /*!< DFSDM SPI interface with falling edge to strobe data */ +#define DFSDM_Interface_Manchester1 ((uint32_t)0x00000002) /*!< DFSDM Manchester coded input, rising edge = logic 0, falling edge = logic 1 */ +#define DFSDM_Interface_Manchester2 ((uint32_t)0x00000003) /*!< DFSDM Manchester coded input, rising edge = logic 1, falling edge = logic 0 */ + +#define IS_DFSDM_INTERFACE(INTERFACE) (((INTERFACE) == DFSDM_Interface_SPI_RisingEdge) || \ + ((INTERFACE) == DFSDM_Interface_SPI_FallingEdge) || \ + ((INTERFACE) == DFSDM_Interface_Manchester1) || \ + ((INTERFACE) == DFSDM_Interface_Manchester2)) +/** + * @} + */ + +/** @defgroup DFSDM_Clock_Selection + * @{ + */ +#define DFSDM_Clock_External ((uint32_t)0x00000000) /*!< DFSDM clock coming from external DFSDM_CKINy input */ +#define DFSDM_Clock_Internal ((uint32_t)0x00000004) /*!< DFSDM clock coming from internal DFSDM_CKOUT output */ +#define DFSDM_Clock_InternalDiv2_Mode1 ((uint32_t)0x00000008) /*!< DFSDM clock coming from internal DFSDM_CKOUT output divided by 2 + and clock change is on every rising edge of DFSDM_CKOUT output signal */ +#define DFSDM_Clock_InternalDiv2_Mode2 ((uint32_t)0x0000000C) /*!< DFSDM clock coming from internal DFSDM_CKOUT output divided by 2 + and clock change is on every falling edge of DFSDM_CKOUT output signal */ + +#define IS_DFSDM_CLOCK(CLOCK) (((CLOCK) == DFSDM_Clock_External) || \ + ((CLOCK) == DFSDM_Clock_Internal) || \ + ((CLOCK) == DFSDM_Clock_InternalDiv2_Mode1) || \ + ((CLOCK) == DFSDM_Clock_InternalDiv2_Mode2)) +/** + * @} + */ + +/** @defgroup DFSDM_Input_Selection + * @{ + */ +#define DFSDM_Input_External ((uint32_t)0x00000000) /*!< DFSDM clock coming from external DFSDM_CKINy input */ +#define DFSDM_Input_ADC ((uint32_t)0x00001000) /*!< DFSDM clock coming from internal DFSDM_CKOUT output */ +#define DFSDM_Input_Internal ((uint32_t)0x00002000) /*!< DFSDM clock coming from internal DFSDM_CKOUT output divided by 2 + and clock change is on every rising edge of DFSDM_CKOUT output signal */ + +#define IS_DFSDM_Input_MODE(INPUT) (((INPUT) == DFSDM_Input_External) || \ + ((INPUT) == DFSDM_Input_ADC) || \ + ((INPUT) == DFSDM_Input_Internal)) +/** + * @} + */ + +/** @defgroup DFSDM_Redirection_Selection + * @{ + */ +#define DFSDM_Redirection_Disabled ((uint32_t)0x00000000) /*!< DFSDM Channel serial inputs are taken from pins of the same channel y */ +#define DFSDM_Redirection_Enabled DFSDM_CHCFGR1_CHINSEL /*!< DFSDM Channel serial inputs are taken from pins of the channel (y+1) modulo 8 */ + +#define IS_DFSDM_Redirection_STATE(STATE) (((STATE) == DFSDM_Redirection_Disabled) || \ + ((STATE) == DFSDM_Redirection_Enabled)) +/** + * @} + */ + +/** @defgroup DFSDM_Pack_Selection + * @{ + */ +#define DFSDM_PackingMode_Standard ((uint32_t)0x00000000) /*!< DFSDM Input data in DFSDM_CHDATINyR register are stored only in INDAT0[15:0] */ +#define DFSDM_PackingMode_Interleaved ((uint32_t)0x00004000) /*!< DFSDM Input data in DFSDM_CHDATINyR register are stored as two samples: + - first sample in INDAT0[15:0] - assigned to channel y + - second sample INDAT1[15:0] - assigned to channel y */ +#define DFSDM_PackingMode_Dual ((uint32_t)0x00008000) /*!< DFSDM Input data in DFSDM_CHDATINyR register are stored as two samples: + - first sample INDAT0[15:0] - assigned to channel y + - second sample INDAT1[15:0] - assigned to channel (y+1) */ + +#define IS_DFSDM_PACK_MODE(MODE) (((MODE) == DFSDM_PackingMode_Standard) || \ + ((MODE) == DFSDM_PackingMode_Interleaved) || \ + ((MODE) == DFSDM_PackingMode_Dual)) +/** + * @} + */ + +/** @defgroup DFSDM_Clock_Absence_Detector_state + * @{ + */ +#define DFSDM_CLKAbsenceDetector_Enable DFSDM_CHCFGR1_CKABEN /*!< DFSDM Clock Absence Detector is Enabled */ +#define DFSDM_CLKAbsenceDetector_Disable ((uint32_t)0x00000000) /*!< DFSDM Clock Absence Detector is Disabled */ + +#define IS_DFSDM_CLK_DETECTOR_STATE(STATE) (((STATE) == DFSDM_CLKAbsenceDetector_Enable) || \ + ((STATE) == DFSDM_CLKAbsenceDetector_Disable)) +/** + * @} + */ + +/** @defgroup DFSDM_Short_Circuit_Detector_state + * @{ + */ +#define DFSDM_ShortCircuitDetector_Enable DFSDM_CHCFGR1_SCDEN /*!< DFSDM Short Circuit Detector is Enabled */ +#define DFSDM_ShortCircuitDetector_Disable ((uint32_t)0x00000000) /*!< DFSDM Short Circuit Detector is Disabled */ + +#define IS_DFSDM_SC_DETECTOR_STATE(STATE) (((STATE) == DFSDM_ShortCircuitDetector_Enable) || \ + ((STATE) == DFSDM_ShortCircuitDetector_Disable)) +/** + * @} + */ + +/** @defgroup DFSDM_Sinc_Order + * @{ + */ +#define DFSDM_SincOrder_FastSinc ((uint32_t)0x00000000) /*!< DFSDM Sinc filter order = Fast sinc */ +#define DFSDM_SincOrder_Sinc1 ((uint32_t)0x20000000) /*!< DFSDM Sinc filter order = 1 */ +#define DFSDM_SincOrder_Sinc2 ((uint32_t)0x40000000) /*!< DFSDM Sinc filter order = 2 */ +#define DFSDM_SincOrder_Sinc3 ((uint32_t)0x60000000) /*!< DFSDM Sinc filter order = 3 */ +#define DFSDM_SincOrder_Sinc4 ((uint32_t)0x80000000) /*!< DFSDM Sinc filter order = 4 */ +#define DFSDM_SincOrder_Sinc5 ((uint32_t)0xA0000000) /*!< DFSDM Sinc filter order = 5 */ + +#define IS_DFSDM_SINC_ORDER(ORDER) (((ORDER) == DFSDM_SincOrder_FastSinc) || \ + ((ORDER) == DFSDM_SincOrder_Sinc1) || \ + ((ORDER) == DFSDM_SincOrder_Sinc2) || \ + ((ORDER) == DFSDM_SincOrder_Sinc3) || \ + ((ORDER) == DFSDM_SincOrder_Sinc4) || \ + ((ORDER) == DFSDM_SincOrder_Sinc5)) +/** + * @} + */ + +/** @defgroup DFSDM_Break_Signal_Assignment + * @{ + */ +#define DFSDM_SCDBreak_0 ((uint32_t)0x00001000) /*!< DFSDM Break 0 signal assigned to short circuit detector */ +#define DFSDM_SCDBreak_1 ((uint32_t)0x00002000) /*!< DFSDM Break 1 signal assigned to short circuit detector */ +#define DFSDM_SCDBreak_2 ((uint32_t)0x00004000) /*!< DFSDM Break 2 signal assigned to short circuit detector */ +#define DFSDM_SCDBreak_3 ((uint32_t)0x00008000) /*!< DFSDM Break 3 signal assigned to short circuit detector */ + +#define IS_DFSDM_SCD_BREAK_SIGNAL(RANK) (((RANK) == DFSDM_SCDBreak_0) || \ + ((RANK) == DFSDM_SCDBreak_1) || \ + ((RANK) == DFSDM_SCDBreak_2) || \ + ((RANK) == DFSDM_SCDBreak_3)) +/** + * @} + */ + +/** @defgroup DFSDM_AWD_Sinc_Order + * @{ + */ +#define DFSDM_AWDSincOrder_Fast ((uint32_t)0x00000000) /*!< DFSDM Fast sinc filter */ +#define DFSDM_AWDSincOrder_Sinc1 ((uint32_t)0x00400000) /*!< DFSDM sinc1 filter */ +#define DFSDM_AWDSincOrder_Sinc2 ((uint32_t)0x00800000) /*!< DFSDM sinc2 filter */ +#define DFSDM_AWDSincOrder_Sinc3 ((uint32_t)0x00C00000) /*!< DFSDM sinc3 filter */ + +#define IS_DFSDM_AWD_SINC_ORDER(ORDER) (((ORDER) == DFSDM_AWDSincOrder_Fast) || \ + ((ORDER) == DFSDM_AWDSincOrder_Sinc1) || \ + ((ORDER) == DFSDM_AWDSincOrder_Sinc2) || \ + ((ORDER) == DFSDM_AWDSincOrder_Sinc3)) +/** + * @} + */ + +/** @defgroup DFSDM_AWD_CHANNEL + * @{ + */ +#define DFSDM_AWDChannel0 ((uint32_t)0x00010000) /*!< DFSDM AWDx guard channel 0 */ +#define DFSDM_AWDChannel1 ((uint32_t)0x00020000) /*!< DFSDM AWDx guard channel 1 */ +#define DFSDM_AWDChannel2 ((uint32_t)0x00040000) /*!< DFSDM AWDx guard channel 2 */ +#define DFSDM_AWDChannel3 ((uint32_t)0x00080000) /*!< DFSDM AWDx guard channel 3 */ +#define DFSDM_AWDChannel4 ((uint32_t)0x00100000) /*!< DFSDM AWDx guard channel 4 */ +#define DFSDM_AWDChannel5 ((uint32_t)0x00200000) /*!< DFSDM AWDx guard channel 5 */ +#define DFSDM_AWDChannel6 ((uint32_t)0x00400000) /*!< DFSDM AWDx guard channel 6 */ +#define DFSDM_AWDChannel7 ((uint32_t)0x00800000) /*!< DFSDM AWDx guard channel 7 */ + +#define IS_DFSDM_AWD_CHANNEL(CHANNEL) (((CHANNEL) == DFSDM_AWDChannel0) || \ + ((CHANNEL) == DFSDM_AWDChannel1) || \ + ((CHANNEL) == DFSDM_AWDChannel2) || \ + ((CHANNEL) == DFSDM_AWDChannel3) || \ + ((CHANNEL) == DFSDM_AWDChannel4) || \ + ((CHANNEL) == DFSDM_AWDChannel5) || \ + ((CHANNEL) == DFSDM_AWDChannel6) || \ + ((CHANNEL) == DFSDM_AWDChannel7)) +/** + * @} + */ + +/** @defgroup DFSDM_Threshold_Selection + * @{ + */ +#define DFSDM_Threshold_Low ((uint8_t)0x00) /*!< DFSDM Low threshold */ +#define DFSDM_Threshold_High ((uint8_t)0x08) /*!< DFSDM High threshold */ + +#define IS_DFSDM_Threshold(THR) (((THR) == DFSDM_Threshold_Low) || \ + ((THR) == DFSDM_Threshold_High)) +/** + * @} + */ + +/** @defgroup DFSDM_AWD_Fast_Mode_Selection + * @{ + */ +#define DFSDM_AWDFastMode_Disable ((uint32_t)0x00000000) /*!< DFSDM Fast mode for AWD is disabled */ +#define DFSDM_AWDFastMode_Enable ((uint32_t)0x40000000) /*!< DFSDM Fast mode for AWD is enabled */ + +#define IS_DFSDM_AWD_MODE(MODE) (((MODE) == DFSDM_AWDFastMode_Disable) || \ + ((MODE) == DFSDM_AWDFastMode_Enable)) +/** + * @} + */ + +/** @defgroup DFSDM_Clock_Output_Source_Selection + * @{ + */ +#define DFSDM_ClkOutSource_SysClock ((uint32_t)0x00000000) /*!< DFSDM Source for output clock is comming from system clock */ +#define DFSDM_ClkOutSource_AudioClock DFSDM_CHCFGR1_CKOUTSRC /*!< DFSDM Source for output clock is comming from audio clock */ + +#define IS_DFSDM_CLOCK_OUT_SOURCE(SRC) (((SRC) == DFSDM_ClkOutSource_SysClock) || \ + ((SRC) == DFSDM_ClkOutSource_AudioClock)) +/** + * @} + */ + +/** @defgroup DFSDM_Conversion_Mode + * @{ + */ +#define DFSDM_DMAConversionMode_Regular ((uint32_t)0x00000010) /*!< DFSDM Regular mode */ +#define DFSDM_DMAConversionMode_Injected ((uint32_t)0x00000000) /*!< DFSDM Injected mode */ + +#define IS_DFSDM_CONVERSION_MODE(MODE) ((MODE) == DFSDM_DMAConversionMode_Regular || \ + ((MODE) == DFSDM_DMAConversionMode_Injected)) +/** + * @} + */ + +/** @defgroup DFSDM_Extremes_Channel_Selection + * @{ + */ +#define DFSDM_ExtremChannel0 ((uint32_t)0x00000100) /*!< DFSDM Extreme detector guard channel 0 */ +#define DFSDM_ExtremChannel1 ((uint32_t)0x00000200) /*!< DFSDM Extreme detector guard channel 1 */ +#define DFSDM_ExtremChannel2 ((uint32_t)0x00000400) /*!< DFSDM Extreme detector guard channel 2 */ +#define DFSDM_ExtremChannel3 ((uint32_t)0x00000800) /*!< DFSDM Extreme detector guard channel 3 */ +#define DFSDM_ExtremChannel4 ((uint32_t)0x00001000) /*!< DFSDM Extreme detector guard channel 4 */ +#define DFSDM_ExtremChannel5 ((uint32_t)0x00002000) /*!< DFSDM Extreme detector guard channel 5 */ +#define DFSDM_ExtremChannel6 ((uint32_t)0x00004000) /*!< DFSDM Extreme detector guard channel 6 */ +#define DFSDM_ExtremChannel7 ((uint32_t)0x00008000) /*!< DFSDM Extreme detector guard channel 7 */ + +#define IS_DFSDM_EXTREM_CHANNEL(CHANNEL) (((CHANNEL) == DFSDM_ExtremChannel0) || \ + ((CHANNEL) == DFSDM_ExtremChannel1) || \ + ((CHANNEL) == DFSDM_ExtremChannel2) || \ + ((CHANNEL) == DFSDM_ExtremChannel3) || \ + ((CHANNEL) == DFSDM_ExtremChannel4) || \ + ((CHANNEL) == DFSDM_ExtremChannel5) || \ + ((CHANNEL) == DFSDM_ExtremChannel6) || \ + ((CHANNEL) == DFSDM_ExtremChannel7)) +/** + * @} + */ + +/** @defgroup DFSDM_Injected_Channel_Selection + * @{ + */ +#define DFSDM_InjectedChannel0 ((uint32_t)0x00000001) /*!< DFSDM channel 0 is selected as injected channel */ +#define DFSDM_InjectedChannel1 ((uint32_t)0x00000002) /*!< DFSDM channel 1 is selected as injected channel */ +#define DFSDM_InjectedChannel2 ((uint32_t)0x00000004) /*!< DFSDM channel 2 is selected as injected channel */ +#define DFSDM_InjectedChannel3 ((uint32_t)0x00000008) /*!< DFSDM channel 3 is selected as injected channel */ +#define DFSDM_InjectedChannel4 ((uint32_t)0x00000010) /*!< DFSDM channel 4 is selected as injected channel */ +#define DFSDM_InjectedChannel5 ((uint32_t)0x00000020) /*!< DFSDM channel 5 is selected as injected channel */ +#define DFSDM_InjectedChannel6 ((uint32_t)0x00000040) /*!< DFSDM channel 6 is selected as injected channel */ +#define DFSDM_InjectedChannel7 ((uint32_t)0x00000080) /*!< DFSDM channel 7 is selected as injected channel */ + +#define IS_DFSDM_INJECT_CHANNEL(CHANNEL) (((CHANNEL) == DFSDM_InjectedChannel0) || \ + ((CHANNEL) == DFSDM_InjectedChannel1) || \ + ((CHANNEL) == DFSDM_InjectedChannel2) || \ + ((CHANNEL) == DFSDM_InjectedChannel3) || \ + ((CHANNEL) == DFSDM_InjectedChannel4) || \ + ((CHANNEL) == DFSDM_InjectedChannel5) || \ + ((CHANNEL) == DFSDM_InjectedChannel6) || \ + ((CHANNEL) == DFSDM_InjectedChannel7)) +/** + * @} + */ + +/** @defgroup DFSDM_Regular_Channel_Selection + * @{ + */ +#define DFSDM_RegularChannel0 ((uint32_t)0x00000000) /*!< DFSDM channel 0 is selected as regular channel */ +#define DFSDM_RegularChannel1 ((uint32_t)0x01000000) /*!< DFSDM channel 1 is selected as regular channel */ +#define DFSDM_RegularChannel2 ((uint32_t)0x02000000) /*!< DFSDM channel 2 is selected as regular channel */ +#define DFSDM_RegularChannel3 ((uint32_t)0x03000000) /*!< DFSDM channel 3 is selected as regular channel */ +#define DFSDM_RegularChannel4 ((uint32_t)0x04000000) /*!< DFSDM channel 4 is selected as regular channel */ +#define DFSDM_RegularChannel5 ((uint32_t)0x05000000) /*!< DFSDM channel 5 is selected as regular channel */ +#define DFSDM_RegularChannel6 ((uint32_t)0x06000000) /*!< DFSDM channel 6 is selected as regular channel */ +#define DFSDM_RegularChannel7 ((uint32_t)0x07000000) /*!< DFSDM channel 7 is selected as regular channel */ + +#define IS_DFSDM_REGULAR_CHANNEL(CHANNEL) (((CHANNEL) == DFSDM_RegularChannel0) || \ + ((CHANNEL) == DFSDM_RegularChannel1) || \ + ((CHANNEL) == DFSDM_RegularChannel2) || \ + ((CHANNEL) == DFSDM_RegularChannel3) || \ + ((CHANNEL) == DFSDM_RegularChannel4) || \ + ((CHANNEL) == DFSDM_RegularChannel5) || \ + ((CHANNEL) == DFSDM_RegularChannel6) || \ + ((CHANNEL) == DFSDM_RegularChannel7)) +/** + * @} + */ + +/** @defgroup DFSDM_Injected_Trigger_signal + * @{ + */ +#define DFSDM_Trigger_TIM1_TRGO ((uint32_t)0x00000000) /*!< DFSDM Internal trigger 0 */ +#define DFSDM_Trigger_TIM1_TRGO2 ((uint32_t)0x00000100) /*!< DFSDM Internal trigger 1 */ +#define DFSDM_Trigger_TIM8_TRGO ((uint32_t)0x00000200) /*!< DFSDM Internal trigger 2 */ +#define DFSDM_Trigger_TIM8_TRGO2 ((uint32_t)0x00000300) /*!< DFSDM Internal trigger 3 */ +#define DFSDM_Trigger_TIM3_TRGO ((uint32_t)0x00000300) /*!< DFSDM Internal trigger 4 */ +#define DFSDM_Trigger_TIM4_TRGO ((uint32_t)0x00000400) /*!< DFSDM Internal trigger 5 */ +#define DFSDM_Trigger_TIM16_OC1 ((uint32_t)0x00000400) /*!< DFSDM Internal trigger 6 */ +#define DFSDM_Trigger_TIM6_TRGO ((uint32_t)0x00000500) /*!< DFSDM Internal trigger 7 */ +#define DFSDM_Trigger_TIM7_TRGO ((uint32_t)0x00000500) /*!< DFSDM Internal trigger 8 */ +#define DFSDM_Trigger_EXTI11 ((uint32_t)0x00000600) /*!< DFSDM External trigger 0 */ +#define DFSDM_Trigger_EXTI15 ((uint32_t)0x00000700) /*!< DFSDM External trigger 1 */ + +#define IS_DFSDM0_INJ_TRIGGER(TRIG) (((TRIG) == DFSDM_Trigger_TIM1_TRGO) || \ + ((TRIG) == DFSDM_Trigger_TIM1_TRGO2) || \ + ((TRIG) == DFSDM_Trigger_TIM8_TRGO) || \ + ((TRIG) == DFSDM_Trigger_TIM8_TRGO2) || \ + ((TRIG) == DFSDM_Trigger_TIM4_TRGO) || \ + ((TRIG) == DFSDM_Trigger_TIM6_TRGO) || \ + ((TRIG) == DFSDM_Trigger_TIM1_TRGO) || \ + ((TRIG) == DFSDM_Trigger_EXTI15)) + +#define IS_DFSDM1_INJ_TRIGGER(TRIG) IS_DFSDM0_INJ_TRIGGER(TRIG) +/** + * @} + */ + +/** @defgroup DFSDM_Trigger_Edge_selection + * @{ + */ +#define DFSDM_TriggerEdge_Disabled ((uint32_t)0x00000000) /*!< DFSDM Trigger detection disabled */ +#define DFSDM_TriggerEdge_Rising ((uint32_t)0x00002000) /*!< DFSDM Each rising edge makes a request to launch an injected conversion */ +#define DFSDM_TriggerEdge_Falling ((uint32_t)0x00004000) /*!< DFSDM Each falling edge makes a request to launch an injected conversion */ +#define DFSDM_TriggerEdge_BothEdges ((uint32_t)0x00006000) /*!< DFSDM Both edges make a request to launch an injected conversion */ + +#define IS_DFSDM_TRIGGER_EDGE(EDGE) (((EDGE) == DFSDM_TriggerEdge_Disabled) || \ + ((EDGE) == DFSDM_TriggerEdge_Rising) || \ + ((EDGE) == DFSDM_TriggerEdge_Falling) || \ + ((EDGE) == DFSDM_TriggerEdge_BothEdges)) +/** + * @} + */ + +/** @defgroup DFSDM_Injected_Conversion_Mode_Selection + * @{ + */ +#define DFSDM_InjectConvMode_Single ((uint32_t)0x00000000) /*!< DFSDM Trigger detection disabled */ +#define DFSDM_InjectConvMode_Scan ((uint32_t)0x00000010) /*!< DFSDM Each rising edge makes a request to launch an injected conversion */ + +#define IS_DFSDM_INJ_CONV_MODE(MODE) (((MODE) == DFSDM_InjectConvMode_Single) || \ + ((MODE) == DFSDM_InjectConvMode_Scan)) +/** + * @} + */ + +/** @defgroup DFSDM_Interrupts_Definition + * @{ + */ +#define DFSDM_IT_JEOC DFSDM_FLTCR2_JEOCIE +#define DFSDM_IT_REOC DFSDM_FLTCR2_REOCIE +#define DFSDM_IT_JOVR DFSDM_FLTCR2_JOVRIE +#define DFSDM_IT_ROVR DFSDM_FLTCR2_ROVRIE +#define DFSDM_IT_AWD DFSDM_FLTCR2_AWDIE +#define DFSDM_IT_SCD DFSDM_FLTCR2_SCDIE +#define DFSDM_IT_CKAB DFSDM_FLTCR2_CKABIE + +#define IS_DFSDM_IT(IT) (((IT) == DFSDM_IT_JEOC) || \ + ((IT) == DFSDM_IT_REOC) || \ + ((IT) == DFSDM_IT_JOVR) || \ + ((IT) == DFSDM_IT_ROVR) || \ + ((IT) == DFSDM_IT_AWD) || \ + ((IT) == DFSDM_IT_SCD) || \ + ((IT) == DFSDM_IT_CKAB)) +/** + * @} + */ + +/** @defgroup DFSDM_Flag_Definition + * @{ + */ +#define DFSDM_FLAG_JEOC DFSDM_FLTISR_JEOCF +#define DFSDM_FLAG_REOC DFSDM_FLTISR_REOCF +#define DFSDM_FLAG_JOVR DFSDM_FLTISR_JOVRF +#define DFSDM_FLAG_ROVR DFSDM_FLTISR_ROVRF +#define DFSDM_FLAG_AWD DFSDM_FLTISR_AWDF +#define DFSDM_FLAG_JCIP DFSDM_FLTISR_JCIP +#define DFSDM_FLAG_RCIP DFSDM_FLTISR_RCIP + +#define IS_DFSDM_FLAG(FLAG) (((FLAG) == DFSDM_FLAG_JEOC) || \ + ((FLAG) == DFSDM_FLAG_REOC) || \ + ((FLAG) == DFSDM_FLAG_JOVR) || \ + ((FLAG) == DFSDM_FLAG_ROVR) || \ + ((FLAG) == DFSDM_FLAG_AWD) || \ + ((FLAG) == DFSDM_FLAG_JCIP) || \ + ((FLAG) == DFSDM_FLAG_RCIP)) +/** + * @} + */ + +/** @defgroup DFSDM_Clock_Absence_Flag_Definition + * @{ + */ +#define DFSDM_FLAG_CLKAbsence_Channel0 ((uint32_t)0x00010000) +#define DFSDM_FLAG_CLKAbsence_Channel1 ((uint32_t)0x00020000) +#define DFSDM_FLAG_CLKAbsence_Channel2 ((uint32_t)0x00040000) +#define DFSDM_FLAG_CLKAbsence_Channel3 ((uint32_t)0x00080000) +#define DFSDM_FLAG_CLKAbsence_Channel4 ((uint32_t)0x00100000) +#define DFSDM_FLAG_CLKAbsence_Channel5 ((uint32_t)0x00200000) +#define DFSDM_FLAG_CLKAbsence_Channel6 ((uint32_t)0x00400000) +#define DFSDM_FLAG_CLKAbsence_Channel7 ((uint32_t)0x00800000) + +#define IS_DFSDM_CLK_ABS_FLAG(FLAG) (((FLAG) == DFSDM_FLAG_CLKAbsence_Channel0) || \ + ((FLAG) == DFSDM_FLAG_CLKAbsence_Channel1) || \ + ((FLAG) == DFSDM_FLAG_CLKAbsence_Channel2) || \ + ((FLAG) == DFSDM_FLAG_CLKAbsence_Channel3) || \ + ((FLAG) == DFSDM_FLAG_CLKAbsence_Channel4) || \ + ((FLAG) == DFSDM_FLAG_CLKAbsence_Channel5) || \ + ((FLAG) == DFSDM_FLAG_CLKAbsence_Channel6) || \ + ((FLAG) == DFSDM_FLAG_CLKAbsence_Channel7)) +/** + * @} + */ + +/** @defgroup DFSDM_SCD_Flag_Definition + * @{ + */ +#define DFSDM_FLAG_SCD_Channel0 ((uint32_t)0x01000000) +#define DFSDM_FLAG_SCD_Channel1 ((uint32_t)0x02000000) +#define DFSDM_FLAG_SCD_Channel2 ((uint32_t)0x04000000) +#define DFSDM_FLAG_SCD_Channel3 ((uint32_t)0x08000000) +#define DFSDM_FLAG_SCD_Channel4 ((uint32_t)0x10000000) +#define DFSDM_FLAG_SCD_Channel5 ((uint32_t)0x20000000) +#define DFSDM_FLAG_SCD_Channel6 ((uint32_t)0x40000000) +#define DFSDM_FLAG_SCD_Channel7 ((uint32_t)0x80000000) + +#define IS_DFSDM_SCD_FLAG(FLAG) (((FLAG) == DFSDM_FLAG_SCD_Channel0) || \ + ((FLAG) == DFSDM_FLAG_SCD_Channel1) || \ + ((FLAG) == DFSDM_FLAG_SCD_Channel2) || \ + ((FLAG) == DFSDM_FLAG_SCD_Channel3) || \ + ((FLAG) == DFSDM_FLAG_SCD_Channel4) || \ + ((FLAG) == DFSDM_FLAG_SCD_Channel5) || \ + ((FLAG) == DFSDM_FLAG_SCD_Channel6) || \ + ((FLAG) == DFSDM_FLAG_SCD_Channel7)) +/** + * @} + */ + +/** @defgroup DFSDM_Clear_Flag_Definition + * @{ + */ +#define DFSDM_CLEARF_JOVR DFSDM_FLTICR_CLRJOVRF +#define DFSDM_CLEARF_ROVR DFSDM_FLTICR_CLRROVRF + +#define IS_DFSDM_CLEAR_FLAG(FLAG) (((FLAG) == DFSDM_CLEARF_JOVR) || \ + ((FLAG) == DFSDM_CLEARF_ROVR)) +/** + * @} + */ + +/** @defgroup DFSDM_Clear_ClockAbs_Flag_Definition + * @{ + */ +#define DFSDM_CLEARF_CLKAbsence_Channel0 ((uint32_t)0x00010000) +#define DFSDM_CLEARF_CLKAbsence_Channel1 ((uint32_t)0x00020000) +#define DFSDM_CLEARF_CLKAbsence_Channel2 ((uint32_t)0x00040000) +#define DFSDM_CLEARF_CLKAbsence_Channel3 ((uint32_t)0x00080000) +#define DFSDM_CLEARF_CLKAbsence_Channel4 ((uint32_t)0x00100000) +#define DFSDM_CLEARF_CLKAbsence_Channel5 ((uint32_t)0x00200000) +#define DFSDM_CLEARF_CLKAbsence_Channel6 ((uint32_t)0x00400000) +#define DFSDM_CLEARF_CLKAbsence_Channel7 ((uint32_t)0x00800000) + +#define IS_DFSDM_CLK_ABS_CLEARF(FLAG) (((FLAG) == DFSDM_CLEARF_CLKAbsence_Channel0) || \ + ((FLAG) == DFSDM_CLEARF_CLKAbsence_Channel1) || \ + ((FLAG) == DFSDM_CLEARF_CLKAbsence_Channel2) || \ + ((FLAG) == DFSDM_CLEARF_CLKAbsence_Channel3) || \ + ((FLAG) == DFSDM_CLEARF_CLKAbsence_Channel4) || \ + ((FLAG) == DFSDM_CLEARF_CLKAbsence_Channel5) || \ + ((FLAG) == DFSDM_CLEARF_CLKAbsence_Channel6) || \ + ((FLAG) == DFSDM_CLEARF_CLKAbsence_Channel7)) +/** + * @} + */ + +/** @defgroup DFSDM_Clear_Short_Circuit_Flag_Definition + * @{ + */ +#define DFSDM_CLEARF_SCD_Channel0 ((uint32_t)0x01000000) +#define DFSDM_CLEARF_SCD_Channel1 ((uint32_t)0x02000000) +#define DFSDM_CLEARF_SCD_Channel2 ((uint32_t)0x04000000) +#define DFSDM_CLEARF_SCD_Channel3 ((uint32_t)0x08000000) +#define DFSDM_CLEARF_SCD_Channel4 ((uint32_t)0x10000000) +#define DFSDM_CLEARF_SCD_Channel5 ((uint32_t)0x20000000) +#define DFSDM_CLEARF_SCD_Channel6 ((uint32_t)0x40000000) +#define DFSDM_CLEARF_SCD_Channel7 ((uint32_t)0x80000000) + +#define IS_DFSDM_SCD_CHANNEL_FLAG(FLAG) (((FLAG) == DFSDM_CLEARF_SCD_Channel0) || \ + ((FLAG) == DFSDM_CLEARF_SCD_Channel1) || \ + ((FLAG) == DFSDM_CLEARF_SCD_Channel2) || \ + ((FLAG) == DFSDM_CLEARF_SCD_Channel3) || \ + ((FLAG) == DFSDM_CLEARF_SCD_Channel4) || \ + ((FLAG) == DFSDM_CLEARF_SCD_Channel5) || \ + ((FLAG) == DFSDM_CLEARF_SCD_Channel6) || \ + ((FLAG) == DFSDM_CLEARF_SCD_Channel7)) +/** + * @} + */ + +/** @defgroup DFSDM_Clock_Absence_Interrupt_Definition + * @{ + */ +#define DFSDM_IT_CLKAbsence_Channel0 ((uint32_t)0x00010000) +#define DFSDM_IT_CLKAbsence_Channel1 ((uint32_t)0x00020000) +#define DFSDM_IT_CLKAbsence_Channel2 ((uint32_t)0x00040000) +#define DFSDM_IT_CLKAbsence_Channel3 ((uint32_t)0x00080000) +#define DFSDM_IT_CLKAbsence_Channel4 ((uint32_t)0x00100000) +#define DFSDM_IT_CLKAbsence_Channel5 ((uint32_t)0x00200000) +#define DFSDM_IT_CLKAbsence_Channel6 ((uint32_t)0x00400000) +#define DFSDM_IT_CLKAbsence_Channel7 ((uint32_t)0x00800000) + +#define IS_DFSDM_CLK_ABS_IT(IT) (((IT) == DFSDM_IT_CLKAbsence_Channel0) || \ + ((IT) == DFSDM_IT_CLKAbsence_Channel1) || \ + ((IT) == DFSDM_IT_CLKAbsence_Channel2) || \ + ((IT) == DFSDM_IT_CLKAbsence_Channel3) || \ + ((IT) == DFSDM_IT_CLKAbsence_Channel4) || \ + ((IT) == DFSDM_IT_CLKAbsence_Channel5) || \ + ((IT) == DFSDM_IT_CLKAbsence_Channel6) || \ + ((IT) == DFSDM_IT_CLKAbsence_Channel7)) +/** + * @} + */ + +/** @defgroup DFSDM_SCD_Interrupt_Definition + * @{ + */ +#define DFSDM_IT_SCD_Channel0 ((uint32_t)0x01000000) +#define DFSDM_IT_SCD_Channel1 ((uint32_t)0x02000000) +#define DFSDM_IT_SCD_Channel2 ((uint32_t)0x04000000) +#define DFSDM_IT_SCD_Channel3 ((uint32_t)0x08000000) +#define DFSDM_IT_SCD_Channel4 ((uint32_t)0x10000000) +#define DFSDM_IT_SCD_Channel5 ((uint32_t)0x20000000) +#define DFSDM_IT_SCD_Channel6 ((uint32_t)0x40000000) +#define DFSDM_IT_SCD_Channel7 ((uint32_t)0x80000000) + +#define IS_DFSDM_SCD_IT(IT) (((IT) == DFSDM_IT_SCD_Channel0) || \ + ((IT) == DFSDM_IT_SCD_Channel1) || \ + ((IT) == DFSDM_IT_SCD_Channel2) || \ + ((IT) == DFSDM_IT_SCD_Channel3) || \ + ((IT) == DFSDM_IT_SCD_Channel4) || \ + ((IT) == DFSDM_IT_SCD_Channel5) || \ + ((IT) == DFSDM_IT_SCD_Channel6) || \ + ((IT) == DFSDM_IT_SCD_Channel7)) +/** + * @} + */ + +#define IS_DFSDM_DATA_RIGHT_BIT_SHIFT(SHIFT) (SHIFT < 0x20 ) + +#define IS_DFSDM_OFFSET(OFFSET) (OFFSET < 0x01000000 ) + +#define IS_DFSDM_ALL_CHANNEL(CHANNEL) (((CHANNEL) == DFSDM1_Channel0) || \ + ((CHANNEL) == DFSDM1_Channel1) || \ + ((CHANNEL) == DFSDM1_Channel2) || \ + ((CHANNEL) == DFSDM1_Channel3)) + +#define IS_DFSDM_ALL_FILTER(FILTER) (((FILTER) == DFSDM0) || \ + ((FILTER) == DFSDM1)) + +#define IS_DFSDM_SYNC_FILTER(FILTER) (((FILTER) == DFSDM1)) + +#define IS_DFSDM_SINC_OVRSMPL_RATIO(RATIO) ( RATIO < 0x401 ) & ( RATIO >= 0x001 ) + +#define IS_DFSDM_INTG_OVRSMPL_RATIO(RATIO) ( RATIO < 0x101 ) & ( RATIO >= 0x001 ) + +#define IS_DFSDM_CLOCK_OUT_DIVIDER(DIVIDER) ( DIVIDER < 0x101 ) + +#define IS_DFSDM_CSD_THRESHOLD_VALUE(VALUE) ( VALUE < 256 ) + +#define IS_DFSDM_AWD_OVRSMPL_RATIO(RATIO) ( RATIO < 33 ) & ( RATIO >= 0x001 ) + +#define IS_DFSDM_HIGH_THRESHOLD(VALUE) (VALUE < 0x1000000 ) +#define IS_DFSDM_LOW_THRESHOLD(VALUE) (VALUE < 0x1000000 ) +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ + +/* Initialization functions ***************************************************/ +void DFSDM_DeInit(void); +void DFSDM_TransceiverInit(DFSDM_Channel_TypeDef* DFSDM_Channelx, DFSDM_TransceiverInitTypeDef* DFSDM_TransceiverInitStruct); +void DFSDM_TransceiverStructInit(DFSDM_TransceiverInitTypeDef* DFSDM_TransceiverInitStruct); +void DFSDM_FilterInit(DFSDM_TypeDef* DFSDMx, DFSDM_FilterInitTypeDef* DFSDM_FilterInitStruct); +void DFSDM_FilterStructInit(DFSDM_FilterInitTypeDef* DFSDM_FilterInitStruct); + +/* Configuration functions ****************************************************/ +void DFSDM_Cmd(FunctionalState NewState); +void DFSDM_ChannelCmd(DFSDM_Channel_TypeDef* DFSDM_Channelx, FunctionalState NewState); +void DFSDM_FilterCmd(DFSDM_TypeDef* DFSDMx, FunctionalState NewState); +void DFSDM_ConfigClkOutputDivider(uint32_t DFSDM_ClkOutDivision); +void DFSDM_ConfigClkOutputSource(uint32_t DFSDM_ClkOutSource); +void DFSDM_SelectInjectedConversionMode(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_InjectConvMode); +void DFSDM_SelectInjectedChannel(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_InjectedChannelx); +void DFSDM_SelectRegularChannel(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_RegularChannelx); +void DFSDM_StartSoftwareInjectedConversion(DFSDM_TypeDef* DFSDMx); +void DFSDM_StartSoftwareRegularConversion(DFSDM_TypeDef* DFSDMx); +void DFSDM_SynchronousFilter0InjectedStart(DFSDM_TypeDef* DFSDMx); +void DFSDM_SynchronousFilter0RegularStart(DFSDM_TypeDef* DFSDMx); +void DFSDM_RegularContinuousModeCmd(DFSDM_TypeDef* DFSDMx, FunctionalState NewState); +void DFSDM_InjectedContinuousModeCmd(DFSDM_TypeDef* DFSDMx, FunctionalState NewState); +void DFSDM_FastModeCmd(DFSDM_TypeDef* DFSDMx, FunctionalState NewState); +void DFSDM_ConfigInjectedTrigger(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_Trigger, uint32_t DFSDM_TriggerEdge); +void DFSDM_ConfigBRKShortCircuitDetector(DFSDM_Channel_TypeDef* DFSDM_Channelx, uint32_t DFSDM_SCDBreak_i, FunctionalState NewState); +void DFSDM_ConfigBRKAnalogWatchDog(DFSDM_Channel_TypeDef* DFSDM_Channelx, uint32_t DFSDM_SCDBreak_i, FunctionalState NewState); +void DFSDM_ConfigShortCircuitThreshold(DFSDM_Channel_TypeDef* DFSDM_Channelx, uint32_t DFSDM_SCDThreshold); +void DFSDM_ConfigAnalogWatchdog(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_AWDChannelx, uint32_t DFSDM_AWDFastMode); +void DFSDM_ConfigAWDFilter(DFSDM_Channel_TypeDef* DFSDM_Channelx, uint32_t AWD_SincOrder, uint32_t AWD_SincOverSampleRatio); +uint32_t DFSDM_GetAWDConversionValue(DFSDM_Channel_TypeDef* DFSDM_Channelx); +void DFSDM_SetAWDThreshold(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_HighThreshold, uint32_t DFSDM_LowThreshold); +void DFSDM_SelectExtremesDetectorChannel(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_ExtremChannelx); +int32_t DFSDM_GetRegularConversionData(DFSDM_TypeDef* DFSDMx); +int32_t DFSDM_GetInjectedConversionData(DFSDM_TypeDef* DFSDMx); +int32_t DFSDM_GetMaxValue(DFSDM_TypeDef* DFSDMx); +int32_t DFSDM_GetMinValue(DFSDM_TypeDef* DFSDMx); +int32_t DFSDM_GetMaxValueChannel(DFSDM_TypeDef* DFSDMx); +int32_t DFSDM_GetMinValueChannel(DFSDM_TypeDef* DFSDMx); +uint32_t DFSDM_GetConversionTime(DFSDM_TypeDef* DFSDMx); +void DFSDM_DMATransferConfig(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_DMAConversionMode, FunctionalState NewState); +/* Interrupts and flags management functions **********************************/ +void DFSDM_ITConfig(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_IT, FunctionalState NewState); +void DFSDM_ITClockAbsenceCmd(FunctionalState NewState); +void DFSDM_ITShortCircuitDetectorCmd(FunctionalState NewState); + +FlagStatus DFSDM_GetFlagStatus(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_FLAG); +FlagStatus DFSDM_GetClockAbsenceFlagStatus(uint32_t DFSDM_FLAG_CLKAbsence); +FlagStatus DFSDM_GetShortCircuitFlagStatus(uint32_t DFSDM_FLAG_SCD); +FlagStatus DFSDM_GetWatchdogFlagStatus(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_AWDChannelx, uint8_t DFSDM_Threshold); + +void DFSDM_ClearFlag(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_CLEARF); +void DFSDM_ClearClockAbsenceFlag(uint32_t DFSDM_CLEARF_CLKAbsence); +void DFSDM_ClearShortCircuitFlag(uint32_t DFSDM_CLEARF_SCD); +void DFSDM_ClearAnalogWatchdogFlag(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_AWDChannelx, uint8_t DFSDM_Threshold); + +ITStatus DFSDM_GetITStatus(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_IT); +ITStatus DFSDM_GetClockAbsenceITStatus(uint32_t DFSDM_IT_CLKAbsence); +ITStatus DFSDM_GetGetShortCircuitITStatus(uint32_t DFSDM_IT_SCR); + +#endif /* STM32F412xG */ + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F4XX_DFSDM_H */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dma.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dma.h index ad35ac97c5..9ecc5a9b97 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dma.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dma.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_dma.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the DMA firmware * library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dma2d.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dma2d.h index 83c72fecf5..519389dc37 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dma2d.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dma2d.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_dma2d.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the DMA2D firmware * library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dsi.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dsi.h index 0166d57f5c..5755b32d2c 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dsi.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dsi.h @@ -2,13 +2,13 @@ ****************************************************************************** * @file stm32f4xx_dsi.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief Header file of DSI module. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -164,10 +164,10 @@ typedef struct uint32_t ColorCoding; /*!< Color coding for LTDC interface This parameter can be any value of @ref DSI_Color_Coding */ - + uint32_t CommandSize; /*!< Maximum allowed size for an LTDC write memory command, measured in pixels. This parameter can be any value between 0x00 and 0xFFFF */ - + uint32_t TearingEffectSource; /*!< Tearing effect source This parameter can be any value of @ref DSI_TearingEffectSource */ diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_exti.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_exti.h index 8dedd1246b..17a5cc1fde 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_exti.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_exti.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_exti.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the EXTI firmware * library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_flash.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_flash.h index 17f7533a50..856280e53a 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_flash.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_flash.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_flash.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the FLASH * firmware library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -171,10 +171,10 @@ typedef enum (((ADDRESS) >= 0x1FFF7800) && ((ADDRESS) <= 0x1FFF7A0F))) #endif /* STM32F427_437xx || STM32F429_439xx || STM32F469_479xx */ -#if defined (STM32F40_41xxx) +#if defined (STM32F40_41xxx) || defined(STM32F412xG) #define IS_FLASH_ADDRESS(ADDRESS) ((((ADDRESS) >= 0x08000000) && ((ADDRESS) <= 0x080FFFFF)) ||\ (((ADDRESS) >= 0x1FFF7800) && ((ADDRESS) <= 0x1FFF7A0F))) -#endif /* STM32F40_41xxx */ +#endif /* STM32F40_41xxx || STM32F412xG */ #if defined (STM32F401xx) #define IS_FLASH_ADDRESS(ADDRESS) ((((ADDRESS) >= 0x08000000) && ((ADDRESS) <= 0x0803FFFF)) ||\ diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_flash_ramfunc.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_flash_ramfunc.h index 2a9500218c..5671e35816 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_flash_ramfunc.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_flash_ramfunc.h @@ -2,13 +2,13 @@ ****************************************************************************** * @file stm32f4xx_flash_ramfunc.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief Header file of FLASH RAMFUNC driver. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_fmc.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_fmc.h index 66ff375de7..a99c194f5f 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_fmc.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_fmc.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_fmc.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the FMC firmware * library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_fmpi2c.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_fmpi2c.h index b3d87e81b8..6dd9662f4f 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_fmpi2c.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_fmpi2c.h @@ -1,15 +1,15 @@ /** ****************************************************************************** - * @file stm32f30x_fmpi2c.h + * @file stm32f4xx_fmpi2c.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the I2C Fast Mode * Plus firmware library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -44,7 +44,7 @@ /** @addtogroup FMPI2C * @{ */ -#if defined(STM32F410xx) || defined(STM32F446xx) +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) /* Exported types ------------------------------------------------------------*/ /** @@ -350,7 +350,6 @@ typedef struct ((IT) == FMPI2C_IT_ARLO) || ((IT) == FMPI2C_IT_OVR) || \ ((IT) == FMPI2C_IT_PECERR) || ((IT) == FMPI2C_IT_TIMEOUT) || \ ((IT) == FMPI2C_IT_ALERT)) - /** * @} @@ -410,7 +409,6 @@ void FMPI2C_Cmd(FMPI2C_TypeDef* FMPI2Cx, FunctionalState NewState); void FMPI2C_SoftwareResetCmd(FMPI2C_TypeDef* FMPI2Cx); void FMPI2C_ITConfig(FMPI2C_TypeDef* FMPI2Cx, uint32_t FMPI2C_IT, FunctionalState NewState); void FMPI2C_StretchClockCmd(FMPI2C_TypeDef* FMPI2Cx, FunctionalState NewState); -void FMPI2C_StopModeCmd(FMPI2C_TypeDef* FMPI2Cx, FunctionalState NewState); void FMPI2C_DualAddressCmd(FMPI2C_TypeDef* FMPI2Cx, FunctionalState NewState); void FMPI2C_OwnAddress2Config(FMPI2C_TypeDef* FMPI2Cx, uint16_t Address, uint8_t Mask); void FMPI2C_GeneralCallCmd(FMPI2C_TypeDef* FMPI2Cx, FunctionalState NewState); @@ -458,7 +456,7 @@ void FMPI2C_ClearFlag(FMPI2C_TypeDef* FMPI2Cx, uint32_t FMPI2C_FLAG); ITStatus FMPI2C_GetITStatus(FMPI2C_TypeDef* FMPI2Cx, uint32_t FMPI2C_IT); void FMPI2C_ClearITPendingBit(FMPI2C_TypeDef* FMPI2Cx, uint32_t FMPI2C_IT); -#endif /* STM32F410xx || STM32F446xx */ +#endif /* STM32F410xx || STM32F412xG || STM32F446xx */ /** * @} */ diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_fsmc.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_fsmc.h index 7ddc364241..ecd80c5754 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_fsmc.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_fsmc.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_fsmc.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the FSMC firmware * library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_gpio.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_gpio.h index 83671eee8f..57e1cea0b8 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_gpio.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_gpio.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_gpio.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the GPIO firmware * library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -286,7 +286,7 @@ typedef struct #if defined(STM32F446xx) #define GPIO_AF4_CEC ((uint8_t)0x04) /* CEC Alternate Function mapping */ #endif /* STM32F446xx */ -#if defined(STM32F410xx) || defined(STM32F446xx) +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) #define GPIO_AF_FMPI2C ((uint8_t)0x04) /* FMPI2C Alternate Function mapping */ #endif /* STM32F410xx || STM32F446xx */ @@ -309,6 +309,10 @@ typedef struct #define GPIO_AF6_SPI4 ((uint8_t)0x06) /* SPI4 Alternate Function mapping (Only for STM32F411xE Devices) */ #define GPIO_AF6_SPI5 ((uint8_t)0x06) /* SPI5 Alternate Function mapping (Only for STM32F410xx/STM32F411xE Devices) */ #define GPIO_AF_SAI1 ((uint8_t)0x06) /* SAI1 Alternate Function mapping */ +#define GPIO_AF_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping (only for STM32F412xG Devices) */ +#if defined(STM32F412xG) +#define GPIO_AF6_DFSDM1 ((uint8_t)0x06) /* DFSDM Alternate Function mapping */ +#endif /* STM32F412xG */ /** * @brief AF 7 selection @@ -331,6 +335,11 @@ typedef struct #define GPIO_AF_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ #define GPIO_AF_UART7 ((uint8_t)0x08) /* UART7 Alternate Function mapping */ #define GPIO_AF_UART8 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ +#if defined(STM32F412xG) +#define GPIO_AF8_USART3 ((uint8_t)0x08) /* USART3 Alternate Function mapping */ +#define GPIO_AF8_DFSDM1 ((uint8_t)0x08) /* DFSDM Alternate Function mapping */ +#define GPIO_AF8_CAN1 ((uint8_t)0x08) /* CAN1 Alternate Function mapping */ +#endif /* STM32F412xG */ #if defined(STM32F446xx) #define GPIO_AF8_SAI2 ((uint8_t)0x08) /* SAI2 Alternate Function mapping */ #define GPIO_AF_SPDIF ((uint8_t)0x08) /* SPDIF Alternate Function mapping */ @@ -344,18 +353,18 @@ typedef struct #define GPIO_AF_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ #define GPIO_AF_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ #define GPIO_AF_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping (Only for STM32F401xx/STM32F410xx/STM32F411xE Devices) */ -#define GPIO_AF9_I2C3 ((uint8_t)0x09) /* I2C3 Alternate Function mapping (Only for STM32F401xx/STM32F411xE Devices) */ +#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping (Only for STM32F401xx/STM32F410xx/STM32F411xE/STM32F412xG Devices) */ +#define GPIO_AF9_I2C3 ((uint8_t)0x09) /* I2C3 Alternate Function mapping (Only for STM32F401xx/STM32F411xE/STM32F412xG Devices) */ #if defined(STM32F446xx) #define GPIO_AF9_SAI2 ((uint8_t)0x09) /* SAI2 Alternate Function mapping */ #endif /* STM32F446xx */ #define GPIO_AF9_LTDC ((uint8_t)0x09) /* LTDC Alternate Function mapping */ -#if defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx) #define GPIO_AF9_QUADSPI ((uint8_t)0x09) /* QuadSPI Alternate Function mapping */ -#endif /* STM32F446xx || STM32F469_479xx */ -#if defined(STM32F410xx) +#endif /* STM32F412xG || STM32F446xx || STM32F469_479xx */ +#if defined(STM32F410xx) || defined(STM32F412xG) #define GPIO_AF9_FMPI2C ((uint8_t)0x09) /* FMPI2C Alternate Function mapping (Only for STM32F410xx Devices) */ -#endif /* STM32F410xx */ +#endif /* STM32F410xx || STM32F412xG */ /** * @brief AF 10 selection @@ -365,9 +374,13 @@ typedef struct #if defined(STM32F446xx) #define GPIO_AF10_SAI2 ((uint8_t)0x0A) /* SAI2 Alternate Function mapping */ #endif /* STM32F446xx */ -#if defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx) #define GPIO_AF10_QUADSPI ((uint8_t)0x0A) /* QuadSPI Alternate Function mapping */ -#endif /* STM32F446xx || STM32F469_479xx */ +#endif /* STM32F412xG || STM32F446xx || STM32F469_479xx */ +#if defined(STM32F412xG) +#define GPIO_AF10_FMC ((uint8_t)0xA) /* FMC Alternate Function mapping */ +#define GPIO_AF10_DFSDM ((uint8_t)0xA) /* DFSDM Alternate Function mapping */ +#endif /* STM32F412xG */ /** * @brief AF 11 selection */ @@ -376,9 +389,9 @@ typedef struct /** * @brief AF 12 selection */ -#if defined(STM32F40_41xxx) +#if defined(STM32F40_41xxx) || defined(STM32F412xG) #define GPIO_AF_FSMC ((uint8_t)0xC) /* FSMC Alternate Function mapping */ -#endif /* STM32F40_41xxx */ +#endif /* STM32F40_41xxx || STM32F412xG */ #if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx) #define GPIO_AF_FMC ((uint8_t)0xC) /* FMC Alternate Function mapping */ @@ -475,6 +488,10 @@ typedef struct ((AF) == GPIO_AF_LTDC)) #endif /* STM32F427_437xx || STM32F429_439xx */ +#if defined(STM32F412xG) +#define IS_GPIO_AF(AF) (((AF) < 16) && ((AF) != 11) && ((AF) != 14)) +#endif /* STM32F412xG */ + #if defined(STM32F446xx) #define IS_GPIO_AF(AF) (((AF) < 16) && ((AF) != 11) && ((AF) != 14)) #endif /* STM32F446xx */ diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_hash.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_hash.h index 9e465f94be..8970959dda 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_hash.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_hash.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_hash.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the HASH * firmware library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_i2c.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_i2c.h index 9492bc9117..dce42043cb 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_i2c.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_i2c.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_i2c.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the I2C firmware * library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_iwdg.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_iwdg.h index 7da7d3aa3a..2c521ab770 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_iwdg.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_iwdg.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_iwdg.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the IWDG * firmware library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_lptim.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_lptim.h index 7bc3814551..35bbaeae79 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_lptim.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_lptim.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_lptim.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the LPTIM * firmware library ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_ltdc.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_ltdc.h index f0b5cd2b9c..21b1cdb496 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_ltdc.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_ltdc.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_ltdc.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the LTDC firmware * library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -156,13 +156,15 @@ typedef struct /** * @brief LTDC Position structure definition */ - typedef struct { uint32_t LTDC_POSX; /*!< Current X Position */ uint32_t LTDC_POSY; /*!< Current Y Position */ } LTDC_PosTypeDef; +/** + * @brief LTDC RGB structure definition + */ typedef struct { uint32_t LTDC_BlueWidth; /*!< Blue width */ @@ -170,6 +172,9 @@ typedef struct uint32_t LTDC_RedWidth; /*!< Red width */ } LTDC_RGBTypeDef; +/** + * @brief LTDC Color Keying structure definition + */ typedef struct { uint32_t LTDC_ColorKeyBlue; /*!< Configures the color key blue value. @@ -182,6 +187,9 @@ typedef struct This parameter must range from 0x00 to 0xFF. */ } LTDC_ColorKeying_InitTypeDef; +/** + * @brief LTDC CLUT structure definition + */ typedef struct { uint32_t LTDC_CLUTAdress; /*!< Configures the CLUT address. @@ -198,9 +206,8 @@ typedef struct } LTDC_CLUT_InitTypeDef; /* Exported constants --------------------------------------------------------*/ - /** @defgroup LTDC_Exported_Constants - * @} + * @{ */ /** @defgroup LTDC_SYNC @@ -218,11 +225,10 @@ typedef struct #define IS_LTDC_AAH(AAH) ((AAH) <= LTDC_VerticalSYNC) #define IS_LTDC_TOTALW(TOTALW) ((TOTALW) <= LTDC_HorizontalSYNC) #define IS_LTDC_TOTALH(TOTALH) ((TOTALH) <= LTDC_VerticalSYNC) - /** * @} */ - + /** @defgroup LTDC_HSPolarity * @{ */ @@ -230,12 +236,11 @@ typedef struct #define LTDC_HSPolarity_AH LTDC_GCR_HSPOL /*!< Horizontal Synchronization is active high. */ #define IS_LTDC_HSPOL(HSPOL) (((HSPOL) == LTDC_HSPolarity_AL) || \ - ((HSPOL) == LTDC_HSPolarity_AH)) - + ((HSPOL) == LTDC_HSPolarity_AH)) /** * @} */ - + /** @defgroup LTDC_VSPolarity * @{ */ @@ -244,11 +249,10 @@ typedef struct #define IS_LTDC_VSPOL(VSPOL) (((VSPOL) == LTDC_VSPolarity_AL) || \ ((VSPOL) == LTDC_VSPolarity_AH)) - /** * @} */ - + /** @defgroup LTDC_DEPolarity * @{ */ @@ -257,7 +261,6 @@ typedef struct #define IS_LTDC_DEPOL(DEPOL) (((DEPOL) == LTDC_VSPolarity_AL) || \ ((DEPOL) == LTDC_DEPolarity_AH)) - /** * @} */ @@ -270,7 +273,6 @@ typedef struct #define IS_LTDC_PCPOL(PCPOL) (((PCPOL) == LTDC_PCPolarity_IPC) || \ ((PCPOL) == LTDC_PCPolarity_IIPC)) - /** * @} */ @@ -283,71 +285,58 @@ typedef struct #define IS_LTDC_RELOAD(RELOAD) (((RELOAD) == LTDC_IMReload) || \ ((RELOAD) == LTDC_VBReload)) - /** * @} */ - + /** @defgroup LTDC_Back_Color * @{ - */ - + */ #define LTDC_Back_Color ((uint32_t)0x000000FF) #define IS_LTDC_BackBlueValue(BBLUE) ((BBLUE) <= LTDC_Back_Color) #define IS_LTDC_BackGreenValue(BGREEN) ((BGREEN) <= LTDC_Back_Color) #define IS_LTDC_BackRedValue(BRED) ((BRED) <= LTDC_Back_Color) - /** * @} */ - + /** @defgroup LTDC_Position * @{ */ - #define LTDC_POS_CY LTDC_CPSR_CYPOS #define LTDC_POS_CX LTDC_CPSR_CXPOS #define IS_LTDC_GET_POS(POS) (((POS) <= LTDC_POS_CY)) - - /** * @} */ - + /** @defgroup LTDC_LIPosition * @{ */ - #define IS_LTDC_LIPOS(LIPOS) ((LIPOS) <= 0x7FF) - /** * @} */ - + /** @defgroup LTDC_CurrentStatus * @{ */ - #define LTDC_CD_VDES LTDC_CDSR_VDES #define LTDC_CD_HDES LTDC_CDSR_HDES #define LTDC_CD_VSYNC LTDC_CDSR_VSYNCS #define LTDC_CD_HSYNC LTDC_CDSR_HSYNCS - #define IS_LTDC_GET_CD(CD) (((CD) == LTDC_CD_VDES) || ((CD) == LTDC_CD_HDES) || \ ((CD) == LTDC_CD_VSYNC) || ((CD) == LTDC_CD_HSYNC)) - - /** * @} - */ + */ /** @defgroup LTDC_Interrupts * @{ - */ - + */ #define LTDC_IT_LI LTDC_IER_LIE #define LTDC_IT_FU LTDC_IER_FUIE #define LTDC_IT_TERR LTDC_IER_TERRIE @@ -358,24 +347,21 @@ typedef struct /** * @} */ - + /** @defgroup LTDC_Flag * @{ */ - #define LTDC_FLAG_LI LTDC_ISR_LIF #define LTDC_FLAG_FU LTDC_ISR_FUIF #define LTDC_FLAG_TERR LTDC_ISR_TERRIF #define LTDC_FLAG_RR LTDC_ISR_RRIF - #define IS_LTDC_FLAG(FLAG) (((FLAG) == LTDC_FLAG_LI) || ((FLAG) == LTDC_FLAG_FU) || \ ((FLAG) == LTDC_FLAG_TERR) || ((FLAG) == LTDC_FLAG_RR)) - /** * @} */ - + /** @defgroup LTDC_Pixelformat * @{ */ @@ -396,39 +382,32 @@ typedef struct /** * @} */ - + /** @defgroup LTDC_BlendingFactor1 * @{ */ - #define LTDC_BlendingFactor1_CA ((uint32_t)0x00000400) #define LTDC_BlendingFactor1_PAxCA ((uint32_t)0x00000600) #define IS_LTDC_BlendingFactor1(BlendingFactor1) (((BlendingFactor1) == LTDC_BlendingFactor1_CA) || ((BlendingFactor1) == LTDC_BlendingFactor1_PAxCA)) - /** * @} */ - + /** @defgroup LTDC_BlendingFactor2 * @{ */ - #define LTDC_BlendingFactor2_CA ((uint32_t)0x00000005) #define LTDC_BlendingFactor2_PAxCA ((uint32_t)0x00000007) #define IS_LTDC_BlendingFactor2(BlendingFactor2) (((BlendingFactor2) == LTDC_BlendingFactor2_CA) || ((BlendingFactor2) == LTDC_BlendingFactor2_PAxCA)) - - /** * @} */ - - + /** @defgroup LTDC_LAYER_Config * @{ */ - #define LTDC_STOPPosition ((uint32_t)0x0000FFFF) #define LTDC_STARTPosition ((uint32_t)0x00000FFF) @@ -447,26 +426,20 @@ typedef struct #define IS_LTDC_CFBLL(CFBLL) ((CFBLL) <= LTDC_ColorFrameBuffer) #define IS_LTDC_CFBLNBR(CFBLNBR) ((CFBLNBR) <= LTDC_LineNumber) - - - /** * @} */ - + /** @defgroup LTDC_colorkeying_Config * @{ */ - #define LTDC_colorkeyingConfig ((uint32_t)0x000000FF) #define IS_LTDC_CKEYING(CKEYING) ((CKEYING) <= LTDC_colorkeyingConfig) - - /** * @} */ - + /** @defgroup LTDC_CLUT_Config * @{ */ @@ -477,7 +450,6 @@ typedef struct /* Exported macro ------------------------------------------------------------*/ /* Exported functions ------------------------------------------------------- */ - /* Function used to set the LTDC configuration to the default reset state *****/ void LTDC_DeInit(void); diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_pwr.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_pwr.h index 579d18b7ff..323649bd2e 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_pwr.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_pwr.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_pwr.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the PWR firmware * library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -102,27 +102,27 @@ /** * @} */ -#if defined(STM32F410xx) || defined(STM32F446xx) +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) /** @defgroup PWR_Wake_Up_Pin * @{ */ #define PWR_WakeUp_Pin1 ((uint32_t)0x00) #define PWR_WakeUp_Pin2 ((uint32_t)0x01) -#if defined(STM32F410xx) +#if defined(STM32F410xx) || defined(STM32F412xG) #define PWR_WakeUp_Pin3 ((uint32_t)0x02) -#endif /* STM32F410xx */ +#endif /* STM32F410xx || STM32F412xG */ #if defined(STM32F446xx) #define IS_PWR_WAKEUP_PIN(PIN) (((PIN) == PWR_WakeUp_Pin1) || \ ((PIN) == PWR_WakeUp_Pin2)) -#else /* STM32F410xx */ -#define IS_PWR_WAKEUP_PIN(PIN) (((PIN) == PWR_WAKEUP_PIN1) || ((PIN) == PWR_WAKEUP_PIN2) || \ - ((PIN) == PWR_WAKEUP_PIN3)) +#else /* STM32F410xx || STM32F412xG */ +#define IS_PWR_WAKEUP_PIN(PIN) (((PIN) == PWR_WakeUp_Pin1) || ((PIN) == PWR_WakeUp_Pin2) || \ + ((PIN) == PWR_WakeUp_Pin3)) #endif /* STM32F446xx */ /** * @} */ -#endif /* STM32F410xx || STM32F446xx */ +#endif /* STM32F410xx || STM32F412xG || STM32F446xx */ /** @defgroup PWR_STOP_mode_entry * @{ @@ -196,9 +196,9 @@ void PWR_PVDCmd(FunctionalState NewState); #if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F411xE) void PWR_WakeUpPinCmd(FunctionalState NewState); #endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F411xE */ -#if defined(STM32F410xx) || defined(STM32F446xx) +#if defined(STM32F410xx) || defined(STM32F412xG) ||defined(STM32F446xx) void PWR_WakeUpPinCmd(uint32_t PWR_WakeUpPinx, FunctionalState NewState); -#endif /* STM32F410xx || STM32F446xx */ +#endif /* STM32F410xx || STM32F412xG || STM32F446xx */ /* Main and Backup Regulators configuration functions *************************/ void PWR_BackupRegulatorCmd(FunctionalState NewState); void PWR_MainRegulatorModeConfig(uint32_t PWR_Regulator_Voltage); @@ -211,10 +211,10 @@ void PWR_MainRegulatorUnderDriveCmd(FunctionalState NewState); void PWR_LowRegulatorUnderDriveCmd(FunctionalState NewState); #endif /* STM32F427_437xx || STM32F429_439xx || STM32F446xx */ -#if defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE) +#if defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE) || defined(STM32F412xG) void PWR_MainRegulatorLowVoltageCmd(FunctionalState NewState); void PWR_LowRegulatorLowVoltageCmd(FunctionalState NewState); -#endif /* STM32F401xx || STM32F410xx || STM32F411xE */ +#endif /* STM32F401xx || STM32F410xx || STM32F411xE || STM32F412xG */ /* FLASH Power Down configuration functions ***********************************/ void PWR_FlashPowerDownCmd(FunctionalState NewState); diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_qspi.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_qspi.h index 1ec600789c..b4d5284a31 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_qspi.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_qspi.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_qspi.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the QSPI * firmware library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -44,7 +44,7 @@ /** @addtogroup QSPI * @{ */ -#if defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx) /* Exported types ------------------------------------------------------------*/ /** @@ -131,11 +131,10 @@ typedef struct * @{ */ #define QSPI_SShift_NoShift ((uint32_t)0x00000000) -#define QSPI_SShift_HalfCycleShift ((uint32_t)QUADSPI_CR_SSHIFT_0) -#define QSPI_SShift_OneCycleShift ((uint32_t)QUADSPI_CR_SSHIFT_1) -#define QSPI_SShift_OneAndHalfCycleShift ((uint32_t)QUADSPI_CR_SSHIFT) -#define IS_QSPI_SSHIFT(SSHIFT) (((SSHIFT) == QSPI_SShift_NoShift) || ((SSHIFT) == QSPI_SShift_HalfCycleShift) || \ - ((SSHIFT) == QSPI_SShift_OneCycleShift) || ((SSHIFT) == QSPI_SShift_OneAndHalfCycleShift)) +#define QSPI_SShift_HalfCycleShift ((uint32_t)QUADSPI_CR_SSHIFT) +#define IS_QSPI_SSHIFT(SSHIFT) (((SSHIFT) == QSPI_SShift_NoShift) || ((SSHIFT) == QSPI_SShift_HalfCycleShift)) +/* Legacy Defines */ +#define QUADSPI_CR_SSHIFT_0 QUADSPI_CR_SSHIFT /** * @} */ @@ -476,7 +475,7 @@ ITStatus QSPI_GetITStatus(uint32_t QSPI_IT); void QSPI_ClearITPendingBit(uint32_t QSPI_IT); uint32_t QSPI_GetFMode(void); -#endif /* STM32F446xx || STM32F469_479xx */ +#endif /* STM32F412xG || STM32F446xx || STM32F469_479xx */ /** * @} */ diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rcc.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rcc.h index 0e7952d54f..06ddee1470 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rcc.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rcc.h @@ -2,13 +2,13 @@ ****************************************************************************** * @file stm32f4xx_rcc.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 - * @brief This file contains all the functions prototypes for the RCC firmware library. + * @version V1.7.1 + * @date 20-May-2016 + * @brief This file contains all the functions prototypes for the RCC firmware library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -108,17 +108,20 @@ typedef struct #define IS_RCC_PLLN_VALUE(VALUE) ((50 <= (VALUE)) && ((VALUE) <= 432)) #define IS_RCC_PLLP_VALUE(VALUE) (((VALUE) == 2) || ((VALUE) == 4) || ((VALUE) == 6) || ((VALUE) == 8)) #define IS_RCC_PLLQ_VALUE(VALUE) ((4 <= (VALUE)) && ((VALUE) <= 15)) -#if defined(STM32F410xx) || defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx) #define IS_RCC_PLLR_VALUE(VALUE) ((2 <= (VALUE)) && ((VALUE) <= 7)) -#endif /* STM32F410xx || STM32F446xx || STM32F469_479xx */ +#endif /* STM32F410xx || STM32F412xG || STM32F446xx || STM32F469_479xx */ #define IS_RCC_PLLI2SN_VALUE(VALUE) ((50 <= (VALUE)) && ((VALUE) <= 432)) #define IS_RCC_PLLI2SR_VALUE(VALUE) ((2 <= (VALUE)) && ((VALUE) <= 7)) #define IS_RCC_PLLI2SM_VALUE(VALUE) ((VALUE) <= 63) #define IS_RCC_PLLI2SQ_VALUE(VALUE) ((2 <= (VALUE)) && ((VALUE) <= 15)) -#if defined(STM32F446xx) +#if defined(STM32F446xx) #define IS_RCC_PLLI2SP_VALUE(VALUE) (((VALUE) == 2) || ((VALUE) == 4) || ((VALUE) == 6) || ((VALUE) == 8)) #define IS_RCC_PLLSAIM_VALUE(VALUE) ((VALUE) <= 63) +#elif defined(STM32F412xG) +#define IS_RCC_PLLI2SP_VALUE(VALUE) (((VALUE) == 2) || ((VALUE) == 4) || ((VALUE) == 6) || ((VALUE) == 8)) +#else #endif /* STM32F446xx */ #define IS_RCC_PLLSAIN_VALUE(VALUE) ((50 <= (VALUE)) && ((VALUE) <= 432)) #if defined(STM32F446xx) || defined(STM32F469_479xx) @@ -137,7 +140,7 @@ typedef struct * @{ */ -#if defined(STM32F446xx) +#if defined(STM32F412xG) || defined(STM32F446xx) #define RCC_SYSCLKSource_HSI ((uint32_t)0x00000000) #define RCC_SYSCLKSource_HSE ((uint32_t)0x00000001) #define RCC_SYSCLKSource_PLLPCLK ((uint32_t)0x00000002) @@ -313,8 +316,10 @@ typedef struct #define RCC_LPTIM1CLKSOURCE_LSI ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_1) #define RCC_LPTIM1CLKSOURCE_LSE ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_0 | RCC_DCKCFGR2_LPTIM1SEL_1) -#define IS_RCC_LPTIM1_SOURCE(SOURCE) (((SOURCE) == RCC_LPTIM1CLKSOURCE_PCLK) || ((SOURCE) == RCC_LPTIM1CLKSOURCE_HSI) || \ - ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSI) || ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSE)) +#define IS_RCC_LPTIM1_CLOCKSOURCE(SOURCE) (((SOURCE) == RCC_LPTIM1CLKSOURCE_PCLK) || ((SOURCE) == RCC_LPTIM1CLKSOURCE_HSI) || \ + ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSI) || ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSE)) +/* Legacy Defines */ +#define IS_RCC_LPTIM1_SOURCE IS_RCC_LPTIM1_CLOCKSOURCE /** * @} */ @@ -325,13 +330,15 @@ typedef struct #define RCC_I2SAPBCLKSOURCE_PLLR ((uint32_t)0x00000000) #define RCC_I2SAPBCLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_I2SSRC_0) #define RCC_I2SAPBCLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_I2SSRC_1) +#define IS_RCC_I2SCLK_SOURCE(SOURCE) (((SOURCE) == RCC_I2SAPBCLKSOURCE_PLLR) || ((SOURCE) == RCC_I2SAPBCLKSOURCE_EXT) || \ + ((SOURCE) == RCC_I2SAPBCLKSOURCE_PLLSRC)) /** * @} */ #endif /* STM32F410xx */ -#if defined(STM32F446xx) +#if defined(STM32F412xG) || defined(STM32F446xx) /** @defgroup RCC_I2S_Clock_Source * @{ */ @@ -355,7 +362,7 @@ typedef struct /** * @} */ - +#if defined(STM32F446xx) /** @defgroup RCC_SAI_Clock_Source * @{ */ @@ -380,6 +387,7 @@ typedef struct * @} */ #endif /* STM32F446xx */ +#endif /* STM32F412xG || STM32F446xx */ #if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F411xE) || defined(STM32F469_479xx) /** @defgroup RCC_I2S_Clock_Source @@ -446,7 +454,7 @@ typedef struct */ #endif /* STM32F469_479xx */ -#if defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx) /** @defgroup RCC_SDIO_Clock_Source_Selection * @{ */ @@ -462,14 +470,22 @@ typedef struct /** @defgroup RCC_48MHZ_Clock_Source_Selection * @{ */ +#if defined(STM32F446xx) || defined(STM32F469_479xx) #define RCC_48MHZCLKSource_PLL ((uint8_t)0x00) #define RCC_48MHZCLKSource_PLLSAI ((uint8_t)0x01) #define IS_RCC_48MHZ_CLOCKSOURCE(CLKSOURCE) (((CLKSOURCE) == RCC_48MHZCLKSource_PLL) || \ ((CLKSOURCE) == RCC_48MHZCLKSource_PLLSAI)) +#endif /* STM32F446xx || STM32F469_479xx */ +#if defined(STM32F412xG) +#define RCC_CK48CLKSOURCE_PLLQ ((uint8_t)0x00) +#define RCC_CK48CLKSOURCE_PLLI2SQ ((uint8_t)0x01) /* Only for STM32F412xG Devices */ +#define IS_RCC_48MHZ_CLOCKSOURCE(CLKSOURCE) (((CLKSOURCE) == RCC_CK48CLKSOURCE_PLLQ) || \ + ((CLKSOURCE) == RCC_CK48CLKSOURCE_PLLI2SQ)) +#endif /* STM32F412xG */ /** * @} */ -#endif /* STM32F446xx || STM32F469_479xx */ +#endif /* STM32F412xG || STM32F446xx || STM32F469_479xx */ #if defined(STM32F446xx) /** @defgroup RCC_SPDIFRX_Clock_Source_Selection @@ -512,7 +528,7 @@ typedef struct */ #endif /* STM32F446xx */ -#if defined(STM32F410xx) || defined(STM32F4446xx) +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) /** @defgroup RCC_FMPI2C1_Clock_Source * @{ */ @@ -521,11 +537,33 @@ typedef struct #define RCC_FMPI2C1CLKSource_HSI ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_1) #define IS_RCC_FMPI2C1_CLOCKSOURCE(SOURCE) (((SOURCE) == RCC_FMPI2C1CLKSource_APB1) || ((SOURCE) == RCC_FMPI2C1CLKSource_SYSCLK) || \ - ((SOURCE) == RCC_FMPI2C1CLKSource_HSI)) + ((SOURCE) == RCC_FMPI2C1CLKSource_HSI)) /** * @} */ -#endif /* STM32F410xx || STM32F4446xx */ +#endif /* STM32F410xx || STM32F412xG || STM32F446xx */ + +#if defined(STM32F412xG) +/** @defgroup RCC_DFSDM_Clock_Source + * @{ + */ +#define RCC_DFSDM1CLKSource_APB ((uint8_t)0x00) +#define RCC_DFSDM1CLKSource_SYS ((uint8_t)0x01) +#define IS_RCC_DFSDM1CLK_SOURCE(SOURCE) (((SOURCE) == RCC_DFSDM1CLKSource_APB) || ((SOURCE) == RCC_DFSDM1CLKSource_SYS)) +/** + * @} + */ + +/** @defgroup RCC_DFSDM_Audio_Clock_Source RCC DFSDM Audio Clock Source + * @{ + */ +#define RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB1 ((uint32_t)0x00000000) +#define RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB2 ((uint32_t)RCC_DCKCFGR_CKDFSDM1ASEL) +#define IS_RCC_DFSDMACLK_SOURCE(SOURCE) (((SOURCE) == RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB1) || ((SOURCE) == RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB2)) +/** + * @} + */ +#endif /* STM32F412xG */ /** @defgroup RCC_AHB1_Peripherals * @{ @@ -574,7 +612,7 @@ typedef struct #define RCC_AHB2Periph_DCMI ((uint32_t)0x00000001) #define RCC_AHB2Periph_CRYP ((uint32_t)0x00000010) #define RCC_AHB2Periph_HASH ((uint32_t)0x00000020) -#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx) +#if defined(STM32F40_41xxx) || defined(STM32F412xG) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx) #define RCC_AHB2Periph_RNG ((uint32_t)0x00000040) #endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F469_479xx */ #define RCC_AHB2Periph_OTG_FS ((uint32_t)0x00000080) @@ -602,6 +640,12 @@ typedef struct #define IS_RCC_AHB3_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFFFC) == 0x00) && ((PERIPH) != 0x00)) #endif /* STM32F446xx || STM32F469_479xx */ +#if defined(STM32F412xG) +#define RCC_AHB3Periph_FSMC ((uint32_t)0x00000001) +#define RCC_AHB3Periph_QSPI ((uint32_t)0x00000002) +#define IS_RCC_AHB3_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFFFC) == 0x00) && ((PERIPH) != 0x00)) +#endif /* STM32F412xG */ + /** * @} */ @@ -634,7 +678,7 @@ typedef struct #define RCC_APB1Periph_I2C1 ((uint32_t)0x00200000) #define RCC_APB1Periph_I2C2 ((uint32_t)0x00400000) #define RCC_APB1Periph_I2C3 ((uint32_t)0x00800000) -#if defined(STM32F410xx) || defined(STM32F446xx) +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) #define RCC_APB1Periph_FMPI2C1 ((uint32_t)0x01000000) #endif /* STM32F410xx || STM32F446xx */ #define RCC_APB1Periph_CAN1 ((uint32_t)0x02000000) @@ -679,9 +723,12 @@ typedef struct #if defined(STM32F469_479xx) #define RCC_APB2Periph_DSI ((uint32_t)0x08000000) #endif /* STM32F469_479xx */ +#if defined(STM32F412xG) +#define RCC_APB2Periph_DFSDM ((uint32_t)0x01000000) +#endif /* STM32F412xG */ -#define IS_RCC_APB2_PERIPH(PERIPH) ((((PERIPH) & 0xF30880CC) == 0x00) && ((PERIPH) != 0x00)) -#define IS_RCC_APB2_RESET_PERIPH(PERIPH) ((((PERIPH) & 0xF30886CC) == 0x00) && ((PERIPH) != 0x00)) +#define IS_RCC_APB2_PERIPH(PERIPH) ((((PERIPH) & 0xF20880CC) == 0x00) && ((PERIPH) != 0x00)) +#define IS_RCC_APB2_RESET_PERIPH(PERIPH) ((((PERIPH) & 0xF20886CC) == 0x00) && ((PERIPH) != 0x00)) /** * @} @@ -782,9 +829,9 @@ void RCC_LSICmd(FunctionalState NewState); void RCC_PLLCmd(FunctionalState NewState); -#if defined(STM32F410xx) || defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx) void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP, uint32_t PLLQ, uint32_t PLLR); -#endif /* STM32F410xx || STM32F446xx || STM32F469_479xx */ +#endif /* STM32F410xx || STM32F412xG || STM32F446xx || STM32F469_479xx */ #if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F411xE) void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP, uint32_t PLLQ); @@ -801,9 +848,9 @@ void RCC_PLLI2SConfig(uint32_t PLLI2SN, uint32_t PLLI2SR, uint32_t PLLI2S #if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx) void RCC_PLLI2SConfig(uint32_t PLLI2SN, uint32_t PLLI2SQ, uint32_t PLLI2SR); #endif /* STM32F427_437xx || STM32F429_439xx || STM32F469_479xx */ -#if defined(STM32F446xx) +#if defined(STM32F412xG) || defined(STM32F446xx) void RCC_PLLI2SConfig(uint32_t PLLI2SM, uint32_t PLLI2SN, uint32_t PLLI2SP, uint32_t PLLI2SQ, uint32_t PLLI2SR); -#endif /* STM32F446xx */ +#endif /* STM32F412xG || STM32F446xx */ void RCC_PLLSAICmd(FunctionalState NewState); #if defined(STM32F469_479xx) @@ -833,10 +880,12 @@ void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource); void RCC_RTCCLKCmd(FunctionalState NewState); void RCC_BackupResetCmd(FunctionalState NewState); -#if defined(STM32F446xx) +#if defined(STM32F412xG) || defined(STM32F446xx) void RCC_I2SCLKConfig(uint32_t RCC_I2SAPBx, uint32_t RCC_I2SCLKSource); +#if defined(STM32F446xx) void RCC_SAICLKConfig(uint32_t RCC_SAIInstance, uint32_t RCC_SAICLKSource); #endif /* STM32F446xx */ +#endif /* STM32F412xG || STM32F446xx */ #if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE) || defined(STM32F469_479xx) void RCC_I2SCLKConfig(uint32_t RCC_I2SCLKSource); @@ -879,11 +928,11 @@ void RCC_LSEModeConfig(uint8_t RCC_Mode); void RCC_DSIClockSourceConfig(uint8_t RCC_ClockSource); #endif /* STM32F469_479xx */ -/* Features available only for STM32F446xx/STM32F469_479xx devices */ -#if defined(STM32F446xx) || defined(STM32F469_479xx) +/* Features available only for STM32F412xG/STM32F446xx/STM32F469_479xx devices */ +#if defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx) void RCC_48MHzClockSourceConfig(uint8_t RCC_ClockSource); void RCC_SDIOClockSourceConfig(uint8_t RCC_ClockSource); -#endif /* STM32F446xx || STM32F469_479xx */ +#endif /* STM32F412xG || STM32F446xx || STM32F469_479xx */ /* Features available only for STM32F446xx devices */ #if defined(STM32F446xx) @@ -892,10 +941,10 @@ void RCC_SPDIFRXClockSourceConfig(uint8_t RCC_ClockSource); void RCC_CECClockSourceConfig(uint8_t RCC_ClockSource); #endif /* STM32F446xx */ -/* Features available only for STM32F410xx/STM32F446xx devices */ -#if defined(STM32F410xx) || defined(STM32F446xx) +/* Features available only for STM32F410xx/STM32F412xG/STM32F446xx devices */ +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) void RCC_FMPI2C1ClockSourceConfig(uint32_t RCC_ClockSource); -#endif /* STM32F410xx || STM32F446xx */ +#endif /* STM32F410xx || STM32F412xG || STM32F446xx */ /* Features available only for STM32F410xx devices */ #if defined(STM32F410xx) @@ -905,6 +954,10 @@ void RCC_MCO1Cmd(FunctionalState NewState); void RCC_MCO2Cmd(FunctionalState NewState); #endif /* STM32F410xx */ +#if defined(STM32F412xG) +void RCC_DFSDM1CLKConfig(uint32_t RCC_DFSDM1CLKSource); +void RCC_DFSDM1ACLKConfig(uint32_t RCC_DFSDM1ACLKSource); +#endif /* STM32F412xG */ /* Interrupts and flags management functions **********************************/ void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState); FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG); diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rng.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rng.h index 55be367024..fca226a6ec 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rng.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rng.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_rng.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the Random * Number Generator(RNG) firmware library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -44,7 +44,7 @@ /** @addtogroup RNG * @{ */ -#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F410xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx) +#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F429_439xx) || defined(STM32F469_479xx) /* Exported types ------------------------------------------------------------*/ /* Exported constants --------------------------------------------------------*/ @@ -102,7 +102,7 @@ FlagStatus RNG_GetFlagStatus(uint8_t RNG_FLAG); void RNG_ClearFlag(uint8_t RNG_FLAG); ITStatus RNG_GetITStatus(uint8_t RNG_IT); void RNG_ClearITPendingBit(uint8_t RNG_IT); -#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F410xx || STM32F429_439xx || STM32F469_479xx */ +#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F410xx || STM32F412xG || STM32F429_439xx || STM32F469_479xx */ #ifdef __cplusplus } diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rtc.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rtc.h index be7c501b94..c46c020aad 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rtc.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rtc.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_rtc.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the RTC firmware * library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -591,8 +591,9 @@ typedef struct /** @defgroup RTC_Tamper_Pins_Definitions * @{ */ -#define RTC_Tamper_1 RTC_TAFCR_TAMP1E -#define IS_RTC_TAMPER(TAMPER) (((TAMPER) == RTC_Tamper_1)) +#define RTC_Tamper_1 RTC_TAFCR_TAMP1E +#define RTC_Tamper_2 RTC_TAFCR_TAMP2E +#define IS_RTC_TAMPER(TAMPER) (((TAMPER) == RTC_Tamper_1) || ((TAMPER) == RTC_Tamper_2)) /** * @} @@ -601,10 +602,13 @@ typedef struct /** @defgroup RTC_Tamper_Pin_Selection * @{ */ -#define RTC_TamperPin_PC13 ((uint32_t)0x00000000) -#define RTC_TamperPin_PI8 ((uint32_t)0x00010000) -#define IS_RTC_TAMPER_PIN(PIN) (((PIN) == RTC_TamperPin_PC13) || \ - ((PIN) == RTC_TamperPin_PI8)) +#define RTC_TamperPin_Default ((uint32_t)0x00000000) +#define RTC_TamperPin_Pos1 ((uint32_t)0x00010000) +#define IS_RTC_TAMPER_PIN(PIN) (((PIN) == RTC_TamperPin_Default) || \ + ((PIN) == RTC_TamperPin_Pos1)) +/* Legacy Defines */ +#define RTC_TamperPin_PC13 RTC_TamperPin_Default +#define RTC_TamperPin_PI8 RTC_TamperPin_Pos1 /** * @} */ @@ -616,6 +620,7 @@ typedef struct #define RTC_TimeStampPin_PI8 ((uint32_t)0x00020000) #define IS_RTC_TIMESTAMP_PIN(PIN) (((PIN) == RTC_TimeStampPin_PC13) || \ ((PIN) == RTC_TimeStampPin_PI8)) + /** * @} */ @@ -716,6 +721,7 @@ typedef struct */ #define RTC_FLAG_RECALPF ((uint32_t)0x00010000) #define RTC_FLAG_TAMP1F ((uint32_t)0x00002000) +#define RTC_FLAG_TAMP2F ((uint32_t)0x00004000) #define RTC_FLAG_TSOVF ((uint32_t)0x00001000) #define RTC_FLAG_TSF ((uint32_t)0x00000800) #define RTC_FLAG_WUTF ((uint32_t)0x00000400) @@ -734,7 +740,7 @@ typedef struct ((FLAG) == RTC_FLAG_RSF) || ((FLAG) == RTC_FLAG_WUTWF) || \ ((FLAG) == RTC_FLAG_ALRBWF) || ((FLAG) == RTC_FLAG_ALRAWF) || \ ((FLAG) == RTC_FLAG_TAMP1F) || ((FLAG) == RTC_FLAG_RECALPF) || \ - ((FLAG) == RTC_FLAG_SHPF)) + ((FLAG) == RTC_FLAG_TAMP2F) ||((FLAG) == RTC_FLAG_SHPF)) #define IS_RTC_CLEAR_FLAG(FLAG) (((FLAG) != (uint32_t)RESET) && (((FLAG) & 0xFFFF00DF) == (uint32_t)RESET)) /** * @} @@ -749,12 +755,13 @@ typedef struct #define RTC_IT_ALRA ((uint32_t)0x00001000) #define RTC_IT_TAMP ((uint32_t)0x00000004) /* Used only to Enable the Tamper Interrupt */ #define RTC_IT_TAMP1 ((uint32_t)0x00020000) +#define RTC_IT_TAMP2 ((uint32_t)0x00040000) #define IS_RTC_CONFIG_IT(IT) (((IT) != (uint32_t)RESET) && (((IT) & 0xFFFF0FFB) == (uint32_t)RESET)) #define IS_RTC_GET_IT(IT) (((IT) == RTC_IT_TS) || ((IT) == RTC_IT_WUT) || \ ((IT) == RTC_IT_ALRB) || ((IT) == RTC_IT_ALRA) || \ - ((IT) == RTC_IT_TAMP1)) -#define IS_RTC_CLEAR_IT(IT) (((IT) != (uint32_t)RESET) && (((IT) & 0xFFFD0FFF) == (uint32_t)RESET)) + ((IT) == RTC_IT_TAMP1) || ((IT) == RTC_IT_TAMP2)) +#define IS_RTC_CLEAR_IT(IT) (((IT) != (uint32_t)RESET) && (((IT) & 0xFFF90FFF) == (uint32_t)RESET)) /** * @} diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_sai.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_sai.h index aa572d5914..40d646d3d6 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_sai.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_sai.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_sai.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the SAI * firmware library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_sdio.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_sdio.h index 891e00b03a..7e43de249a 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_sdio.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_sdio.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_sdio.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the SDIO firmware * library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_spdifrx.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_spdifrx.h index 6cf999664d..6db84c9a26 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_spdifrx.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_spdifrx.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_spdifrx.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the SPDIFRX firmware * library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_spi.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_spi.h index 9a42d0401f..58b2690f7b 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_spi.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_spi.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_spi.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the SPI * firmware library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_syscfg.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_syscfg.h index af075d5c09..62d4df1047 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_syscfg.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_syscfg.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_syscfg.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the SYSCFG firmware * library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -132,9 +132,9 @@ #define SYSCFG_MemoryRemap_SRAM ((uint8_t)0x03) #define SYSCFG_MemoryRemap_SDRAM ((uint8_t)0x04) -#if defined (STM32F40_41xxx) +#if defined (STM32F40_41xxx) || defined(STM32F412xG) #define SYSCFG_MemoryRemap_FSMC ((uint8_t)0x02) -#endif /* STM32F40_41xxx */ +#endif /* STM32F40_41xxx || STM32F412xG */ #if defined (STM32F427_437xx) || defined (STM32F429_439xx) #define SYSCFG_MemoryRemap_FMC ((uint8_t)0x02) @@ -144,12 +144,12 @@ #define SYSCFG_MemoryRemap_ExtMEM ((uint8_t)0x02) #endif /* STM32F446xx || STM32F469_479xx */ -#if defined (STM32F40_41xxx) +#if defined (STM32F40_41xxx) || defined(STM32F412xG) #define IS_SYSCFG_MEMORY_REMAP_CONFING(REMAP) (((REMAP) == SYSCFG_MemoryRemap_Flash) || \ ((REMAP) == SYSCFG_MemoryRemap_SystemFlash) || \ ((REMAP) == SYSCFG_MemoryRemap_SRAM) || \ ((REMAP) == SYSCFG_MemoryRemap_FSMC)) -#endif /* STM32F40_41xxx */ +#endif /* STM32F40_41xxx || defined(STM32F412xG */ #if defined (STM32F401xx) || defined (STM32F410xx) || defined (STM32F411xE) #define IS_SYSCFG_MEMORY_REMAP_CONFING(REMAP) (((REMAP) == SYSCFG_MemoryRemap_Flash) || \ @@ -173,13 +173,13 @@ ((REMAP) == SYSCFG_MemoryRemap_SDRAM)) #endif /* STM32F446xx || STM32F469_479xx */ -#if defined(STM32F410xx) +#if defined(STM32F410xx) || defined(STM32F412xG) #define SYSCFG_Break_PVD SYSCFG_CFGR2_PVDL #define SYSCFG_Break_HardFault SYSCFG_CFGR2_CLL #define IS_SYSCFG_LOCK_CONFIG(BREAK) (((BREAK) == SYSCFG_Break_PVD) || \ - ((BREAK) == SYSCFG_Break_PVD)) -#endif /* STM32F410xx */ + ((BREAK) == SYSCFG_Break_HardFault)) +#endif /* STM32F410xx || STM32F412xG */ /** * @} */ @@ -211,9 +211,9 @@ void SYSCFG_EXTILineConfig(uint8_t EXTI_PortSourceGPIOx, uint8_t EXTI_PinS void SYSCFG_ETH_MediaInterfaceConfig(uint32_t SYSCFG_ETH_MediaInterface); void SYSCFG_CompensationCellCmd(FunctionalState NewState); FlagStatus SYSCFG_GetCompensationCellStatus(void); -#if defined(STM32F410xx) +#if defined(STM32F410xx) || defined(STM32F412xG) void SYSCFG_BreakConfig(uint32_t SYSCFG_Break); -#endif /* STM32F410xx */ +#endif /* STM32F410xx || STM32F412xG */ #ifdef __cplusplus } #endif diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_tim.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_tim.h index 8546142416..eb5032f047 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_tim.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_tim.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_tim.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the TIM firmware * library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_usart.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_usart.h index a1c723b6d3..f70e24e17d 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_usart.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_usart.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_usart.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the USART * firmware library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_wwdg.h b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_wwdg.h index 38a194da97..0d33d55127 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_wwdg.h +++ b/lib/main/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_wwdg.h @@ -2,14 +2,14 @@ ****************************************************************************** * @file stm32f4xx_wwdg.h * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file contains all the functions prototypes for the WWDG firmware * library. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/misc.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/misc.c index 5b99dc04e0..62ee73edda 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/misc.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/misc.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file misc.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides all the miscellaneous firmware functions (add-on * to CMSIS functions). * @@ -55,7 +55,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_adc.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_adc.c index e5f65573b5..cb0fcbc2a9 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_adc.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_adc.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_adc.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Analog to Digital Convertor (ADC) peripheral: * + Initialization and Configuration (in addition to ADC multi mode @@ -85,7 +85,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_can.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_can.c index 9f8e235c06..6334dce3bd 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_can.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_can.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_can.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Controller area network (CAN) peripheral: * + Initialization and Configuration @@ -63,7 +63,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cec.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cec.c index 470e0ddf6c..b3eec64cf7 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cec.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cec.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_cec.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Consumer Electronics Control (CEC) peripheral * applicable only on STM32F446xx devices: @@ -72,7 +72,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_crc.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_crc.c index a44af6f8f6..b505d85cd7 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_crc.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_crc.c @@ -2,13 +2,13 @@ ****************************************************************************** * @file stm32f4xx_crc.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides all the CRC firmware functions. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp.c index 47d8e0ce8f..517f223075 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_cryp.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Cryptographic processor (CRYP) peripheral: * + Initialization and Configuration functions @@ -143,7 +143,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_aes.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_aes.c index 4f4fc5e588..a99808f8f9 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_aes.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_aes.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_cryp_aes.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides high level functions to encrypt and decrypt an * input message using AES in ECB/CBC/CTR/GCM/CCM modes. * It uses the stm32f4xx_cryp.c/.h drivers to access the STM32F4xx CRYP @@ -34,7 +34,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_des.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_des.c index e2bb078cc6..0fd815b759 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_des.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_des.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_cryp_des.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides high level functions to encrypt and decrypt an * input message using DES in ECB/CBC modes. * It uses the stm32f4xx_cryp.c/.h drivers to access the STM32F4xx CRYP @@ -27,7 +27,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_tdes.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_tdes.c index 63c5ba9174..93e06a45e0 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_tdes.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_tdes.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_cryp_tdes.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides high level functions to encrypt and decrypt an * input message using TDES in ECB/CBC modes . * It uses the stm32f4xx_cryp.c/.h drivers to access the STM32F4xx CRYP @@ -27,7 +27,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dac.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dac.c index d2f349253a..6948816c3f 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dac.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dac.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_dac.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Digital-to-Analog Converter (DAC) peripheral: * + DAC channels configuration: trigger, output buffer, data format @@ -109,7 +109,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dbgmcu.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dbgmcu.c index f93c5dd9e2..e9c161a271 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dbgmcu.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dbgmcu.c @@ -2,13 +2,13 @@ ****************************************************************************** * @file stm32f4xx_dbgmcu.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides all the DBGMCU firmware functions. ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dcmi.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dcmi.c index e872103303..e1076cef35 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dcmi.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dcmi.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_dcmi.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the DCMI peripheral: * + Initialization and Configuration @@ -65,7 +65,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dfsdm.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dfsdm.c new file mode 100644 index 0000000000..623561af2a --- /dev/null +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dfsdm.c @@ -0,0 +1,1441 @@ +/** + ****************************************************************************** + * @file stm32f4xx_dfsdm.c + * @author MCD Application Team + * @version V1.7.1 + * @date 20-May-2016 + * @brief This file provides firmware functions to manage the following + * functionalities of Digital Filter for Sigma Delta modulator + * (DFSDM) peripheral: + * + Initialization functions. + * + Configuration functions. + * + Interrupts and flags management functions. + * + * @verbatim + * +================================================================================ + ##### How to use this driver ##### +================================================================================ + [..] + + @endverbatim + ****************************************************************************** + * @attention + * + *

© COPYRIGHT 2016 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_dfsdm.h" +#include "stm32f4xx_rcc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup DFSDM + * @brief DFSDM driver modules + * @{ + */ +#if defined(STM32F412xG) + +/* External variables --------------------------------------------------------*/ +/* Private typedef -----------------------------------------------------------*/ +/* Private defines -----------------------------------------------------------*/ + +#define CHCFGR_INIT_CLEAR_MASK (uint32_t) 0xFFFE0F10 + +/* Private macros ------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup DFSDM_Private_Functions + * @{ + */ + +/** @defgroup DFSDM_Group1 Initialization functions + * @brief Initialization functions + * +@verbatim + =============================================================================== + Initialization functions + =============================================================================== + This section provides functions allowing to: + - Deinitialize the DFSDM + - Initialize DFSDM serial channels transceiver + - Initialize DFSDM filter + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the DFSDM peripheral registers to their default reset values. + * @param None. + * @retval None. + * + */ +void DFSDM_DeInit(void) +{ + /* Enable LPTx reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_DFSDM, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_DFSDM, DISABLE); +} + +/** + * @brief Initializes the DFSDM serial channels transceiver according to the specified + * parameters in the DFSDM_TransceiverInit. + * @param DFSDM_Channelx: where x can be a value from 0 to 7 to select the DFSDM Channel. + * @param DFSDM_TransceiverInitStruct: pointer to a DFSDM_TransceiverInitTypeDef structure + * that contains the configuration information for the specified channel. + * @retval None + * @note It is mandatory to disable the selected channel to use this function. + */ +void DFSDM_TransceiverInit(DFSDM_Channel_TypeDef* DFSDM_Channelx, DFSDM_TransceiverInitTypeDef* DFSDM_TransceiverInitStruct) +{ + uint32_t tmpreg1 = 0; + uint32_t tmpreg2 = 0; + + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_CHANNEL(DFSDM_Channelx)); + assert_param(IS_DFSDM_INTERFACE(DFSDM_TransceiverInitStruct->DFSDM_Interface)); + assert_param(IS_DFSDM_Input_MODE(DFSDM_TransceiverInitStruct->DFSDM_Input)); + assert_param(IS_DFSDM_Redirection_STATE(DFSDM_TransceiverInitStruct->DFSDM_Redirection)); + assert_param(IS_DFSDM_PACK_MODE(DFSDM_TransceiverInitStruct->DFSDM_PackingMode)); + assert_param(IS_DFSDM_CLOCK(DFSDM_TransceiverInitStruct->DFSDM_Clock)); + assert_param(IS_DFSDM_DATA_RIGHT_BIT_SHIFT(DFSDM_TransceiverInitStruct->DFSDM_DataRightShift)); + assert_param(IS_DFSDM_OFFSET(DFSDM_TransceiverInitStruct->DFSDM_Offset)); + assert_param(IS_DFSDM_CLK_DETECTOR_STATE(DFSDM_TransceiverInitStruct->DFSDM_CLKAbsenceDetector)); + assert_param(IS_DFSDM_SC_DETECTOR_STATE(DFSDM_TransceiverInitStruct->DFSDM_ShortCircuitDetector)); + + /* Get the DFSDM Channelx CHCFGR1 value */ + tmpreg1 = DFSDM_Channelx->CHCFGR1; + + /* Clear SITP, CKABEN, SCDEN and SPICKSEL bits */ + tmpreg1 &= CHCFGR_INIT_CLEAR_MASK; + + /* Set or Reset SITP bits according to DFSDM_Interface value */ + /* Set or Reset SPICKSEL bits according to DFSDM_Clock value */ + /* Set or Reset DATMPX bits according to DFSDM_InputMode value */ + /* Set or Reset CHINSEL bits according to DFSDM_Redirection value */ + /* Set or Reset DATPACK bits according to DFSDM_PackingMode value */ + /* Set or Reset CKABEN bit according to DFSDM_CLKAbsenceDetector value */ + /* Set or Reset SCDEN bit according to DFSDM_ShortCircuitDetector value */ + tmpreg1 |= (DFSDM_TransceiverInitStruct->DFSDM_Interface | + DFSDM_TransceiverInitStruct->DFSDM_Clock | + DFSDM_TransceiverInitStruct->DFSDM_Input | + DFSDM_TransceiverInitStruct->DFSDM_Redirection | + DFSDM_TransceiverInitStruct->DFSDM_PackingMode | + DFSDM_TransceiverInitStruct->DFSDM_CLKAbsenceDetector | + DFSDM_TransceiverInitStruct->DFSDM_ShortCircuitDetector); + + /* Write to DFSDM Channelx CHCFGR1R */ + DFSDM_Channelx->CHCFGR1 = tmpreg1; + + /* Get the DFSDM Channelx CHCFGR2 value */ + tmpreg2 = DFSDM_Channelx->CHCFGR2; + + /* Clear DTRBS and OFFSET bits */ + tmpreg2 &= ~(DFSDM_CHCFGR2_DTRBS | DFSDM_CHCFGR2_OFFSET); + + /* Set or Reset DTRBS bits according to DFSDM_DataRightShift value */ + /* Set or Reset OFFSET bits according to DFSDM_Offset value */ + tmpreg2 |= (((DFSDM_TransceiverInitStruct->DFSDM_DataRightShift) <<3 ) | + ((DFSDM_TransceiverInitStruct->DFSDM_Offset) <<8 )); + + /* Write to DFSDM Channelx CHCFGR1R */ + DFSDM_Channelx->CHCFGR2 = tmpreg2; +} + +/** + * @brief Fills each DFSDM_TransceiverInitStruct member with its default value. + * @param DFSDM_TransceiverInitStruct : pointer to a DFSDM_TransceiverInitTypeDef structure + * which will be initialized. + * @retval None + */ +void DFSDM_TransceiverStructInit(DFSDM_TransceiverInitTypeDef* DFSDM_TransceiverInitStruct) +{ + /* SPI with rising edge to strobe data is selected as default serial interface */ + DFSDM_TransceiverInitStruct->DFSDM_Interface = DFSDM_Interface_SPI_FallingEdge; + + /* Clock coming from internal DFSDM_CKOUT output is selected as default serial clock */ + DFSDM_TransceiverInitStruct->DFSDM_Clock = DFSDM_Clock_Internal; + + /* No data right bit-shift is selected as default data right bit-shift */ + DFSDM_TransceiverInitStruct->DFSDM_DataRightShift = 0x0; + + /* No offset is selected as default offset */ + DFSDM_TransceiverInitStruct->DFSDM_Offset = 0x0; + + /* Clock Absence Detector is Enabled as default state */ + DFSDM_TransceiverInitStruct->DFSDM_CLKAbsenceDetector = DFSDM_CLKAbsenceDetector_Enable; +} + +/** + * @brief Initializes the DFSDMx Filter according to the specified + * parameters in the DFSDM_FilterInitStruct. + * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module. + * @param DFSDM_FilterInitStruct: pointer to a DFSDM_FilterInitTypeDef structure + * that contains the configuration information for the specified filter. + * @retval None + * + * @note It is mandatory to disable the selected filter to use this function. + */ +void DFSDM_FilterInit(DFSDM_TypeDef* DFSDMx, DFSDM_FilterInitTypeDef* DFSDM_FilterInitStruct) +{ + uint32_t tmpreg1 = 0; + + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + assert_param(IS_DFSDM_SINC_ORDER(DFSDM_FilterInitStruct->DFSDM_SincOrder)); + assert_param(IS_DFSDM_SINC_OVRSMPL_RATIO(DFSDM_FilterInitStruct->DFSDM_FilterOversamplingRatio)); + assert_param(IS_DFSDM_INTG_OVRSMPL_RATIO(DFSDM_FilterInitStruct->DFSDM_IntegratorOversamplingRatio)); + + /* Get the DFSDMx FCR value */ + tmpreg1 = DFSDMx->FLTFCR; + + /* Clear FORD, FOSR and IOSR bits */ + tmpreg1 &= ~(DFSDM_FLTFCR_FORD | DFSDM_FLTFCR_FOSR | DFSDM_FLTFCR_IOSR); + + /* Set or Reset FORD bits according to DFSDM_SincOrder value */ + /* Set or Reset FOSR bits according to DFSDM_FilterOversamplingRatio value */ + /* Set or Reset IOSR bits according to DFSDM_IntegratorOversamplingRatio value */ + tmpreg1 |= (DFSDM_FilterInitStruct->DFSDM_SincOrder | + ((DFSDM_FilterInitStruct->DFSDM_FilterOversamplingRatio -1) << 16) | + (DFSDM_FilterInitStruct->DFSDM_IntegratorOversamplingRatio -1)); + + /* Write to DFSDMx FCR */ + DFSDMx->FLTFCR = tmpreg1; +} + +/** + * @brief Fills each DFSDM_FilterInitStruct member with its default value. + * @param DFSDM_FilterInitStruct: pointer to a DFSDM_FilterInitTypeDef structure + * which will be initialized. + * @retval None + */ +void DFSDM_FilterStructInit(DFSDM_FilterInitTypeDef* DFSDM_FilterInitStruct) +{ + /* Order = 3 is selected as default sinc order */ + DFSDM_FilterInitStruct->DFSDM_SincOrder = DFSDM_SincOrder_Sinc3; + + /* Ratio = 64 is selected as default oversampling ratio */ + DFSDM_FilterInitStruct->DFSDM_FilterOversamplingRatio = 64 ; + + /* Ratio = 4 is selected as default integrator oversampling ratio */ + DFSDM_FilterInitStruct->DFSDM_IntegratorOversamplingRatio = 4; +} + +/** + * @} + */ + +/** @defgroup DFSDM_Group2 Configuration functions + * @brief Configuration functions + * +@verbatim + =============================================================================== + Configuration functions + =============================================================================== + This section provides functions allowing to configure DFSDM: + - Enable/Disable (DFSDM peripheral, Channel, Filter) + - Configure Clock output + - Configure Injected/Regular channels for Conversion + - Configure short circuit detector + - Configure Analog watchdog filter + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the DFSDM peripheral. + * @param NewState: new state of the DFSDM interface. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DFSDM_Cmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the ENABLE bit */ + DFSDM1_Channel0 -> CHCFGR1 |= DFSDM_CHCFGR1_DFSDMEN; + } + else + { + /* Reset the ENABLE bit */ + DFSDM1_Channel0 -> CHCFGR1 &= ~(DFSDM_CHCFGR1_DFSDMEN); + } +} + +/** + * @brief Enables or disables the specified DFSDM serial channelx. + * @param DFSDM_Channelx: where x can be a value from 0 to 7 to select the DFSDM Channel. + * @param NewState: new state of the DFSDM serial channelx . + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DFSDM_ChannelCmd(DFSDM_Channel_TypeDef* DFSDM_Channelx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_CHANNEL(DFSDM_Channelx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the ENABLE bit */ + DFSDM_Channelx->CHCFGR1 |= DFSDM_CHCFGR1_CHEN; + } + else + { + /* Reset the ENABLE bit */ + DFSDM_Channelx->CHCFGR1 &= ~(DFSDM_CHCFGR1_CHEN); + } +} + +/** + * @brief Enables or disables the specified DFSDMx Filter. + * @param DFSDMx: where x can be 0, 1 to select the DFSDM module. + * @param NewState: new state of the selected DFSDM module. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DFSDM_FilterCmd(DFSDM_TypeDef* DFSDMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the ENABLE bit */ + DFSDMx->FLTCR1 |= DFSDM_FLTCR1_DFEN; + } + else + { + /* Reset the ENABLE bit */ + DFSDMx->FLTCR1 &= ~(DFSDM_FLTCR1_DFEN); + } +} + +/** + * @brief Configures the Output serial clock divider. + * @param DFSDM_ClkOutDivision: Defines the divider for the output serial clock + * This parameter can be a value between 1 and 256. + * @retval None + * @note The output serial clock is stopped if the divider =1. + * By default the serial output clock is stopped. + */ +void DFSDM_ConfigClkOutputDivider(uint32_t DFSDM_ClkOutDivision) +{ + uint32_t tmpreg1 = 0; + + /* Check the parameters */ + assert_param(IS_DFSDM_CLOCK_OUT_DIVIDER(DFSDM_ClkOutDivision)); + + /* Get the DFSDM_Channel0 CHCFGR1 value */ + tmpreg1 = DFSDM1_Channel0 -> CHCFGR1; + + /* Clear the CKOUTDIV bits */ + tmpreg1 &= (uint32_t)(~DFSDM_CHCFGR1_CKOUTDIV); + + /* Set or Reset the CKOUTDIV bits */ + tmpreg1 |= (uint32_t)((DFSDM_ClkOutDivision - 1) << 16); + + /* Write to DFSDM Channel0 CHCFGR1 */ + DFSDM1_Channel0 -> CHCFGR1 = tmpreg1; +} + +/** + * @brief Configures the Output serial clock source. + * @param DFSDM_ClkOutSource: Defines the divider for the output serial clock + * This parameter can be a value of: + * @arg DFSDM_ClkOutSource_SysClock + * @arg DFSDM_ClkOutSource_AudioClock + * @retval None + */ +void DFSDM_ConfigClkOutputSource(uint32_t DFSDM_ClkOutSource) +{ + uint32_t tmpreg1 = 0; + + /* Check the parameters */ + assert_param(IS_DFSDM_CLOCK_OUT_SOURCE(DFSDM_ClkOutSource)); + + /* Get the DFSDM_Channel0 CHCFGR1 value */ + tmpreg1 = DFSDM1_Channel0 -> CHCFGR1; + + /* Clear the CKOUTSRC bit */ + tmpreg1 &= ~(DFSDM_CHCFGR1_CKOUTSRC); + + /* Set or Reset the CKOUTSRC bit */ + tmpreg1 |= DFSDM_ClkOutSource; + + /* Write to DFSDM Channel0 CHCFGR1 */ + DFSDM1_Channel0 -> CHCFGR1 = tmpreg1; +} + +/** + * @brief Enables or disables the specified Break_i siganl to the specified DFSDM_Channelx. + * @param DFSDM_Channelx: where x can be a value from 0 to 7 to select the DFSDM Channel. + * @param DFSDM_SCDBreak_i: where i can be a value from 0 to 3 to select the specified Break signal. + * @param NewState: new state of the selected DFSDM_SCDBreak_i. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DFSDM_ConfigBRKAnalogWatchDog(DFSDM_Channel_TypeDef* DFSDM_Channelx, uint32_t DFSDM_SCDBreak_i, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_CHANNEL(DFSDM_Channelx)); + assert_param(IS_DFSDM_SCD_BREAK_SIGNAL(DFSDM_SCDBreak_i)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the BKSCD[i] bit */ + DFSDM_Channelx -> CHAWSCDR |= DFSDM_SCDBreak_i; + } + else + { + /* Reset the BKSCD[i] bit */ + DFSDM_Channelx -> CHAWSCDR &= ~(DFSDM_SCDBreak_i); + } +} + +/** + * @brief Enables or disables the specified Break_i siganl to the specified DFSDM_Channelx. + * @param DFSDM_Channelx: where x can be a value from 0 to 7 to select the DFSDM Channel. + * @param DFSDM_SCDBreak_i: where i can be a value from 0 to 3 to select the specified Break signal. + * @param NewState: new state of the selected DFSDM_SCDBreak_i. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DFSDM_ConfigBRKShortCircuitDetector(DFSDM_Channel_TypeDef* DFSDM_Channelx, uint32_t DFSDM_SCDBreak_i, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_CHANNEL(DFSDM_Channelx)); + assert_param(IS_DFSDM_SCD_BREAK_SIGNAL(DFSDM_SCDBreak_i)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the BKSCD[i] bit */ + DFSDM_Channelx -> CHAWSCDR |= DFSDM_SCDBreak_i; + } + else + { + /* Reset the BKSCD[i] bit */ + DFSDM_Channelx -> CHAWSCDR &= ~(DFSDM_SCDBreak_i); + } +} + +/** + * @brief Defines the threshold counter for the short circuit detector for the selected DFSDM_Channelx. + * @param DFSDM_Channelx: where x can be a value from 0 to 7 to select the DFSDM Channel. + * @param DFSDM_SCDThreshold: The threshold counter, this parameter can be a value between 0 and 255. + * @retval None + */ +void DFSDM_ConfigShortCircuitThreshold(DFSDM_Channel_TypeDef* DFSDM_Channelx, uint32_t DFSDM_SCDThreshold) +{ + uint32_t tmpreg1 = 0; + + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_CHANNEL(DFSDM_Channelx)); + assert_param(IS_DFSDM_CSD_THRESHOLD_VALUE(DFSDM_SCDThreshold)); + + /* Get the DFSDM_Channelx AWSCDR value */ + tmpreg1 = DFSDM_Channelx -> CHAWSCDR; + + /* Clear the SCDT bits */ + tmpreg1 &= ~(DFSDM_CHAWSCDR_SCDT); + + /* Set or Reset the SCDT bits */ + tmpreg1 |= DFSDM_SCDThreshold; + + /* Write to DFSDM Channelx AWSCDR */ + DFSDM_Channelx -> CHAWSCDR = tmpreg1; +} + +/** + * @brief Selects the channel to be guarded by the Analog watchdog for the selected DFSDMx, + * and select if the fast analog watchdog is enabled or not. + * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module. + * @param DFSDM_AWDChannelx: where x can be a value from 0 to 7 to select the DFSDM Channel. + * @param DFSDM_AWDFastMode: The analog watchdog fast mode. + * This parameter can be a value of @ref DFSDM_AWD_Fast_Mode_Selection. + * @retval None + */ +void DFSDM_ConfigAnalogWatchdog(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_AWDChannelx, uint32_t DFSDM_AWDFastMode) +{ + uint32_t tmpreg1 = 0; + uint32_t tmpreg2 = 0; + + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + assert_param(IS_DFSDM_AWD_CHANNEL(DFSDM_AWDChannelx)); + assert_param(IS_DFSDM_AWD_MODE(DFSDM_AWDFastMode)); + + /* Get the DFSDMx CR2 value */ + tmpreg1 = DFSDMx -> FLTCR2; + + /* Clear the AWDCH bits */ + tmpreg1 &= ~(DFSDM_FLTCR2_AWDCH); + + /* Set or Reset the AWDCH bits */ + tmpreg1 |= DFSDM_AWDChannelx; + + /* Write to DFSDMx CR2 Register */ + DFSDMx -> FLTCR2 |= tmpreg1; + + /* Get the DFSDMx CR1 value */ + tmpreg2 = DFSDMx->FLTCR1; + + /* Clear the AWFSEL bit */ + tmpreg2 &= ~(DFSDM_FLTCR1_AWFSEL); + + /* Set or Reset the AWFSEL bit */ + tmpreg2 |= DFSDM_AWDFastMode; + + /* Write to DFSDMx CR1 Register */ + DFSDMx->FLTCR1 = tmpreg2; +} + +/** + * @brief Selects the channel to be guarded by the Analog watchdog of the selected DFSDMx, and the mode to be used. + * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module. + * @param DFSDM_ExtremChannelx: where x can be a value from 0 to 7 to select the Channel to be connected + * to the Extremes detector. + * @retval None + */ +void DFSDM_SelectExtremesDetectorChannel(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_ExtremChannelx) +{ + uint32_t tmpreg1 = 0; + + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + assert_param(IS_DFSDM_EXTREM_CHANNEL(DFSDM_ExtremChannelx)); + + /* Get the DFSDMx CR2 value */ + tmpreg1 = DFSDMx -> FLTCR2; + + /* Clear the EXCH bits */ + tmpreg1 &= ~(DFSDM_FLTCR2_EXCH); + + /* Set or Reset the AWDCH bits */ + tmpreg1 |= DFSDM_ExtremChannelx; + + /* Write to DFSDMx CR2 Register */ + DFSDMx -> FLTCR2 = tmpreg1; +} + +/** + * @brief Returns the regular conversion data by the DFSDMx. + * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module. + * @retval The converted regular data. + * @note This function returns a signed value. + */ +int32_t DFSDM_GetRegularConversionData(DFSDM_TypeDef* DFSDMx) +{ + uint32_t reg = 0; + int32_t value = 0; + + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + + /* Get value of data register for regular channel */ + reg = DFSDMx -> FLTRDATAR; + + /* Extract conversion value */ + value = ((int32_t)((reg & 0xFFFFFF00) >> 8)); + + /* Return the conversion result */ + return value; +} + +/** + * @brief Returns the injected conversion data by the DFSDMx. + * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module. + * @retval The converted regular data. + * @note This function returns a signed value. + */ +int32_t DFSDM_GetInjectedConversionData(DFSDM_TypeDef* DFSDMx) +{ + uint32_t reg = 0; + int32_t value = 0; + + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + + /* Get value of data register for regular channel */ + reg = DFSDMx -> FLTJDATAR; + + /* Extract conversion value */ + value = ((int32_t)((reg & 0xFFFFFF00) >> 8)); + + /* Return the conversion result */ + return value; +} + +/** + * @brief Returns the highest value converted by the DFSDMx. + * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module. + * @retval The highest converted value. + * @note This function returns a signed value. + */ +int32_t DFSDM_GetMaxValue(DFSDM_TypeDef* DFSDMx) +{ + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + + /* Return the highest converted value */ + return (((int32_t)(DFSDMx -> FLTEXMAX)) >> 8); +} + +/** + * @brief Returns the lowest value converted by the DFSDMx. + * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module. + * @retval The lowest converted value. + * @note This function returns a signed value. + */ +int32_t DFSDM_GetMinValue(DFSDM_TypeDef* DFSDMx) +{ + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + + /* Return the lowest conversion value */ + return (((int32_t)(DFSDMx ->FLTEXMIN )) >> 8); +} + +/** + * @brief Returns the number of channel on which is captured the highest converted data by the DFSDMx. + * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module. + * @retval The highest converted value. + */ +int32_t DFSDM_GetMaxValueChannel(DFSDM_TypeDef* DFSDMx) +{ + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + + /* Return the highest converted value */ + return ((DFSDMx -> FLTEXMAX) & (~DFSDM_FLTEXMAX_EXMAXCH)); +} + +/** + * @brief Returns the number of channel on which is captured the lowest converted data by the DFSDMx. + * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module. + * @retval The lowest converted value. + */ +int32_t DFSDM_GetMinValueChannel(DFSDM_TypeDef* DFSDMx) +{ + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + + /* Return the lowest converted value */ + return ((DFSDMx -> FLTEXMIN) & (~DFSDM_FLTEXMIN_EXMINCH)); +} + +/** + * @brief Returns the conversion time (in 28-bit timer unit) for DFSDMx. + * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module. + * @retval Conversion time. + */ +uint32_t DFSDM_GetConversionTime(DFSDM_TypeDef* DFSDMx) +{ + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + + /* Return the lowest converted value */ + return ((DFSDMx -> FLTCNVTIMR >> 4) & 0x0FFFFFFF); +} + +/** + * @brief Configures Sinc Filter for the Analog watchdog by setting + * the Sinc filter order and the Oversampling ratio for the specified DFSDM_Channelx. + * @param DFSDM_Channelx: where x can be a value from 0 to 7 to select the DFSDM Channel. + * @param DFSDM_AWDSincOrder: The Sinc Filter order this parameter can be a value of @ref DFSDM_AWD_Sinc_Order. + * @param DFSDM_AWDSincOverSampleRatio: The Filter Oversampling ratio, this parameter can be a value between 1 and 32. + * @retval None + */ +void DFSDM_ConfigAWDFilter(DFSDM_Channel_TypeDef* DFSDM_Channelx, uint32_t DFSDM_AWDSincOrder, uint32_t DFSDM_AWDSincOverSampleRatio) +{ + uint32_t tmpreg1 = 0; + + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_CHANNEL(DFSDM_Channelx)); + assert_param(IS_DFSDM_AWD_SINC_ORDER(DFSDM_AWDSincOrder)); + assert_param(IS_DFSDM_AWD_OVRSMPL_RATIO(DFSDM_AWDSincOverSampleRatio)); + + /* Get the DFSDM_Channelx CHAWSCDR value */ + tmpreg1 = DFSDM_Channelx -> CHAWSCDR; + + /* Clear the FORD and FOSR bits */ + tmpreg1 &= ~(DFSDM_CHAWSCDR_AWFORD | DFSDM_CHAWSCDR_AWFOSR); + + /* Set or Reset the SCDT bits */ + tmpreg1 |= (DFSDM_AWDSincOrder | ((DFSDM_AWDSincOverSampleRatio -1) << 16)) ; + + /* Write to DFSDM Channelx CHAWSCDR */ + DFSDM_Channelx -> CHAWSCDR = tmpreg1; +} + +/** + * @brief Returns the last Analog Watchdog Filter conversion result data for channelx. + * @param DFSDM_Channelx: where x can be a value from 0 to 7 to select the DFSDM Channel. + * @retval The Data conversion value. + */ +uint32_t DFSDM_GetAWDConversionValue(DFSDM_Channel_TypeDef* DFSDM_Channelx) +{ + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_CHANNEL(DFSDM_Channelx)); + + /* Return the last analog watchdog filter conversion value */ + return DFSDM_Channelx -> CHWDATAR; +} + + +/** + * @brief Configures the High Threshold and the Low threshold for the Analog watchdog of the selected DFSDMx. + * @param DFSDM_HighThreshold: High threshold value. This parameter can be value between 0 and 0xFFFFFF. + * @param DFSDM_LowThreshold: Low threshold value. This parameter can be value between 0 and 0xFFFFFF. + * @retval None. + * @note In case of channels transceivers monitoring (Analog Watchdog fast mode Enabled)), + * only the higher 16 bits define the 16-bit threshold compared with analog watchdog filter output. + */ + +void DFSDM_SetAWDThreshold(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_HighThreshold, uint32_t DFSDM_LowThreshold) +{ + uint32_t tmpreg1 = 0; + uint32_t tmpreg2 = 0; + + /* Check the parameters */ + assert_param(IS_DFSDM_HIGH_THRESHOLD(DFSDM_HighThreshold)); + assert_param(IS_DFSDM_LOW_THRESHOLD(DFSDM_LowThreshold)); + + /* Get the DFSDMx AWHTR value */ + tmpreg1 = DFSDMx -> FLTAWHTR; + + /* Clear the AWHT bits */ + tmpreg1 &= ~(DFSDM_FLTAWHTR_AWHT); + + /* Set or Reset the AWHT bits */ + tmpreg1 |= (DFSDM_HighThreshold << 8 ); + + /* Write to DFSDMx AWHTR Register */ + DFSDMx -> FLTAWHTR = tmpreg1; + + /* Get the DFSDMx AWLTR value */ + tmpreg2 = DFSDMx -> FLTAWLTR; + + /* Clear the AWLTR bits */ + tmpreg2 &= ~(DFSDM_FLTAWLTR_AWLT); + + /* Set or Reset the AWLTR bits */ + tmpreg2 |= (DFSDM_LowThreshold << 8 ); + + /* Write to DFSDMx AWLTR Register */ + DFSDMx -> FLTAWLTR = tmpreg2; +} + +/** + * @brief Selects the injected channel for the selected DFSDMx. + * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module. + * @param DFSDM_InjectedChannelx: where x can be a value from 0 to 7 to select the Channel to be configuraed as + * injected channel. + * @retval None + * @note User can select up to 8 channels. + */ +void DFSDM_SelectInjectedChannel(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_InjectedChannelx) +{ + uint32_t tmpreg1 = 0; + + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + assert_param(IS_DFSDM_INJECT_CHANNEL(DFSDM_InjectedChannelx)); + + /* Get the DFSDMx JCHGR value */ + tmpreg1 = DFSDMx -> FLTJCHGR; + + /* Clear the JCHGR bits */ + tmpreg1 &= ~(DFSDM_FLTJCHGR_JCHG); + + /* Set or Reset the JCHGR bits */ + tmpreg1 |= DFSDM_InjectedChannelx; + + /* Write to DFSDMx JCHGR Register */ + DFSDMx -> FLTJCHGR |= tmpreg1; +} + +/** + * @brief Selects the regular channel for the selected DFSDMx. + * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module. + * @param DFSDM_RegularChannelx: where x can be a value from 0 to 7 to select the Channel to be configurated as + * regular channel. + * @retval None + * @note User can select only one channel. + */ +void DFSDM_SelectRegularChannel(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_RegularChannelx) +{ + uint32_t tmpreg1 = 0; + + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + assert_param(IS_DFSDM_REGULAR_CHANNEL(DFSDM_RegularChannelx)); + + /* Get the DFSDMx CR1 value */ + tmpreg1 = DFSDMx -> FLTCR1; + + /* Clear the RCH bits */ + tmpreg1 &= ~(DFSDM_FLTCR1_RCH); + + /* Set or Reset the RCH bits */ + tmpreg1 |= DFSDM_RegularChannelx; + + /* Write to DFSDMx CR1 Register */ + DFSDMx -> FLTCR1 = tmpreg1; +} + +/** + * @brief Starts a software start for the injected group of channels of the selected DFSDMx. + * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module. + * @retval None + */ +void DFSDM_StartSoftwareInjectedConversion(DFSDM_TypeDef* DFSDMx) +{ + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + + /* Write 1 to DFSDMx CR1 RSWSTAR bit */ + DFSDMx -> FLTCR1 |= DFSDM_FLTCR1_JSWSTART; +} + +/** + * @brief Starts a software start of the regular channel of the selected DFSDMx. + * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module. + * @retval None + */ +void DFSDM_StartSoftwareRegularConversion(DFSDM_TypeDef* DFSDMx) +{ + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + + /* Write 1 to DFSDMx CR1 RSWSTAR bit */ + DFSDMx -> FLTCR1 |= DFSDM_FLTCR1_RSWSTART; +} + +/** + * @brief Selects the Trigger signal to launch the injected conversions of the selected DFSDMx. + * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module. + * @param DFSDM_InjectedTrigger: the trigger signal. + * This parameter can be a value of: @ref DFSDM_Injected_Trigger_signal + * @param DFSDM_TriggerEdge: the edge of the selected trigger + * This parameter can be a value of: @ref DFSDM_Trigger_Edge_selection + * @retval None. + * @note This function can be used only when the filter is disabled, use DFSDM_FilterCmd() + * to disable the filter. + */ +void DFSDM_ConfigInjectedTrigger(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_Trigger, uint32_t DFSDM_TriggerEdge) +{ + uint32_t tmpreg1 = 0; + + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + + if (DFSDMx == DFSDM0) + { + assert_param(IS_DFSDM0_INJ_TRIGGER(DFSDM_Trigger)); + } + else + { + assert_param(IS_DFSDM1_INJ_TRIGGER(DFSDM_Trigger)); + } + + assert_param(IS_DFSDM_TRIGGER_EDGE(DFSDM_TriggerEdge)); + + /* Get the DFSDMx CR1 value */ + tmpreg1 = DFSDMx -> FLTCR1; + + /* Clear the JEXTSEL & JEXTEN bits */ + tmpreg1 &= ~(DFSDM_FLTCR1_JEXTSEL | DFSDM_FLTCR1_JEXTEN); + + /* Set or Reset the JEXTSEL & JEXTEN bits */ + tmpreg1 |= (DFSDM_Trigger | DFSDM_TriggerEdge); + + /* Write to DFSDMx CR1 Register */ + DFSDMx -> FLTCR1 = tmpreg1; +} + +/** + * @brief Starts an injected conversion synchronously when in DFSDM0 + * an injected conversion started by software. + * @param DFSDMx: where x can be 0 or 1 to select the DFSDM Module. + * @retval None + * @note This function can be used only when the filter is disabled, use DFSDM_FilterCmd() + * to disable the filter. + */ +void DFSDM_SynchronousFilter0InjectedStart(DFSDM_TypeDef* DFSDMx) +{ + /* Check the parameters */ + assert_param(IS_DFSDM_SYNC_FILTER(DFSDMx)); + + /* Write 1 to DFSDMx CR1 JSYNC bit */ + DFSDMx -> FLTCR1 |= DFSDM_FLTCR1_JSYNC; +} + +/** + * @brief Starts a regular conversion synchronously when in DFSDM0 + * a regular conversion started by software. + * @param DFSDMx: where x can be 0 or 1 to select the DFSDM Module. + * @retval None + * @note This function can be used only when the filter is disabled, use DFSDM_FilterCmd() + * to disable the filter. + */ +void DFSDM_SynchronousFilter0RegularStart(DFSDM_TypeDef* DFSDMx) +{ + /* Check the parameters */ + assert_param(IS_DFSDM_SYNC_FILTER(DFSDMx)); + + /* Write 1 to DFSDMx CR1 RSYNC bit */ + DFSDMx -> FLTCR1 |= DFSDM_FLTCR1_RSYNC; +} + +/** + * @brief Enables or Disables the continue mode for Regular conversion for the selected filter DFSDMx. + * @param DFSDMx: where x can be 0 or 1 to select the DFSDM Module. + * @param NewState: new state of the Continuous mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DFSDM_RegularContinuousModeCmd(DFSDM_TypeDef* DFSDMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the RCONT bit */ + DFSDMx -> FLTCR1 |= DFSDM_FLTCR1_RCONT; + } + else + { + /* Disable the RCONT bit */ + DFSDMx -> FLTCR1 &= ~(DFSDM_FLTCR1_RCONT); + } +} + +/** + * @brief Enables or Disables the Fast mode for the selected filter DFSDMx. + * @param DFSDMx: where x can be 0 or 1 to select the DFSDM Module. + * @param NewState: new state of the Fast mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + * @note If just a single channel is selected in continuous mode (either by executing a regular + * conversion or by executing a injected conversion with only one channel selected), + * the sampling rate can be increased several times by enabling the fast mode. + * @note This function can be used only when the filter is disabled, use DFSDM_FilterCmd() + * to disable the filter. + */ +void DFSDM_FastModeCmd(DFSDM_TypeDef* DFSDMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the FAST bit */ + DFSDMx -> FLTCR1 |= DFSDM_FLTCR1_FAST; + } + else + { + /* Disable the FAST bit */ + DFSDMx -> FLTCR1 &= ~(DFSDM_FLTCR1_FAST); + } +} + +/** + * @brief Selects the injected conversions mode for the selected DFSDMx. + * Injected conversions can operates in Single mode or Scan mode. + * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module. + * @param DFSDM_InjectConvMode: The injected conversion mode, this parameter can be: + * @arg DFSDM_InjectConvMode_Single + * @arg DFSDM_InjectConvMode_Scan + * @retval None. + * @note This function can be used only when the filter is disabled, use DFSDM_FilterCmd() + * to disable the filter. + */ +void DFSDM_SelectInjectedConversionMode(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_InjectConvMode) +{ + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + assert_param(IS_DFSDM_INJ_CONV_MODE(DFSDM_InjectConvMode)); + + /* Clear the JSCAN bit */ + DFSDMx -> FLTCR1 &= ~(DFSDM_FLTCR1_JSCAN); + + /* Write to DFSDMx CR1 Register */ + DFSDMx -> FLTCR1 |= DFSDM_InjectConvMode; +} + +/** + * @brief Enables or Disables the DMA to read data for the injected channel group of the selected filter DFSDMx. + * @param DFSDMx: where x can be 0 or 1 to select the DFSDM Module. + * @param DFSDM_DMAConversionMode: Selects the mode to be configured for DMA read . + * @arg DFSDM_DMAConversionMode_Regular: DMA channel Enabled/Disabled to read data for the regular conversion + * @arg DFSDM_DMAConversionMode_Injected: DMA channel Enabled/Disabled to read data for the Injected conversion +* @param NewState: new state of the DMA channel. + * This parameter can be: ENABLE or DISABLE. + * @retval None. + * @note This function can be used only when the filter is disabled, use DFSDM_FilterCmd() + * to disable the filter. + */ +void DFSDM_DMATransferConfig(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_DMAConversionMode, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + assert_param(IS_DFSDM_CONVERSION_MODE(DFSDM_DMAConversionMode)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the JDMAEN or RDMAEN bit */ + DFSDMx -> FLTCR1 |= (DFSDM_FLTCR1_JDMAEN << DFSDM_DMAConversionMode) ; + } + else + { + /* Disable the JDMAEN or RDMAEN bit */ + DFSDMx -> FLTCR1 &= ~(DFSDM_FLTCR1_JDMAEN << DFSDM_DMAConversionMode); + } +} + +/** @defgroup DFSDM_Group3 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + Interrupts and flags management functions + =============================================================================== + This section provides functions allowing to configure the DFSDM Interrupts, get + the status and clear flags bits. + + The LPT provides 7 Flags and Interrupts sources (2 flags and Interrupt sources + are available only on LPT peripherals equipped with encoder mode interface) + + Flags and Interrupts sources: + ============================= + 1. End of injected conversion. + 2. End of regular conversion. + 3. Injected data overrun. + 4. Regular data overrun. + 5. Analog watchdog. + 6. Short circuit detector. + 7. Channel clock absence + + - To enable a specific interrupt source, use "DFSDM_ITConfig", + "DFSDM_ITClockAbsenceCmd" and "DFSDM_ITShortCircuitDetectorCmd" functions. + - To check if an interrupt was occurred, call "DFSDM_GetITStatus","DFSDM_GetClockAbsenceITStatusfunction" + and "DFSDM_GetGetShortCircuitITStatus" functions and read returned values. + - To get a flag status, call the "DFSDM_GetFlagStatus" ,"DFSDM_GetClockAbsenceFlagStatus" ,"DFSDM_GetShortCircuitFlagStatus" + and "DFSDM_GetWatchdogFlagStatus" functions and read the returned value. + - To clear a flag or an interrupt, use DFSDM_ClearFlag,DFSDM_ClearClockAbsenceFlag, + DFSDM_ClearShortCircuitFlag,DFSDM_ClearAnalogWatchdogFlag functions with the + corresponding flag (interrupt). + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified DFSDMx interrupts. + * @param DFSDMx: where x can be 0 or 1 to select the DFSDM peripheral. + * @param DFSDM_IT: specifies the DFSDM interrupts sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg DFSDM_IT_JEOC: End of injected conversion Interrupt source + * @arg DFSDM_IT_REOC: End of regular conversion Interrupt source + * @arg DFSDM_IT_JOVR: Injected data overrun Interrupt source + * @arg DFSDM_IT_ROVR: Regular data overrun Interrupt source + * @arg DFSDM_IT_AWD : Analog watchdog Interrupt source + * @param NewState: new state of the DFSDM interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DFSDM_ITConfig(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_IT, FunctionalState NewState) + { + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + assert_param(IS_DFSDM_IT(DFSDM_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the Interrupt sources */ + DFSDMx->FLTCR2 |= DFSDM_IT; + } + else + { + /* Disable the Interrupt sources */ + DFSDMx->FLTCR2 &= ~(DFSDM_IT); + } +} + +/** + * @brief Enables or disables the Clock Absence Interrupt. + * @param NewState: new state of the interrupt. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DFSDM_ITClockAbsenceCmd(FunctionalState NewState) + { + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the Interrupt source */ + DFSDM0->FLTCR2 |= DFSDM_IT_CKAB; + } + else + { + /* Disable the Interrupt source */ + DFSDM0->FLTCR2 &= ~(DFSDM_IT_CKAB); + } +} + +/** + * @brief Enables or disables the Short Circuit Detector Interrupt. + * @param NewState: new state of the interrupt. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DFSDM_ITShortCircuitDetectorCmd(FunctionalState NewState) + { + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the Interrupt source */ + DFSDM0->FLTCR2 |= DFSDM_IT_SCD; + } + else + { + /* Disable the Interrupt source */ + DFSDM0->FLTCR2 &= ~(DFSDM_IT_SCD); + } +} + +/** + * @brief Checks whether the specified DFSDM flag is set or not. + * @param DFSDMx: where x can be 0 or 1 to select the DFSDM peripheral. + * @param LPT_FLAG: specifies the flag to check. + * This parameter can be any combination of the following values: + * @arg DFSDM_FLAG_JEOC: End of injected conversion Flag + * @arg DFSDM_FLAG_REOC: End of regular conversion Flag + * @arg DFSDM_FLAG_JOVR: Injected data overrun Flag + * @arg DFSDM_FLAG_ROVR: Regular data overrun Flag + * @arg DFSDM_FLAG_AWD: Analog watchdog Flag + * @arg DFSDM_FLAG_JCIP: Injected conversion in progress status + * @arg DFSDM_FLAG_RCIP: Regular conversion in progress status + * @retval None + */ +FlagStatus DFSDM_GetFlagStatus(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_FLAG) +{ + ITStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + assert_param(IS_DFSDM_FLAG(DFSDM_FLAG)); + + if ((DFSDMx->FLTISR & DFSDM_FLAG) != RESET ) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Checks whether the specified Clock Absence Channel flag is set or not. + * @param DFSDM_FLAG_CLKAbsence: specifies the flag to check. + * This parameter can be a value of @ref DFSDM_Clock_Absence_Flag_Definition + * @retval None + */ +FlagStatus DFSDM_GetClockAbsenceFlagStatus(uint32_t DFSDM_FLAG_CLKAbsence) +{ + ITStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_DFSDM_CLK_ABS_FLAG(DFSDM_FLAG_CLKAbsence)); + + if ((DFSDM0->FLTISR & DFSDM_FLAG_CLKAbsence) != RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Checks whether the specified Short Circuit Channel Detector flag is set or not. + * @param DFSDM_FLAG_SCD: specifies the flag to check. + * This parameter can be a value of @ref DFSDM_SCD_Flag_Definition + * @retval None + */ +FlagStatus DFSDM_GetShortCircuitFlagStatus(uint32_t DFSDM_FLAG_SCD) +{ + ITStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_DFSDM_SCD_FLAG(DFSDM_FLAG_SCD)); + + if ((DFSDM0->FLTISR & DFSDM_FLAG_SCD) != RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Checks whether the specified Watchdog threshold flag is set or not. + * @param DFSDMx: where x can be 0 or 1 to select the DFSDM peripheral. + * @param DFSDM_AWDChannelx: where x can be a value from 0 to 7 to select the DFSDM Channel. + * @param DFSDM_Threshold: specifies the Threshold. + * This parameter can be a value of @ref DFSDM_Threshold_Selection. + * @retval None + */ +FlagStatus DFSDM_GetWatchdogFlagStatus(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_AWDChannelx, uint8_t DFSDM_Threshold) +{ + ITStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + assert_param(IS_DFSDM_Threshold(DFSDM_Threshold)); + assert_param(IS_DFSDM_AWD_CHANNEL(DFSDM_AWDChannelx)); + + if ((DFSDMx->FLTAWSR & ((DFSDM_AWDChannelx >> 16) << DFSDM_Threshold) ) != RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the DFSDMx's pending flag. + * @param DFSDMx: where x can be 0 or 1 to select the DFSDM peripheral. + * @param DFSDM_CLEARF: specifies the pending bit to clear. + * This parameter can be any combination of the following values: + * @arg DFSDM_CLEARF_JOVR: Injected data overrun Clear Flag + * @arg DFSDM_CLEARF_ROVR: Regular data overrun Clear Flag + * @retval None + */ +void DFSDM_ClearFlag(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_CLEARF) +{ + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + assert_param(IS_DFSDM_CLEAR_FLAG(DFSDM_CLEARF)); + + /* Clear the pending Flag Bit */ + DFSDMx->FLTICR |= DFSDM_CLEARF; +} + +/** + * @brief Clears the DFSDMx's pending Clock Absence Channel flag. + * @param DFSDM_CLEARF_CLKAbsence: specifies the pending bit to clear. + * This parameter can be any combination of @ref DFSDM_Clear_ClockAbs_Flag_Definition + * @retval None + */ +void DFSDM_ClearClockAbsenceFlag(uint32_t DFSDM_CLEARF_CLKAbsence) +{ + /* Check the parameters */ + assert_param(IS_DFSDM_CLK_ABS_CLEARF(DFSDM_CLEARF_CLKAbsence)); + + /* Clear the IT pending Flag Bit */ + DFSDM0->FLTICR |= DFSDM_CLEARF_CLKAbsence; +} + +/** + * @brief Clears the DFSDMx's pending Short circuit Channel flag. + * @param DFSDM_CLEARF_SCD: specifies the pending bit to clear. + * This parameter can be any combination of @ref DFSDM_Clear_Short_Circuit_Flag_Definition + * @retval None + */ +void DFSDM_ClearShortCircuitFlag(uint32_t DFSDM_CLEARF_SCD) +{ + /* Check the parameters */ + assert_param(IS_DFSDM_SCD_CHANNEL_FLAG(DFSDM_CLEARF_SCD)); + + /* Clear the pending Flag Bit */ + DFSDM0->FLTICR |= DFSDM_CLEARF_SCD; +} + +/** + * @brief Clears the DFSDMx's pending Analog watchdog Channel flag. + * @param DFSDMx: where x can be 0 or 1 to select the DFSDM peripheral. + * @param DFSDM_AWDChannelx: where x can be a value from 0 to 7 to select the DFSDM Channel. + * @param DFSDM_Threshold: specifies the Threshold. + * This parameter can be a value of @ref DFSDM_Threshold_Selection. + * @retval None + */ +void DFSDM_ClearAnalogWatchdogFlag(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_AWDChannelx, uint8_t DFSDM_Threshold) +{ + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + assert_param(IS_DFSDM_Threshold(DFSDM_Threshold)); + assert_param(IS_DFSDM_AWD_CHANNEL(DFSDM_AWDChannelx)); + + if ((DFSDMx->FLTAWSR & ((DFSDM_AWDChannelx >> 16) << DFSDM_Threshold) ) != RESET) + + /* Clear the pending Flag Bit */ + DFSDMx->FLTAWCFR |= (DFSDM_AWDChannelx >> 16) << DFSDM_Threshold; +} + +/** + * @brief Check whether the specified DFSDM interrupt has occurred or not. + * @param DFSDMx: where x can be 0 or 1 to select the DFSDM peripheral. + * @param DFSDM_IT: specifies the DFSDM interrupt source to check. + * @arg DFSDM_IT_JEOC: End of injected conversion Interrupt source + * @arg DFSDM_IT_REOC: End of regular conversion Interrupt source + * @arg DFSDM_IT_JOVR: Injected data overrun Interrupt source + * @arg DFSDM_IT_ROVR: Regular data overrun Interrupt source + * @arg DFSDM_IT_AWD : Analog watchdog Interrupt source + * @retval The new state of DFSDM_IT (SET or RESET). + */ +ITStatus DFSDM_GetITStatus(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_IT) +{ + ITStatus bitstatus = RESET; + uint32_t itstatus = 0x0, itenable = 0x0; + + /* Check the parameters */ + assert_param(IS_DFSDM_ALL_FILTER(DFSDMx)); + assert_param(IS_DFSDM_IT(DFSDM_IT)); + + /* Get the Interrupt Status bit value */ + itstatus = DFSDMx->FLTISR & DFSDM_IT; + + /* Check if the Interrupt is enabled */ + itenable = DFSDMx->FLTCR2 & DFSDM_IT; + + if ((itstatus != RESET) && (itenable != RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Check whether the specified Clock Absence channel interrupt has occurred or not. + * @param DFSDM_IT_CLKAbsence: specifies on which channel check the interrupt source. + * This parameter can be a value of @ref DFSDM_Clock_Absence_Interrupt_Definition. + * @retval The new state of DFSDM_IT (SET or RESET). + * @note Clock absence interrupt is handled only by DFSDM0. + */ +ITStatus DFSDM_GetClockAbsenceITStatus(uint32_t DFSDM_IT_CLKAbsence) +{ + ITStatus bitstatus = RESET; + uint32_t itstatus = 0x0, itenable = 0x0; + + /* Check the parameters */ + assert_param(IS_DFSDM_CLK_ABS_IT(DFSDM_IT_CLKAbsence)); + + /* Get the Interrupt Status bit value */ + itstatus = DFSDM0->FLTISR & DFSDM_IT_CLKAbsence; + + /* Check if the Interrupt is enabled */ + itenable = DFSDM0->FLTCR2 & DFSDM_IT_CKAB; + + if ((itstatus != RESET) && (itenable != RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Check whether the specified Short Circuit channel interrupt has occurred or not. + * @param DFSDM_IT_SCR: specifies on which channel check the interrupt source. + * This parameter can be a value of @ref DFSDM_SCD_Interrupt_Definition. + * @retval The new state of DFSDM_IT (SET or RESET). + * @note Short circuit interrupt is handled only by DFSDM0. + */ +ITStatus DFSDM_GetGetShortCircuitITStatus(uint32_t DFSDM_IT_SCR) +{ + ITStatus bitstatus = RESET; + uint32_t itstatus = 0x0, itenable = 0x0; + + /* Check the parameters */ + assert_param(IS_DFSDM_SCD_IT(DFSDM_IT_SCR)); + + /* Get the Interrupt Status bit value */ + itstatus = DFSDM0->FLTISR & DFSDM_IT_SCR; + + /* Check if the Interrupt is enabled */ + itenable = DFSDM0->FLTCR2 & DFSDM_IT_SCD; + + if ((itstatus != RESET) && (itenable != RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @} + */ + +/** + * @} + */ +#endif /* STM32F412xG */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dma.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dma.c index f0d455f5c8..c87e7904ad 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dma.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dma.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_dma.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Direct Memory Access controller (DMA): * + Initialization and Configuration @@ -103,7 +103,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dma2d.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dma2d.c index 0fe0810ef5..4ade37326b 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dma2d.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dma2d.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_dma2d.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the DMA2D controller (DMA2D) peripheral: * + Initialization and configuration @@ -37,7 +37,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dsi.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dsi.c index c69f21e984..b10e6da904 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dsi.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dsi.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_dsi.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Display Serial Interface (DSI): * + Initialization and Configuration @@ -23,7 +23,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_exti.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_exti.c index 0eab72e9d8..d929c80a3b 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_exti.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_exti.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_exti.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the EXTI peripheral: * + Initialization and Configuration @@ -47,7 +47,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_flash.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_flash.c index b20a3562e9..dd5d577205 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_flash.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_flash.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_flash.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the FLASH peripheral: * + FLASH Interface configuration @@ -51,7 +51,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -266,8 +266,8 @@ * @arg FLASH_Latency_14: FLASH Fourteen Latency cycles * @arg FLASH_Latency_15: FLASH Fifteen Latency cycles * - * @note For STM32F405xx/407xx, STM32F415xx/417xx and STM32F401xx/411xE devices this parameter - * can be a value between FLASH_Latency_0 and FLASH_Latency_7. + * @note For STM32F405xx/407xx, STM32F415xx/417xx, STM32F401xx/411xE and STM32F412xG devices + * this parameter can be a value between FLASH_Latency_0 and FLASH_Latency_7. * * @note For STM32F42xxx/43xxx devices this parameter can be a value between * FLASH_Latency_0 and FLASH_Latency_15. @@ -449,7 +449,7 @@ void FLASH_Lock(void) * For STM32F401xx devices this parameter can be a value between * FLASH_Sector_0 and FLASH_Sector_5. * - * For STM32F411xE devices this parameter can be a value between + * For STM32F411xE and STM32F412xG devices this parameter can be a value between * FLASH_Sector_0 and FLASH_Sector_7. * * For STM32F410xx devices this parameter can be a value between @@ -565,7 +565,7 @@ FLASH_Status FLASH_EraseAllSectors(uint8_t VoltageRange) if(status == FLASH_COMPLETE) { /* if the previous operation is completed, proceed to erase all sectors */ -#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx) +#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx) FLASH->CR &= CR_PSIZE_MASK; FLASH->CR |= tmp_psize; FLASH->CR |= (FLASH_CR_MER1 | FLASH_CR_MER2); @@ -578,7 +578,7 @@ FLASH_Status FLASH_EraseAllSectors(uint8_t VoltageRange) FLASH->CR &= ~(FLASH_CR_MER1 | FLASH_CR_MER2); #endif /* STM32F427_437xx || STM32F429_439xx || STM32F469_479xx */ -#if defined(STM32F40_41xxx) || defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE) || defined(STM32F446xx) +#if defined(STM32F40_41xxx) || defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE) || defined(STM32F412xG) || defined(STM32F446xx) FLASH->CR &= CR_PSIZE_MASK; FLASH->CR |= tmp_psize; FLASH->CR |= FLASH_CR_MER; @@ -589,7 +589,7 @@ FLASH_Status FLASH_EraseAllSectors(uint8_t VoltageRange) /* if the erase operation is completed, disable the MER Bit */ FLASH->CR &= (~FLASH_CR_MER); -#endif /* STM32F40_41xxx || STM32F401xx || STM32F410xx || STM32F411xE || STM32F446xx */ +#endif /* STM32F40_41xxx || STM32F401xx || STM32F410xx || STM32F411xE || STM32F412xG || STM32F446xx */ } /* Return the Erase Status */ @@ -1116,7 +1116,8 @@ void FLASH_OB_PCROPSelectionConfig(uint8_t OB_PcROP) * @brief Enables or disables the read/write protection (PCROP) of the desired * sectors, for the first 1 MB of the Flash. * - * @note This function can be used only for STM32F42xxx/43xxx and STM32F401xx/411xE devices. + * @note This function can be used only for STM32F42xxx/43xxx , STM32F401xx/411xE + * and STM32F412xG devices. * * @param OB_PCROP: specifies the sector(s) to be read/write protected or unprotected. * This parameter can be one of the following values: diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_flash_ramfunc.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_flash_ramfunc.c index 2d28307474..5ff1e80706 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_flash_ramfunc.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_flash_ramfunc.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_flash_ramfunc.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief FLASH RAMFUNC module driver. * This file provides a FLASH firmware functions which should be * executed from internal SRAM @@ -37,7 +37,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_fmc.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_fmc.c index 246a357381..3a346ba9e9 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_fmc.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_fmc.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_fmc.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the FMC peripheral: * + Interface with SRAM, PSRAM, NOR and OneNAND memories @@ -15,7 +15,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -232,13 +232,13 @@ void FMC_NORSRAMInit(FMC_NORSRAMInitTypeDef* FMC_NORSRAMInitStruct) /* NOR/SRAM Bank timing register configuration */ FMC_Bank1->BTCR[FMC_NORSRAMInitStruct->FMC_Bank+1] = - (uint32_t)(FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_AddressSetupTime | + (uint32_t)FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_AddressSetupTime | (FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_AddressHoldTime << 4) | (FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_DataSetupTime << 8) | (FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_BusTurnAroundDuration << 16) | (FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_CLKDivision << 20) | (FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_DataLatency << 24) | - FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_AccessMode); + FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_AccessMode; /* NOR/SRAM Bank timing register for write configuration, if extended mode is used */ if(FMC_NORSRAMInitStruct->FMC_ExtendedMode == FMC_ExtendedMode_Enable) @@ -248,7 +248,7 @@ void FMC_NORSRAMInit(FMC_NORSRAMInitTypeDef* FMC_NORSRAMInitStruct) assert_param(IS_FMC_DATASETUP_TIME(FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_DataSetupTime)); assert_param(IS_FMC_TURNAROUND_TIME(FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_BusTurnAroundDuration)); assert_param(IS_FMC_ACCESS_MODE(FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_AccessMode)); - + /* Get the BWTR register value */ tmpbwr = FMC_Bank1E->BWTR[FMC_NORSRAMInitStruct->FMC_Bank]; diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_fmpi2c.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_fmpi2c.c index 26bd4fb116..46c1cf7513 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_fmpi2c.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_fmpi2c.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_fmpi2c.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Inter-Integrated circuit Fast Mode Plus (FMPI2C): * + Initialization and Configuration @@ -58,7 +58,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -79,15 +79,15 @@ #include "stm32f4xx_fmpi2c.h" #include "stm32f4xx_rcc.h" -/** @addtogroup STM32F40x_StdPeriph_Driver +/** @addtogroup STM32F4xx_StdPeriph_Driver * @{ */ -/** @defgroup FMPI2C +/** @defgroup FMPI2C FMPI2C * @brief FMPI2C driver modules * @{ */ -#if defined(STM32F410xx) || defined(STM32F446xx) +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) /* Private typedef -----------------------------------------------------------*/ /* Private define ------------------------------------------------------------*/ @@ -368,31 +368,6 @@ void FMPI2C_StretchClockCmd(FMPI2C_TypeDef* FMPI2Cx, FunctionalState NewState) } } -/** - * @brief Enables or disables FMPI2Cp from stop mode. - * @param FMPI2Cx: where x can be 1 to select the FMPI2C peripheral. - * @param NewState: new state of the FMPI2Cx stop mode. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void FMPI2C_StopModeCmd(FMPI2C_TypeDef* FMPI2Cx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FMPI2C_ALL_PERIPH(FMPI2Cx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - /* Enable wakeup from stop mode */ - FMPI2Cx->CR1 |= FMPI2C_CR1_WUPEN; - } - else - { - /* Disable wakeup from stop mode */ - FMPI2Cx->CR1 &= (uint32_t)~((uint32_t)FMPI2C_CR1_WUPEN); - } -} - /** * @brief Enables or disables the FMPI2C own address 2. * @param FMPI2Cx: where x can be 1 to select the FMPI2C peripheral. @@ -1566,7 +1541,7 @@ void FMPI2C_ClearITPendingBit(FMPI2C_TypeDef* FMPI2Cx, uint32_t FMPI2C_IT) /** * @} */ -#endif /* STM32F410xx || STM32F446xx */ +#endif /* STM32F410xx || STM32F412xG || STM32F446xx */ /** * @} diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_fsmc.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_fsmc.c index 54fa8784d3..08ca90de56 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_fsmc.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_fsmc.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_fsmc.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the FSMC peripheral: * + Interface with SRAM, PSRAM, NOR and OneNAND memories @@ -14,7 +14,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_gpio.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_gpio.c index 61d653a820..f15d839cf6 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_gpio.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_gpio.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_gpio.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the GPIO peripheral: * + Initialization and Configuration @@ -63,7 +63,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash.c index 3847e837c5..4d0f7f4fbc 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_hash.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the HASH / HMAC Processor (HASH) peripheral: * - Initialization and Configuration functions @@ -102,7 +102,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash_md5.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash_md5.c index 265d3217b4..ef2aa4c708 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash_md5.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash_md5.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_hash_md5.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides high level functions to compute the HASH MD5 and * HMAC MD5 Digest of an input message. * It uses the stm32f4xx_hash.c/.h drivers to access the STM32F4xx HASH @@ -26,7 +26,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash_sha1.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash_sha1.c index 01440fb8ad..8a7b39f17b 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash_sha1.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash_sha1.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_hash_sha1.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides high level functions to compute the HASH SHA1 and * HMAC SHA1 Digest of an input message. * It uses the stm32f4xx_hash.c/.h drivers to access the STM32F4xx HASH @@ -26,7 +26,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_i2c.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_i2c.c index 8159ac5d41..832322102b 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_i2c.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_i2c.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_i2c.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Inter-integrated circuit (I2C) * + Initialization and Configuration @@ -71,7 +71,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_iwdg.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_iwdg.c index cfce319d4e..352812e8ca 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_iwdg.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_iwdg.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_iwdg.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Independent watchdog (IWDG) peripheral: * + Prescaler and Counter configuration @@ -64,7 +64,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_lptim.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_lptim.c index 0926f081da..8566bf96de 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_lptim.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_lptim.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_lptim.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Low Power Timer (LPT) peripheral: * + Initialization functions. @@ -75,7 +75,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_ltdc.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_ltdc.c index c102dbd4e5..d2ead80bbb 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_ltdc.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_ltdc.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_ltdc.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the LTDC controller (LTDC) peripheral: * + Initialization and configuration @@ -55,7 +55,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_pwr.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_pwr.c index ea6e0ebd91..2b477fc56f 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_pwr.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_pwr.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_pwr.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Power Controller (PWR) peripheral: * + Backup Domain Access @@ -17,7 +17,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -89,7 +89,7 @@ #define CR_LPUDS_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (LPUDS_BitNumber * 4)) #endif /* STM32F427_437xx || STM32F429_439xx || STM32F446xx */ -#if defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE) +#if defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE) || defined(STM32F412xG) /* Alias word address of MRLVDS bit */ #define MRLVDS_BitNumber 0x0B #define CR_MRLVDS_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (MRLVDS_BitNumber * 4)) @@ -97,7 +97,7 @@ /* Alias word address of LPLVDS bit */ #define LPLVDS_BitNumber 0x0A #define CR_LPLVDS_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (LPLVDS_BitNumber * 4)) -#endif /* STM32F401xx || STM32F410xx || STM32F411xE */ +#endif /* STM32F401xx || STM32F410xx || STM32F411xE || STM32F412xG */ /* --- CSR Register ---*/ #if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE) || defined(STM32F469_479xx) @@ -107,18 +107,18 @@ #define CSR_EWUP_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (EWUP_BitNumber * 4)) #endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F410xx || STM32F411xE || STM32F469_479xx */ -#if defined(STM32F410xx) || defined(STM32F446xx) +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) /* Alias word address of EWUP2 bit */ #define CSR_OFFSET (PWR_OFFSET + 0x04) #define EWUP1_BitNumber 0x08 #define CSR_EWUP1_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (EWUP1_BitNumber * 4)) #define EWUP2_BitNumber 0x07 #define CSR_EWUP2_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (EWUP2_BitNumber * 4)) -#if defined(STM32F410xx) +#if defined(STM32F410xx) || defined(STM32F412xG) #define EWUP3_BitNumber 0x06 #define CSR_EWUP3_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (EWUP2_BitNumber * 4)) -#endif /* STM32F410xx */ -#endif /* STM32F410xx || STM32F446xx */ +#endif /* STM32F410xx || STM32F412xG */ +#endif /* STM32F410xx || STM32F412xG || STM32F446xx */ /* Alias word address of BRE bit */ #define BRE_BitNumber 0x09 @@ -297,14 +297,14 @@ void PWR_WakeUpPinCmd(FunctionalState NewState) } #endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F411xE */ -#if defined(STM32F410xx) || defined(STM32F446xx) +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) /** * @brief Enables or disables the WakeUp Pin functionality. * @param PWR_WakeUpPinx: specifies the WakeUp Pin. * This parameter can be one of the following values: * @arg PWR_WakeUp_Pin1: WKUP1 pin is used for wakeup from Standby mode. * @arg PWR_WakeUp_Pin2: WKUP2 pin is used for wakeup from Standby mode. - * @arg PWR_WakeUp_Pin3: WKUP3 pin is used for wakeup from Standby mode.(only for STM32F410xx) + * @arg PWR_WakeUp_Pin3: WKUP3 pin is used for wakeup from Standby mode.(only for STM32F410xx and STM32F412xG Devices) * @param NewState: new state of the WakeUp Pin functionality. * This parameter can be: ENABLE or DISABLE. * @retval None @@ -318,7 +318,7 @@ void PWR_WakeUpPinCmd(uint32_t PWR_WakeUpPinx, FunctionalState NewState) { *(__IO uint32_t *) CSR_EWUP1_BB = (uint32_t)NewState; } -#if defined(STM32F410xx) +#if defined(STM32F410xx)|| defined(STM32F412xG) else if(PWR_WakeUpPinx == PWR_WakeUp_Pin3) /* PWR_WakeUp_Pin3 */ { *(__IO uint32_t *) CSR_EWUP3_BB = (uint32_t)NewState; @@ -329,7 +329,7 @@ void PWR_WakeUpPinCmd(uint32_t PWR_WakeUpPinx, FunctionalState NewState) *(__IO uint32_t *) CSR_EWUP2_BB = (uint32_t)NewState; } } -#endif /* STM32F410xx || STM32F446xx */ +#endif /* STM32F410xx || STM32F412xG || STM32F446xx */ /** * @} @@ -589,11 +589,11 @@ void PWR_LowRegulatorUnderDriveCmd(FunctionalState NewState) } #endif /* STM32F427_437xx || STM32F429_439xx || STM32F446xx */ -#if defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE) +#if defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE) || defined(STM32F412xG) /** * @brief Enables or disables the Main Regulator low voltage mode. * - * @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx devices. + * @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx/STM32F412xG devices. * * @param NewState: new state of the Main Regulator Low Voltage mode. * This parameter can be: ENABLE or DISABLE. @@ -617,7 +617,7 @@ void PWR_MainRegulatorLowVoltageCmd(FunctionalState NewState) /** * @brief Enables or disables the Low Power Regulator low voltage mode. * - * @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx devices. + * @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx/STM32F412xG devices. * * @param NewState: new state of the Low Power Regulator Low Voltage mode. * This parameter can be: ENABLE or DISABLE. @@ -637,7 +637,7 @@ void PWR_LowRegulatorLowVoltageCmd(FunctionalState NewState) *(__IO uint32_t *) CR_LPLVDS_BB = (uint32_t)DISABLE; } } -#endif /* STM32F401xx || STM32F410xx || STM32F411xE */ +#endif /* STM32F401xx || STM32F410xx || STM32F411xE || STM32F412xG */ /** * @} @@ -1029,9 +1029,9 @@ void PWR_ClearFlag(uint32_t PWR_FLAG) } #endif /* STM32F427_437xx || STM32F429_439xx */ -#if defined (STM32F40_41xxx) || defined (STM32F401xx) || defined (STM32F410xx) || defined (STM32F411xE) +#if defined (STM32F40_41xxx) || defined (STM32F401xx) || defined (STM32F410xx) || defined (STM32F411xE) || defined(STM32F412xG) PWR->CR |= PWR_FLAG << 2; -#endif /* STM32F40_41xxx || STM32F401xx || STM32F410xx || STM32F411xE */ +#endif /* STM32F40_41xxx || STM32F401xx || STM32F410xx || STM32F411xE || STM32F412xG */ } /** diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_qspi.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_qspi.c index e97f5407c0..c116777c32 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_qspi.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_qspi.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_qspi.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Serial peripheral interface (QSPI): * + Initialization and Configuration @@ -61,7 +61,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -89,7 +89,7 @@ * @brief QSPI driver modules * @{ */ -#if defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx) /* Private typedef -----------------------------------------------------------*/ /* Private define ------------------------------------------------------------*/ #define QSPI_CR_CLEAR_MASK 0x00FFFFCF @@ -898,7 +898,7 @@ void QSPI_DualFlashMode_Cmd(FunctionalState NewState) /** * @} */ -#endif /* STM32F446xx || STM32F469_479xx */ +#endif /* STM32F412xG || STM32F446xx || STM32F469_479xx */ /** * @} diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rcc.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rcc.c index 720a59229b..330c776e8f 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rcc.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rcc.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_rcc.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Reset and clock control (RCC) peripheral: * + Internal/external clocks, PLL, CSS and MCO configuration @@ -38,7 +38,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -445,7 +445,7 @@ void RCC_LSICmd(FunctionalState NewState) *(__IO uint32_t *) CSR_LSION_BB = (uint32_t)NewState; } -#if defined(STM32F410xx) || defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx) /** * @brief Configures the main PLL clock source, multiplication and division factors. * @note This function must be used only when the main PLL is disabled. @@ -498,7 +498,7 @@ void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t PLLM, uint32_t PLLN, uint32_ RCC->PLLCFGR = PLLM | (PLLN << 6) | (((PLLP >> 1) -1) << 16) | (RCC_PLLSource) | (PLLQ << 24) | (PLLR << 28); } -#endif /* STM32F410xx || STM32F446xx || STM32F469_479xx */ +#endif /* STM32F410xx || STM32F412xG || STM32F446xx || STM32F469_479xx */ #if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F411xE) /** @@ -675,7 +675,7 @@ void RCC_PLLI2SConfig(uint32_t PLLI2SN, uint32_t PLLI2SQ, uint32_t PLLI2SR) } #endif /* STM32F427_437xx || STM32F429_439xx || STM32F469_479xx */ -#if defined(STM32F446xx) +#if defined(STM32F412xG ) || defined(STM32F446xx) /** * @brief Configures the PLLI2S clock multiplication and division factors. * @@ -721,7 +721,7 @@ void RCC_PLLI2SConfig(uint32_t PLLI2SM, uint32_t PLLI2SN, uint32_t PLLI2SP, uint RCC->PLLI2SCFGR = PLLI2SM | (PLLI2SN << 6) | (((PLLI2SP >> 1) -1) << 16) | (PLLI2SQ << 24) | (PLLI2SR << 28); } -#endif /* STM32F446xx */ +#endif /* STM32F412xG || STM32F446xx */ /** * @brief Enables or disables the PLLI2S. @@ -770,7 +770,7 @@ void RCC_PLLSAIConfig(uint32_t PLLSAIN, uint32_t PLLSAIP, uint32_t PLLSAIQ, uint assert_param(IS_RCC_PLLSAIQ_VALUE(PLLSAIQ)); assert_param(IS_RCC_PLLSAIR_VALUE(PLLSAIR)); - RCC->PLLSAICFGR = (PLLSAIN << 6) | (PLLSAIP << 16) | (PLLSAIQ << 24) | (PLLSAIR << 28); + RCC->PLLSAICFGR = (PLLSAIN << 6) | (((PLLSAIP >> 1) -1) << 16) | (PLLSAIQ << 24) | (PLLSAIR << 28); } #endif /* STM32F469_479xx */ @@ -1143,7 +1143,7 @@ void RCC_MCO2Config(uint32_t RCC_MCO2Source, uint32_t RCC_MCO2Div) * @arg RCC_SYSCLKSource_HSI: HSI selected as system clock source * @arg RCC_SYSCLKSource_HSE: HSE selected as system clock source * @arg RCC_SYSCLKSource_PLLCLK: PLL selected as system clock source (RCC_SYSCLKSource_PLLPCLK for STM32F446xx devices) - * @arg RCC_SYSCLKSource_PLLRCLK: PLL R selected as system clock source only for STM32F446xx devices + * @arg RCC_SYSCLKSource_PLLRCLK: PLL R selected as system clock source only for STM32F412xG and STM32F446xx devices * @retval None */ void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource) @@ -1173,7 +1173,7 @@ void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource) * - 0x00: HSI used as system clock * - 0x04: HSE used as system clock * - 0x08: PLL used as system clock (PLL P for STM32F446xx devices) - * - 0x0C: PLL R used as system clock (only for STM32F446xx devices) + * - 0x0C: PLL R used as system clock (only for STM32F412xG and STM32F446xx devices) */ uint8_t RCC_GetSYSCLKSource(void) { @@ -1317,9 +1317,9 @@ void RCC_PCLK2Config(uint32_t RCC_HCLK) void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks) { uint32_t tmp = 0, presc = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2; -#if defined(STM32F446xx) +#if defined(STM32F412xG) || defined(STM32F446xx) uint32_t pllr = 2; -#endif /* STM32F446xx */ +#endif /* STM32F412xG || STM32F446xx */ /* Get SYSCLK source -------------------------------------------------------*/ tmp = RCC->CFGR & RCC_CFGR_SWS; @@ -1348,14 +1348,14 @@ void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks) else { /* HSI used as PLL clock source */ - pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); + pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); } pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2; RCC_Clocks->SYSCLK_Frequency = pllvco/pllp; break; -#if defined(STM32F446xx) +#if defined(STM32F412xG) || defined(STM32F446xx) case 0x0C: /* PLL R used as system clock source */ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN SYSCLK = PLL_VCO / PLLR @@ -1371,13 +1371,13 @@ void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks) else { /* HSI used as PLL clock source */ - pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); + pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); } pllr = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >>28) + 1 ) *2; RCC_Clocks->SYSCLK_Frequency = pllvco/pllr; break; -#endif /* STM32F446xx */ +#endif /* STM32F412xG || STM32F446xx */ default: RCC_Clocks->SYSCLK_Frequency = HSI_VALUE; @@ -1523,7 +1523,7 @@ void RCC_BackupResetCmd(FunctionalState NewState) *(__IO uint32_t *) BDCR_BDRST_BB = (uint32_t)NewState; } -#if defined(STM32F446xx) +#if defined (STM32F412xG) || defined(STM32F446xx) /** * @brief Configures the I2S clock source (I2SCLK). * @note This function must be called before enabling the I2S APB clock. @@ -1563,7 +1563,7 @@ void RCC_I2SCLKConfig(uint32_t RCC_I2SAPBx, uint32_t RCC_I2SCLKSource) RCC->DCKCFGR |= (RCC_I2SCLKSource << 2); } } - +#if defined(STM32F446xx) /** * @brief Configures the SAIx clock source (SAIxCLK). * @note This function must be called before enabling the SAIx APB clock. @@ -1603,6 +1603,7 @@ void RCC_SAICLKConfig(uint32_t RCC_SAIInstance, uint32_t RCC_SAICLKSource) } } #endif /* STM32F446xx */ +#endif /* STM32F412xG || STM32F446xx */ #if defined(STM32F410xx) /** @@ -1822,6 +1823,66 @@ void RCC_LTDCCLKDivConfig(uint32_t RCC_PLLSAIDivR) RCC->DCKCFGR = tmpreg; } +#if defined(STM32F412xG) +/** + * @brief Configures the DFSDM clock source (DFSDMCLK). + * @note This function must be called before enabling the DFSDM APB clock. + * @param RCC_DFSDMCLKSource: specifies the DFSDM clock source. + * This parameter can be one of the following values: + * @arg RCC_DFSDM1CLKSource_APB: APB clock used as DFSDM clock source. + * @arg RCC_DFSDM1CLKSource_SYS: System clock used as DFSDM clock source. + * + * @retval None + */ +void RCC_DFSDM1CLKConfig(uint32_t RCC_DFSDM1CLKSource) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_DFSDM1CLK_SOURCE(RCC_DFSDM1CLKSource)); + + tmpreg = RCC->DCKCFGR; + + /* Clear CKDFSDM-SEL bit */ + tmpreg &= ~RCC_DCKCFGR_CKDFSDM1SEL; + + /* Set CKDFSDM-SEL bit according to RCC_DFSDMCLKSource value */ + tmpreg |= (RCC_DFSDM1CLKSource << 31) ; + + /* Store the new value */ + RCC->DCKCFGR = tmpreg; +} + +/** + * @brief Configures the DFSDM Audio clock source (DFSDMACLK). + * @note This function must be called before enabling the DFSDM APB clock. + * @param RCC_DFSDMACLKSource: specifies the DFSDM clock source. + * This parameter can be one of the following values: + * @arg RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB1: APB clock used as DFSDM clock source. + * @arg RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB2: System clock used as DFSDM clock source. + * + * @retval None + */ +void RCC_DFSDM1ACLKConfig(uint32_t RCC_DFSDMACLKSource) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_DFSDMACLK_SOURCE(RCC_DFSDMACLKSource)); + + tmpreg = RCC->DCKCFGR; + + /* Clear CKDFSDMA SEL bit */ + tmpreg &= ~RCC_DCKCFGR_CKDFSDM1ASEL; + + /* Set CKDFSDM-SEL bt according to RCC_DFSDMCLKSource value */ + tmpreg |= RCC_DFSDMACLKSource; + + /* Store the new value */ + RCC->DCKCFGR = tmpreg; +} +#endif /* STM32F412xG */ + /** * @brief Configures the Timers clocks prescalers selection. * @@ -1930,7 +1991,7 @@ void RCC_AHB2PeriphClockCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState) } } -#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F40_41xxx) || defined(STM32F412xG) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx) /** * @brief Enables or disables the AHB3 peripheral clock. * @note After reset, the peripheral clock (used for registers read/write access) @@ -1938,8 +1999,8 @@ void RCC_AHB2PeriphClockCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState) * using it. * @param RCC_AHBPeriph: specifies the AHB3 peripheral to gates its clock. * This parameter must be: - * - RCC_AHB3Periph_FSMC or RCC_AHB3Periph_FMC (STM32F429x/439x devices) - * - RCC_AHB3Periph_QSPI (STM32F446xx/STM32F469_479xx devices) + * - RCC_AHB3Periph_FSMC or RCC_AHB3Periph_FMC (STM32F412xG/STM32F429x/439x devices) + * - RCC_AHB3Periph_QSPI (STM32F412xG/STM32F446xx/STM32F469_479xx devices) * @param NewState: new state of the specified peripheral clock. * This parameter can be: ENABLE or DISABLE. * @retval None @@ -1959,7 +2020,7 @@ void RCC_AHB3PeriphClockCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState) RCC->AHB3ENR &= ~RCC_AHB3Periph; } } -#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */ +#endif /* STM32F40_41xxx || STM32F412xG || STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */ /** * @brief Enables or disables the Low Speed APB (APB1) peripheral clock. @@ -2043,7 +2104,8 @@ void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState) * @arg RCC_APB2Periph_SAI1: SAI1 clock (STM32F42xxx/43xxx/446xx/469xx/479xx devices) * @arg RCC_APB2Periph_SAI2: SAI2 clock (STM32F446xx devices) * @arg RCC_APB2Periph_LTDC: LTDC clock (STM32F429xx/439xx devices) - * @arg RCC_APB2Periph_DSI: DSI clock (STM32F469_479xx devices) + * @arg RCC_APB2Periph_DSI: DSI clock (STM32F469_479xx devices) + * @arg RCC_APB2Periph_DFSDM: DFSDM Clock (STM32F412xG Devices) * @param NewState: new state of the specified peripheral clock. * This parameter can be: ENABLE or DISABLE. * @retval None @@ -2114,7 +2176,7 @@ void RCC_AHB1PeriphResetCmd(uint32_t RCC_AHB1Periph, FunctionalState NewState) * @arg RCC_AHB2Periph_DCMI: DCMI clock * @arg RCC_AHB2Periph_CRYP: CRYP clock * @arg RCC_AHB2Periph_HASH: HASH clock - * @arg RCC_AHB2Periph_RNG: RNG clock for STM32F40_41xxx/STM32F427_437xx/STM32F429_439xx/STM32F469_479xx devices + * @arg RCC_AHB2Periph_RNG: RNG clock for STM32F40_41xxx/STM32F412xG/STM32F427_437xx/STM32F429_439xx/STM32F469_479xx devices * @arg RCC_AHB2Periph_OTG_FS: USB OTG FS clock * @param NewState: new state of the specified peripheral reset. * This parameter can be: ENABLE or DISABLE. @@ -2136,13 +2198,13 @@ void RCC_AHB2PeriphResetCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState) } } -#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F40_41xxx) || defined(STM32F412xG) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx) /** * @brief Forces or releases AHB3 peripheral reset. * @param RCC_AHB3Periph: specifies the AHB3 peripheral to reset. * This parameter must be: - * - RCC_AHB3Periph_FSMC or RCC_AHB3Periph_FMC (STM32F429x/439x devices) - * - RCC_AHB3Periph_QSPI (STM32F446xx/STM32F469_479xx devices) + * - RCC_AHB3Periph_FSMC or RCC_AHB3Periph_FMC (STM32F412xG and STM32F429x/439x devices) + * - RCC_AHB3Periph_QSPI (STM32F412xG/STM32F446xx/STM32F469_479xx devices) * @param NewState: new state of the specified peripheral reset. * This parameter can be: ENABLE or DISABLE. * @retval None @@ -2162,7 +2224,7 @@ void RCC_AHB3PeriphResetCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState) RCC->AHB3RSTR &= ~RCC_AHB3Periph; } } -#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */ +#endif /* STM32F40_41xxx || STM32F412xG || STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */ /** * @brief Forces or releases Low Speed APB (APB1) peripheral reset. @@ -2340,7 +2402,7 @@ void RCC_AHB2PeriphClockLPModeCmd(uint32_t RCC_AHB2Periph, FunctionalState NewSt } } -#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F40_41xxx) || defined(STM32F412xG) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx) /** * @brief Enables or disables the AHB3 peripheral clock during Low Power (Sleep) mode. * @note Peripheral clock gating in SLEEP mode can be used to further reduce @@ -2349,8 +2411,8 @@ void RCC_AHB2PeriphClockLPModeCmd(uint32_t RCC_AHB2Periph, FunctionalState NewSt * @note By default, all peripheral clocks are enabled during SLEEP mode. * @param RCC_AHBPeriph: specifies the AHB3 peripheral to gates its clock. * This parameter must be: - * - RCC_AHB3Periph_FSMC or RCC_AHB3Periph_FMC (STM32F429x/439x devices) - * - RCC_AHB3Periph_QSPI (STM32F446xx/STM32F469_479xx devices) + * - RCC_AHB3Periph_FSMC or RCC_AHB3Periph_FMC (STM32F412xG/STM32F429x/439x devices) + * - RCC_AHB3Periph_QSPI (STM32F412xG/STM32F446xx/STM32F469_479xx devices) * @param NewState: new state of the specified peripheral clock. * This parameter can be: ENABLE or DISABLE. * @retval None @@ -2369,7 +2431,7 @@ void RCC_AHB3PeriphClockLPModeCmd(uint32_t RCC_AHB3Periph, FunctionalState NewSt RCC->AHB3LPENR &= ~RCC_AHB3Periph; } } -#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */ +#endif /* STM32F40_41xxx || STM32F412xG || STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */ /** * @brief Enables or disables the APB1 peripheral clock during Low Power (Sleep) mode. @@ -2548,7 +2610,7 @@ void RCC_DSIClockSourceConfig(uint8_t RCC_ClockSource) } #endif /* STM32F469_479xx */ -#if defined(STM32F446xx) || defined(STM32F469_479xx) +#if defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx) /** * @brief Configures the 48MHz clock Source. * @note This feature is only available for STM32F446xx/STM32F469_479xx devices. @@ -2556,6 +2618,7 @@ void RCC_DSIClockSourceConfig(uint8_t RCC_ClockSource) * This parameter can be one of the following values: * @arg RCC_48MHZCLKSource_PLL: 48MHz from PLL selected. * @arg RCC_48MHZCLKSource_PLLSAI: 48MHz from PLLSAI selected. + * @arg RCC_CK48CLKSOURCE_PLLI2SQ : 48MHz from PLLI2SQ * @retval None */ void RCC_48MHzClockSourceConfig(uint8_t RCC_ClockSource) @@ -2571,7 +2634,7 @@ void RCC_48MHzClockSourceConfig(uint8_t RCC_ClockSource) { CLEAR_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL); } -#elif defined(STM32F446xx) +#elif defined(STM32F446xx) if(RCC_ClockSource == RCC_48MHZCLKSource_PLLSAI) { SET_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL); @@ -2580,6 +2643,15 @@ void RCC_48MHzClockSourceConfig(uint8_t RCC_ClockSource) { CLEAR_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL); } +#elif defined(STM32F412xG) + if(RCC_ClockSource == RCC_CK48CLKSOURCE_PLLI2SQ) + { + SET_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL); + } + else + { + CLEAR_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL); + } #else #endif /* STM32F469_479xx */ } @@ -2606,7 +2678,7 @@ void RCC_SDIOClockSourceConfig(uint8_t RCC_ClockSource) { CLEAR_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SDIOSEL); } -#elif defined(STM32F446xx) +#elif defined(STM32F412xG) || defined(STM32F446xx) if(RCC_ClockSource == RCC_SDIOCLKSource_SYSCLK) { SET_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL); @@ -2618,7 +2690,7 @@ void RCC_SDIOClockSourceConfig(uint8_t RCC_ClockSource) #else #endif /* STM32F469_479xx */ } -#endif /* STM32F446xx || STM32F469_479xx */ +#endif /* STM32F412xG || STM32F446xx || STM32F469_479xx */ #if defined(STM32F446xx) /** @@ -2702,7 +2774,7 @@ void RCC_CECClockSourceConfig(uint8_t RCC_ClockSource) } #endif /* STM32F446xx */ -#if defined(STM32F410xx) || defined(STM32F446xx) +#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) /** * @brief Configures the FMPI2C1 clock Source. * @note This feature is only available for STM32F446xx devices. @@ -2723,7 +2795,7 @@ void RCC_FMPI2C1ClockSourceConfig(uint32_t RCC_ClockSource) /* Set new FMPI2C1 clock source */ RCC->DCKCFGR2 |= RCC_ClockSource; } -#endif /* STM32F410xx || STM32F446xx */ +#endif /* STM32F410xx || STM32F412xG || STM32F446xx */ /** * @} */ diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rng.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rng.c index f1b0f952b2..dc8da38e3b 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rng.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rng.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_rng.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Random Number Generator (RNG) peripheral: * + Initialization and Configuration @@ -35,7 +35,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -64,7 +64,7 @@ * @brief RNG driver modules * @{ */ -#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F410xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx) +#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F429_439xx) || defined(STM32F469_479xx) /* Private typedef -----------------------------------------------------------*/ /* Private define ------------------------------------------------------------*/ /* Private macro -------------------------------------------------------------*/ @@ -393,7 +393,7 @@ void RNG_ClearITPendingBit(uint8_t RNG_IT) /** * @} */ -#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F410xx || STM32F429_439xx || STM32F469_479xx */ +#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F410xx || STM32F412xG || STM32F429_439xx || STM32F469_479xx */ /** * @} */ diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rtc.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rtc.c index 20dd43f85b..7ab48d4316 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rtc.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rtc.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_rtc.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Real-Time Clock (RTC) peripheral: * + Initialization @@ -264,7 +264,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -305,7 +305,7 @@ RTC_FLAG_ALRBF | RTC_FLAG_ALRAF | RTC_FLAG_INITF | \ RTC_FLAG_RSF | RTC_FLAG_INITS | RTC_FLAG_WUTWF | \ RTC_FLAG_ALRBWF | RTC_FLAG_ALRAWF | RTC_FLAG_TAMP1F | \ - RTC_FLAG_RECALPF | RTC_FLAG_SHPF)) + RTC_FLAG_TAMP2F | RTC_FLAG_RECALPF | RTC_FLAG_SHPF)) #define INITMODE_TIMEOUT ((uint32_t) 0x00010000) #define SYNCHRO_TIMEOUT ((uint32_t) 0x00020000) @@ -2092,7 +2092,7 @@ uint32_t RTC_GetTimeStampSubSecond(void) /** * @brief Configures the select Tamper pin edge. * @param RTC_Tamper: Selected tamper pin. - * This parameter can be RTC_Tamper_1. + * This parameter can be RTC_Tamper_1 or RTC_Tamper 2 * @param RTC_TamperTrigger: Specifies the trigger on the tamper pin that * stimulates tamper event. * This parameter can be one of the following values: @@ -2123,7 +2123,7 @@ void RTC_TamperTriggerConfig(uint32_t RTC_Tamper, uint32_t RTC_TamperTrigger) /** * @brief Enables or Disables the Tamper detection. * @param RTC_Tamper: Selected tamper pin. - * This parameter can be RTC_Tamper_1. + * This parameter can be RTC_Tamper_1 or RTC_Tamper_2 * @param NewState: new state of the tamper pin. * This parameter can be: ENABLE or DISABLE. * @retval None @@ -2356,8 +2356,8 @@ uint32_t RTC_ReadBackupRegister(uint32_t RTC_BKP_DR) * @brief Selects the RTC Tamper Pin. * @param RTC_TamperPin: specifies the RTC Tamper Pin. * This parameter can be one of the following values: - * @arg RTC_TamperPin_PC13: PC13 is selected as RTC Tamper Pin. - * @arg RTC_TamperPin_PI8: PI8 is selected as RTC Tamper Pin. + * @arg RTC_TamperPin_Default: RTC_AF1 is used as RTC Tamper Pin. + * @arg RTC_TamperPin_Pos1: RTC_AF2 is selected as RTC Tamper Pin. * @retval None */ void RTC_TamperPinSelection(uint32_t RTC_TamperPin) @@ -2588,6 +2588,7 @@ void RTC_ITConfig(uint32_t RTC_IT, FunctionalState NewState) * This parameter can be one of the following values: * @arg RTC_FLAG_RECALPF: RECALPF event flag. * @arg RTC_FLAG_TAMP1F: Tamper 1 event flag + * @arg RTC_FLAG_TAMP2F: Tamper 2 event flag * @arg RTC_FLAG_TSOVF: Time Stamp OverFlow flag * @arg RTC_FLAG_TSF: Time Stamp event flag * @arg RTC_FLAG_WUTF: WakeUp Timer flag @@ -2630,6 +2631,7 @@ FlagStatus RTC_GetFlagStatus(uint32_t RTC_FLAG) * @param RTC_FLAG: specifies the RTC flag to clear. * This parameter can be any combination of the following values: * @arg RTC_FLAG_TAMP1F: Tamper 1 event flag + * @arg RTC_FLAG_TAMP2F: Tamper 2 event flag * @arg RTC_FLAG_TSOVF: Time Stamp Overflow flag * @arg RTC_FLAG_TSF: Time Stamp event flag * @arg RTC_FLAG_WUTF: WakeUp Timer flag @@ -2655,7 +2657,8 @@ void RTC_ClearFlag(uint32_t RTC_FLAG) * @arg RTC_IT_WUT: WakeUp Timer interrupt * @arg RTC_IT_ALRB: Alarm B interrupt * @arg RTC_IT_ALRA: Alarm A interrupt - * @arg RTC_IT_TAMP1: Tamper 1 event interrupt + * @arg RTC_IT_TAMP1: Tamper 1 event interrupt + * @arg RTC_IT_TAMP2: Tamper 2 event interrupt * @retval The new state of RTC_IT (SET or RESET). */ ITStatus RTC_GetITStatus(uint32_t RTC_IT) @@ -2670,7 +2673,7 @@ ITStatus RTC_GetITStatus(uint32_t RTC_IT) tmpreg = (uint32_t)(RTC->TAFCR & (RTC_TAFCR_TAMPIE)); /* Get the Interrupt enable Status */ - enablestatus = (uint32_t)((RTC->CR & RTC_IT) | (tmpreg & (RTC_IT >> 15))); + enablestatus = (uint32_t)((RTC->CR & RTC_IT) | (tmpreg & (RTC_IT >> 15)) | (tmpreg & (RTC_IT >> 16))); /* Get the Interrupt pending bit */ tmpreg = (uint32_t)((RTC->ISR & (uint32_t)(RTC_IT >> 4))); @@ -2695,7 +2698,8 @@ ITStatus RTC_GetITStatus(uint32_t RTC_IT) * @arg RTC_IT_WUT: WakeUp Timer interrupt * @arg RTC_IT_ALRB: Alarm B interrupt * @arg RTC_IT_ALRA: Alarm A interrupt - * @arg RTC_IT_TAMP1: Tamper 1 event interrupt + * @arg RTC_IT_TAMP1: Tamper 1 event interrupt + * @arg RTC_IT_TAMP2: Tamper 2 event interrupt * @retval None */ void RTC_ClearITPendingBit(uint32_t RTC_IT) diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_sai.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_sai.c index eeb2a0ab9f..4215e6908e 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_sai.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_sai.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_sai.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Serial Audio Interface (SAI): * + Initialization and Configuration @@ -105,7 +105,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_sdio.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_sdio.c index 77f4df23c1..8c4659a080 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_sdio.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_sdio.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_sdio.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Secure digital input/output interface (SDIO) * peripheral: @@ -135,7 +135,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spdifrx.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spdifrx.c index af75b1544e..c95f0faeb6 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spdifrx.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spdifrx.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_spdifrx.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Serial Audio Interface (SPDIFRX): * + Initialization and Configuration @@ -13,7 +13,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spi.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spi.c index 421c58c8ae..4aa38e731f 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spi.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spi.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_spi.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Serial peripheral interface (SPI): * + Initialization and Configuration @@ -138,7 +138,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_syscfg.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_syscfg.c index c4b54fbca8..5ba89035bb 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_syscfg.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_syscfg.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_syscfg.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the SYSCFG peripheral. * @verbatim @@ -29,7 +29,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. @@ -225,7 +225,7 @@ FlagStatus SYSCFG_GetCompensationCellStatus(void) return bitstatus; } -#if defined(STM32F410xx) +#if defined(STM32F410xx) || defined(STM32F412xG) /** * @brief Connects the selected parameter to the break input of TIM1. * @note The selected configuration is locked and can be unlocked by system reset @@ -243,7 +243,7 @@ void SYSCFG_BreakConfig(uint32_t SYSCFG_Break) SYSCFG->CFGR2 |= (uint32_t) SYSCFG_Break; } -#endif /* STM32F410xx */ +#endif /* STM32F410xx || STM32F412xG */ /** * @} */ diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_tim.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_tim.c index d8889ddfff..376845c5c9 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_tim.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_tim.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_tim.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the TIM peripheral: * + TimeBase management @@ -98,7 +98,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_usart.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_usart.c index be60e0753c..5c2cee074e 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_usart.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_usart.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_usart.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Universal synchronous asynchronous receiver * transmitter (USART): @@ -71,7 +71,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_wwdg.c b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_wwdg.c index 66fd438486..f4e2e92dbd 100644 --- a/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_wwdg.c +++ b/lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_wwdg.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file stm32f4xx_wwdg.c * @author MCD Application Team - * @version V1.6.1 - * @date 21-October-2015 + * @version V1.7.1 + * @date 20-May-2016 * @brief This file provides firmware functions to manage the following * functionalities of the Window watchdog (WWDG) peripheral: * + Prescaler, Refresh window and Counter configuration @@ -63,7 +63,7 @@ ****************************************************************************** * @attention * - *

© COPYRIGHT 2015 STMicroelectronics

+ *

© COPYRIGHT 2016 STMicroelectronics

* * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); * You may not use this file except in compliance with the License. diff --git a/lib/main/STM32_USB-FS-Device_Driver/inc/usb_regs.h b/lib/main/STM32_USB-FS-Device_Driver/inc/usb_regs.h index 88c6e6735d..1f24863052 100644 --- a/lib/main/STM32_USB-FS-Device_Driver/inc/usb_regs.h +++ b/lib/main/STM32_USB-FS-Device_Driver/inc/usb_regs.h @@ -228,8 +228,8 @@ enum EP_BUF_NUM /* GetDADDR */ #define _GetDADDR() ((__IO uint16_t) *DADDR) -/* GetBTABLE */ -#define _GetBTABLE() ((__IO uint16_t) *BTABLE) +/* GetBTABLE ; clear low-order bits explicitly to avoid problems in gcc 5.x */ +#define _GetBTABLE() (((__IO uint16_t) *BTABLE) & ~0x07) /* SetENDPOINT */ #define _SetENDPOINT(bEpNum,wRegValue) (*(EP0REG + bEpNum)= \ diff --git a/lib/main/STM32_USB_Device_Library/Class/audio/inc/usbd_audio_core.h b/lib/main/STM32_USB_Device_Library/Class/audio/inc/usbd_audio_core.h deleted file mode 100644 index f58ff06018..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/audio/inc/usbd_audio_core.h +++ /dev/null @@ -1,158 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_audio_core.h - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief header file for the usbd_audio_core.c file. - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ - -#ifndef __USB_AUDIO_CORE_H_ -#define __USB_AUDIO_CORE_H_ - -#include "usbd_ioreq.h" -#include "usbd_req.h" -#include "usbd_desc.h" - - - - -/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY - * @{ - */ - -/** @defgroup usbd_audio - * @brief This file is the Header file for USBD_audio.c - * @{ - */ - - -/** @defgroup usbd_audio_Exported_Defines - * @{ - */ - -/* AudioFreq * DataSize (2 bytes) * NumChannels (Stereo: 2) */ -#define AUDIO_OUT_PACKET (uint32_t)(((USBD_AUDIO_FREQ * 2 * 2) /1000)) - -/* Number of sub-packets in the audio transfer buffer. You can modify this value but always make sure - that it is an even number and higher than 3 */ -#define OUT_PACKET_NUM 4 -/* Total size of the audio transfer buffer */ -#define TOTAL_OUT_BUF_SIZE ((uint32_t)(AUDIO_OUT_PACKET * OUT_PACKET_NUM)) - -#define AUDIO_CONFIG_DESC_SIZE 109 -#define AUDIO_INTERFACE_DESC_SIZE 9 -#define USB_AUDIO_DESC_SIZ 0x09 -#define AUDIO_STANDARD_ENDPOINT_DESC_SIZE 0x09 -#define AUDIO_STREAMING_ENDPOINT_DESC_SIZE 0x07 - -#define AUDIO_DESCRIPTOR_TYPE 0x21 -#define USB_DEVICE_CLASS_AUDIO 0x01 -#define AUDIO_SUBCLASS_AUDIOCONTROL 0x01 -#define AUDIO_SUBCLASS_AUDIOSTREAMING 0x02 -#define AUDIO_PROTOCOL_UNDEFINED 0x00 -#define AUDIO_STREAMING_GENERAL 0x01 -#define AUDIO_STREAMING_FORMAT_TYPE 0x02 - -/* Audio Descriptor Types */ -#define AUDIO_INTERFACE_DESCRIPTOR_TYPE 0x24 -#define AUDIO_ENDPOINT_DESCRIPTOR_TYPE 0x25 - -/* Audio Control Interface Descriptor Subtypes */ -#define AUDIO_CONTROL_HEADER 0x01 -#define AUDIO_CONTROL_INPUT_TERMINAL 0x02 -#define AUDIO_CONTROL_OUTPUT_TERMINAL 0x03 -#define AUDIO_CONTROL_FEATURE_UNIT 0x06 - -#define AUDIO_INPUT_TERMINAL_DESC_SIZE 0x0C -#define AUDIO_OUTPUT_TERMINAL_DESC_SIZE 0x09 -#define AUDIO_STREAMING_INTERFACE_DESC_SIZE 0x07 - -#define AUDIO_CONTROL_MUTE 0x0001 - -#define AUDIO_FORMAT_TYPE_I 0x01 -#define AUDIO_FORMAT_TYPE_III 0x03 - -#define USB_ENDPOINT_TYPE_ISOCHRONOUS 0x01 -#define AUDIO_ENDPOINT_GENERAL 0x01 - -#define AUDIO_REQ_GET_CUR 0x81 -#define AUDIO_REQ_SET_CUR 0x01 - -#define AUDIO_OUT_STREAMING_CTRL 0x02 - -/** - * @} - */ - - -/** @defgroup USBD_CORE_Exported_TypesDefinitions - * @{ - */ -typedef struct _Audio_Fops -{ - uint8_t (*Init) (uint32_t AudioFreq, uint32_t Volume, uint32_t options); - uint8_t (*DeInit) (uint32_t options); - uint8_t (*AudioCmd) (uint8_t* pbuf, uint32_t size, uint8_t cmd); - uint8_t (*VolumeCtl) (uint8_t vol); - uint8_t (*MuteCtl) (uint8_t cmd); - uint8_t (*PeriodicTC) (uint8_t cmd); - uint8_t (*GetState) (void); -}AUDIO_FOPS_TypeDef; -/** - * @} - */ - - - -/** @defgroup USBD_CORE_Exported_Macros - * @{ - */ -#define AUDIO_PACKET_SZE(frq) (uint8_t)(((frq * 2 * 2)/1000) & 0xFF), \ - (uint8_t)((((frq * 2 * 2)/1000) >> 8) & 0xFF) -#define SAMPLE_FREQ(frq) (uint8_t)(frq), (uint8_t)((frq >> 8)), (uint8_t)((frq >> 16)) -/** - * @} - */ - -/** @defgroup USBD_CORE_Exported_Variables - * @{ - */ - -extern USBD_Class_cb_TypeDef AUDIO_cb; - -/** - * @} - */ - -/** @defgroup USB_CORE_Exported_Functions - * @{ - */ -/** - * @} - */ - -#endif // __USB_AUDIO_CORE_H_ -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/audio/inc/usbd_audio_out_if.h b/lib/main/STM32_USB_Device_Library/Class/audio/inc/usbd_audio_out_if.h deleted file mode 100644 index a6b53fa832..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/audio/inc/usbd_audio_out_if.h +++ /dev/null @@ -1,117 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_audio_out_if.h - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief header file for the usbd_audio_out_if.c file. - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ - -#ifndef __USB_AUDIO_OUT_IF_H_ -#define __USB_AUDIO_OUT_IF_H_ - -#ifdef STM32F2XX - #include "stm322xg_usb_audio_codec.h" -#elif defined(STM32F10X_CL) - #include "stm3210c_usb_audio_codec.h" -#endif /* STM32F2XX */ - -/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY - * @{ - */ - -/** @defgroup usbd_audio - * @brief This file is the Header file for USBD_audio.c - * @{ - */ - - -/** @defgroup usbd_audio_Exported_Defines - * @{ - */ -/* Audio Commands enmueration */ -typedef enum -{ - AUDIO_CMD_PLAY = 1, - AUDIO_CMD_PAUSE, - AUDIO_CMD_STOP, -}AUDIO_CMD_TypeDef; - -/* Mute commands */ -#define AUDIO_MUTE 0x01 -#define AUDIO_UNMUTE 0x00 - -/* Functions return value */ -#define AUDIO_OK 0x00 -#define AUDIO_FAIL 0xFF - -/* Audio Machine States */ -#define AUDIO_STATE_INACTIVE 0x00 -#define AUDIO_STATE_ACTIVE 0x01 -#define AUDIO_STATE_PLAYING 0x02 -#define AUDIO_STATE_PAUSED 0x03 -#define AUDIO_STATE_STOPPED 0x04 -#define AUDIO_STATE_ERROR 0x05 - -/** - * @} - */ - - -/** @defgroup USBD_CORE_Exported_TypesDefinitions - * @{ - */ -/** - * @} - */ - - - -/** @defgroup USBD_CORE_Exported_Macros - * @{ - */ -/** - * @} - */ - -/** @defgroup USBD_CORE_Exported_Variables - * @{ - */ - -extern AUDIO_FOPS_TypeDef AUDIO_OUT_fops; - -/** - * @} - */ - -/** @defgroup USB_CORE_Exported_Functions - * @{ - */ -/** - * @} - */ - -#endif /* __USB_AUDIO_OUT_IF_H_ */ -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/audio/src/usbd_audio_core.c b/lib/main/STM32_USB_Device_Library/Class/audio/src/usbd_audio_core.c deleted file mode 100644 index b26f574a3f..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/audio/src/usbd_audio_core.c +++ /dev/null @@ -1,665 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_audio_core.c - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief This file provides the high layer firmware functions to manage the - * following functionalities of the USB Audio Class: - * - Initialization and Configuration of high and low layer - * - Enumeration as Audio Streaming Device - * - Audio Streaming data transfer - * - AudioControl requests management - * - Error management - * - * @verbatim - * - * =================================================================== - * Audio Class Driver Description - * =================================================================== - * This driver manages the Audio Class 1.0 following the "USB Device Class Definition for - * Audio Devices V1.0 Mar 18, 98". - * This driver implements the following aspects of the specification: - * - Device descriptor management - * - Configuration descriptor management - * - Standard AC Interface Descriptor management - * - 1 Audio Streaming Interface (with single channel, PCM, Stereo mode) - * - 1 Audio Streaming Endpoint - * - 1 Audio Terminal Input (1 channel) - * - Audio Class-Specific AC Interfaces - * - Audio Class-Specific AS Interfaces - * - AudioControl Requests: only SET_CUR and GET_CUR requests are supported (for Mute) - * - Audio Feature Unit (limited to Mute control) - * - Audio Synchronization type: Asynchronous - * - Single fixed audio sampling rate (configurable in usbd_conf.h file) - * - * @note - * The Audio Class 1.0 is based on USB Specification 1.0 and thus supports only - * Low and Full speed modes and does not allow High Speed transfers. - * Please refer to "USB Device Class Definition for Audio Devices V1.0 Mar 18, 98" - * for more details. - * - * These aspects may be enriched or modified for a specific user application. - * - * This driver doesn't implement the following aspects of the specification - * (but it is possible to manage these features with some modifications on this driver): - * - AudioControl Endpoint management - * - AudioControl requsests other than SET_CUR and GET_CUR - * - Abstraction layer for AudioControl requests (only Mute functionality is managed) - * - Audio Synchronization type: Adaptive - * - Audio Compression modules and interfaces - * - MIDI interfaces and modules - * - Mixer/Selector/Processing/Extension Units (Feature unit is limited to Mute control) - * - Any other application-specific modules - * - Multiple and Variable audio sampling rates - * - Out Streaming Endpoint/Interface (microphone) - * - * @endverbatim - * - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ - -#include "usbd_audio_core.h" -#include "usbd_audio_out_if.h" - -/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY - * @{ - */ - - -/** @defgroup usbd_audio - * @brief usbd core module - * @{ - */ - -/** @defgroup usbd_audio_Private_TypesDefinitions - * @{ - */ -/** - * @} - */ - - -/** @defgroup usbd_audio_Private_Defines - * @{ - */ -/** - * @} - */ - - -/** @defgroup usbd_audio_Private_Macros - * @{ - */ -/** - * @} - */ - - -/** @defgroup usbd_audio_Private_FunctionPrototypes - * @{ - */ - -/********************************************* - AUDIO Device library callbacks - *********************************************/ -static uint8_t usbd_audio_Init (void *pdev, uint8_t cfgidx); -static uint8_t usbd_audio_DeInit (void *pdev, uint8_t cfgidx); -static uint8_t usbd_audio_Setup (void *pdev, USB_SETUP_REQ *req); -static uint8_t usbd_audio_EP0_RxReady(void *pdev); -static uint8_t usbd_audio_DataIn (void *pdev, uint8_t epnum); -static uint8_t usbd_audio_DataOut (void *pdev, uint8_t epnum); -static uint8_t usbd_audio_SOF (void *pdev); -static uint8_t usbd_audio_OUT_Incplt (void *pdev); - -/********************************************* - AUDIO Requests management functions - *********************************************/ -static void AUDIO_Req_GetCurrent(void *pdev, USB_SETUP_REQ *req); -static void AUDIO_Req_SetCurrent(void *pdev, USB_SETUP_REQ *req); -static uint8_t *USBD_audio_GetCfgDesc (uint8_t speed, uint16_t *length); -/** - * @} - */ - -/** @defgroup usbd_audio_Private_Variables - * @{ - */ -/* Main Buffer for Audio Data Out transfers and its relative pointers */ -uint8_t IsocOutBuff [TOTAL_OUT_BUF_SIZE * 2]; -uint8_t* IsocOutWrPtr = IsocOutBuff; -uint8_t* IsocOutRdPtr = IsocOutBuff; - -/* Main Buffer for Audio Control Rrequests transfers and its relative variables */ -uint8_t AudioCtl[64]; -uint8_t AudioCtlCmd = 0; -uint32_t AudioCtlLen = 0; -uint8_t AudioCtlUnit = 0; - -static uint32_t PlayFlag = 0; - -static __IO uint32_t usbd_audio_AltSet = 0; -static uint8_t usbd_audio_CfgDesc[AUDIO_CONFIG_DESC_SIZE]; - -/* AUDIO interface class callbacks structure */ -USBD_Class_cb_TypeDef AUDIO_cb = -{ - usbd_audio_Init, - usbd_audio_DeInit, - usbd_audio_Setup, - NULL, /* EP0_TxSent */ - usbd_audio_EP0_RxReady, - usbd_audio_DataIn, - usbd_audio_DataOut, - usbd_audio_SOF, - NULL, - usbd_audio_OUT_Incplt, - USBD_audio_GetCfgDesc, -#ifdef USB_OTG_HS_CORE - USBD_audio_GetCfgDesc, /* use same config as per FS */ -#endif -}; - -/* USB AUDIO device Configuration Descriptor */ -static uint8_t usbd_audio_CfgDesc[AUDIO_CONFIG_DESC_SIZE] = -{ - /* Configuration 1 */ - 0x09, /* bLength */ - USB_CONFIGURATION_DESCRIPTOR_TYPE, /* bDescriptorType */ - LOBYTE(AUDIO_CONFIG_DESC_SIZE), /* wTotalLength 109 bytes*/ - HIBYTE(AUDIO_CONFIG_DESC_SIZE), - 0x02, /* bNumInterfaces */ - 0x01, /* bConfigurationValue */ - 0x00, /* iConfiguration */ - 0xC0, /* bmAttributes BUS Powred*/ - 0x32, /* bMaxPower = 100 mA*/ - /* 09 byte*/ - - /* USB Speaker Standard interface descriptor */ - AUDIO_INTERFACE_DESC_SIZE, /* bLength */ - USB_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */ - 0x00, /* bInterfaceNumber */ - 0x00, /* bAlternateSetting */ - 0x00, /* bNumEndpoints */ - USB_DEVICE_CLASS_AUDIO, /* bInterfaceClass */ - AUDIO_SUBCLASS_AUDIOCONTROL, /* bInterfaceSubClass */ - AUDIO_PROTOCOL_UNDEFINED, /* bInterfaceProtocol */ - 0x00, /* iInterface */ - /* 09 byte*/ - - /* USB Speaker Class-specific AC Interface Descriptor */ - AUDIO_INTERFACE_DESC_SIZE, /* bLength */ - AUDIO_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */ - AUDIO_CONTROL_HEADER, /* bDescriptorSubtype */ - 0x00, /* 1.00 */ /* bcdADC */ - 0x01, - 0x27, /* wTotalLength = 39*/ - 0x00, - 0x01, /* bInCollection */ - 0x01, /* baInterfaceNr */ - /* 09 byte*/ - - /* USB Speaker Input Terminal Descriptor */ - AUDIO_INPUT_TERMINAL_DESC_SIZE, /* bLength */ - AUDIO_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */ - AUDIO_CONTROL_INPUT_TERMINAL, /* bDescriptorSubtype */ - 0x01, /* bTerminalID */ - 0x01, /* wTerminalType AUDIO_TERMINAL_USB_STREAMING 0x0101 */ - 0x01, - 0x00, /* bAssocTerminal */ - 0x01, /* bNrChannels */ - 0x00, /* wChannelConfig 0x0000 Mono */ - 0x00, - 0x00, /* iChannelNames */ - 0x00, /* iTerminal */ - /* 12 byte*/ - - /* USB Speaker Audio Feature Unit Descriptor */ - 0x09, /* bLength */ - AUDIO_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */ - AUDIO_CONTROL_FEATURE_UNIT, /* bDescriptorSubtype */ - AUDIO_OUT_STREAMING_CTRL, /* bUnitID */ - 0x01, /* bSourceID */ - 0x01, /* bControlSize */ - AUDIO_CONTROL_MUTE, /* bmaControls(0) */ - 0x00, /* bmaControls(1) */ - 0x00, /* iTerminal */ - /* 09 byte*/ - - /*USB Speaker Output Terminal Descriptor */ - 0x09, /* bLength */ - AUDIO_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */ - AUDIO_CONTROL_OUTPUT_TERMINAL, /* bDescriptorSubtype */ - 0x03, /* bTerminalID */ - 0x01, /* wTerminalType 0x0301*/ - 0x03, - 0x00, /* bAssocTerminal */ - 0x02, /* bSourceID */ - 0x00, /* iTerminal */ - /* 09 byte*/ - - /* USB Speaker Standard AS Interface Descriptor - Audio Streaming Zero Bandwith */ - /* Interface 1, Alternate Setting 0 */ - AUDIO_INTERFACE_DESC_SIZE, /* bLength */ - USB_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */ - 0x01, /* bInterfaceNumber */ - 0x00, /* bAlternateSetting */ - 0x00, /* bNumEndpoints */ - USB_DEVICE_CLASS_AUDIO, /* bInterfaceClass */ - AUDIO_SUBCLASS_AUDIOSTREAMING, /* bInterfaceSubClass */ - AUDIO_PROTOCOL_UNDEFINED, /* bInterfaceProtocol */ - 0x00, /* iInterface */ - /* 09 byte*/ - - /* USB Speaker Standard AS Interface Descriptor - Audio Streaming Operational */ - /* Interface 1, Alternate Setting 1 */ - AUDIO_INTERFACE_DESC_SIZE, /* bLength */ - USB_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */ - 0x01, /* bInterfaceNumber */ - 0x01, /* bAlternateSetting */ - 0x01, /* bNumEndpoints */ - USB_DEVICE_CLASS_AUDIO, /* bInterfaceClass */ - AUDIO_SUBCLASS_AUDIOSTREAMING, /* bInterfaceSubClass */ - AUDIO_PROTOCOL_UNDEFINED, /* bInterfaceProtocol */ - 0x00, /* iInterface */ - /* 09 byte*/ - - /* USB Speaker Audio Streaming Interface Descriptor */ - AUDIO_STREAMING_INTERFACE_DESC_SIZE, /* bLength */ - AUDIO_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */ - AUDIO_STREAMING_GENERAL, /* bDescriptorSubtype */ - 0x01, /* bTerminalLink */ - 0x01, /* bDelay */ - 0x01, /* wFormatTag AUDIO_FORMAT_PCM 0x0001*/ - 0x00, - /* 07 byte*/ - - /* USB Speaker Audio Type III Format Interface Descriptor */ - 0x0B, /* bLength */ - AUDIO_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */ - AUDIO_STREAMING_FORMAT_TYPE, /* bDescriptorSubtype */ - AUDIO_FORMAT_TYPE_III, /* bFormatType */ - 0x02, /* bNrChannels */ - 0x02, /* bSubFrameSize : 2 Bytes per frame (16bits) */ - 16, /* bBitResolution (16-bits per sample) */ - 0x01, /* bSamFreqType only one frequency supported */ - SAMPLE_FREQ(USBD_AUDIO_FREQ), /* Audio sampling frequency coded on 3 bytes */ - /* 11 byte*/ - - /* Endpoint 1 - Standard Descriptor */ - AUDIO_STANDARD_ENDPOINT_DESC_SIZE, /* bLength */ - USB_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType */ - AUDIO_OUT_EP, /* bEndpointAddress 1 out endpoint*/ - USB_ENDPOINT_TYPE_ISOCHRONOUS, /* bmAttributes */ - AUDIO_PACKET_SZE(USBD_AUDIO_FREQ), /* wMaxPacketSize in Bytes (Freq(Samples)*2(Stereo)*2(HalfWord)) */ - 0x01, /* bInterval */ - 0x00, /* bRefresh */ - 0x00, /* bSynchAddress */ - /* 09 byte*/ - - /* Endpoint - Audio Streaming Descriptor*/ - AUDIO_STREAMING_ENDPOINT_DESC_SIZE, /* bLength */ - AUDIO_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType */ - AUDIO_ENDPOINT_GENERAL, /* bDescriptor */ - 0x00, /* bmAttributes */ - 0x00, /* bLockDelayUnits */ - 0x00, /* wLockDelay */ - 0x00, - /* 07 byte*/ -} ; - -/** - * @} - */ - -/** @defgroup usbd_audio_Private_Functions - * @{ - */ - -/** -* @brief usbd_audio_Init -* Initilaizes the AUDIO interface. -* @param pdev: device instance -* @param cfgidx: Configuration index -* @retval status -*/ -static uint8_t usbd_audio_Init (void *pdev, - uint8_t cfgidx) -{ - /* Open EP OUT */ - DCD_EP_Open(pdev, - AUDIO_OUT_EP, - AUDIO_OUT_PACKET, - USB_OTG_EP_ISOC); - - /* Initialize the Audio output Hardware layer */ - if (AUDIO_OUT_fops.Init(USBD_AUDIO_FREQ, DEFAULT_VOLUME, 0) != USBD_OK) - { - return USBD_FAIL; - } - - /* Prepare Out endpoint to receive audio data */ - DCD_EP_PrepareRx(pdev, - AUDIO_OUT_EP, - (uint8_t*)IsocOutBuff, - AUDIO_OUT_PACKET); - - return USBD_OK; -} - -/** -* @brief usbd_audio_Init -* DeInitializes the AUDIO layer. -* @param pdev: device instance -* @param cfgidx: Configuration index -* @retval status -*/ -static uint8_t usbd_audio_DeInit (void *pdev, - uint8_t cfgidx) -{ - DCD_EP_Close (pdev , AUDIO_OUT_EP); - - /* DeInitialize the Audio output Hardware layer */ - if (AUDIO_OUT_fops.DeInit(0) != USBD_OK) - { - return USBD_FAIL; - } - - return USBD_OK; -} - -/** - * @brief usbd_audio_Setup - * Handles the Audio control request parsing. - * @param pdev: instance - * @param req: usb requests - * @retval status - */ -static uint8_t usbd_audio_Setup (void *pdev, - USB_SETUP_REQ *req) -{ - uint16_t len; - uint8_t *pbuf; - - switch (req->bmRequest & USB_REQ_TYPE_MASK) - { - /* AUDIO Class Requests -------------------------------*/ - case USB_REQ_TYPE_CLASS : - switch (req->bRequest) - { - case AUDIO_REQ_GET_CUR: - AUDIO_Req_GetCurrent(pdev, req); - break; - - case AUDIO_REQ_SET_CUR: - AUDIO_Req_SetCurrent(pdev, req); - break; - - default: - USBD_CtlError (pdev, req); - return USBD_FAIL; - } - break; - - /* Standard Requests -------------------------------*/ - case USB_REQ_TYPE_STANDARD: - switch (req->bRequest) - { - case USB_REQ_GET_DESCRIPTOR: - if( (req->wValue >> 8) == AUDIO_DESCRIPTOR_TYPE) - { -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - pbuf = usbd_audio_Desc; -#else - pbuf = usbd_audio_CfgDesc + 18; -#endif - len = MIN(USB_AUDIO_DESC_SIZ , req->wLength); - } - - USBD_CtlSendData (pdev, - pbuf, - len); - break; - - case USB_REQ_GET_INTERFACE : - USBD_CtlSendData (pdev, - (uint8_t *)&usbd_audio_AltSet, - 1); - break; - - case USB_REQ_SET_INTERFACE : - if ((uint8_t)(req->wValue) < AUDIO_TOTAL_IF_NUM) - { - usbd_audio_AltSet = (uint8_t)(req->wValue); - } - else - { - /* Call the error management function (command will be nacked */ - USBD_CtlError (pdev, req); - } - break; - } - } - return USBD_OK; -} - -/** - * @brief usbd_audio_EP0_RxReady - * Handles audio control requests data. - * @param pdev: device device instance - * @retval status - */ -static uint8_t usbd_audio_EP0_RxReady (void *pdev) -{ - /* Check if an AudioControl request has been issued */ - if (AudioCtlCmd == AUDIO_REQ_SET_CUR) - {/* In this driver, to simplify code, only SET_CUR request is managed */ - /* Check for which addressed unit the AudioControl request has been issued */ - if (AudioCtlUnit == AUDIO_OUT_STREAMING_CTRL) - {/* In this driver, to simplify code, only one unit is manage */ - /* Call the audio interface mute function */ - AUDIO_OUT_fops.MuteCtl(AudioCtl[0]); - - /* Reset the AudioCtlCmd variable to prevent re-entering this function */ - AudioCtlCmd = 0; - AudioCtlLen = 0; - } - } - - return USBD_OK; -} - -/** - * @brief usbd_audio_DataIn - * Handles the audio IN data stage. - * @param pdev: instance - * @param epnum: endpoint number - * @retval status - */ -static uint8_t usbd_audio_DataIn (void *pdev, uint8_t epnum) -{ - return USBD_OK; -} - -/** - * @brief usbd_audio_DataOut - * Handles the Audio Out data stage. - * @param pdev: instance - * @param epnum: endpoint number - * @retval status - */ -static uint8_t usbd_audio_DataOut (void *pdev, uint8_t epnum) -{ - if (epnum == AUDIO_OUT_EP) - { - /* Increment the Buffer pointer or roll it back when all buffers are full */ - if (IsocOutWrPtr >= (IsocOutBuff + (AUDIO_OUT_PACKET * OUT_PACKET_NUM))) - {/* All buffers are full: roll back */ - IsocOutWrPtr = IsocOutBuff; - } - else - {/* Increment the buffer pointer */ - IsocOutWrPtr += AUDIO_OUT_PACKET; - } - - /* Toggle the frame index */ - ((USB_OTG_CORE_HANDLE*)pdev)->dev.out_ep[epnum].even_odd_frame = - (((USB_OTG_CORE_HANDLE*)pdev)->dev.out_ep[epnum].even_odd_frame)? 0:1; - - /* Prepare Out endpoint to receive next audio packet */ - DCD_EP_PrepareRx(pdev, - AUDIO_OUT_EP, - (uint8_t*)(IsocOutWrPtr), - AUDIO_OUT_PACKET); - - /* Trigger the start of streaming only when half buffer is full */ - if ((PlayFlag == 0) && (IsocOutWrPtr >= (IsocOutBuff + ((AUDIO_OUT_PACKET * OUT_PACKET_NUM) / 2)))) - { - /* Enable start of Streaming */ - PlayFlag = 1; - } - } - - return USBD_OK; -} - -/** - * @brief usbd_audio_SOF - * Handles the SOF event (data buffer update and synchronization). - * @param pdev: instance - * @param epnum: endpoint number - * @retval status - */ -static uint8_t usbd_audio_SOF (void *pdev) -{ - /* Check if there are available data in stream buffer. - In this function, a single variable (PlayFlag) is used to avoid software delays. - The play operation must be executed as soon as possible after the SOF detection. */ - if (PlayFlag) - { - /* Start playing received packet */ - AUDIO_OUT_fops.AudioCmd((uint8_t*)(IsocOutRdPtr), /* Samples buffer pointer */ - AUDIO_OUT_PACKET, /* Number of samples in Bytes */ - AUDIO_CMD_PLAY); /* Command to be processed */ - - /* Increment the Buffer pointer or roll it back when all buffers all full */ - if (IsocOutRdPtr >= (IsocOutBuff + (AUDIO_OUT_PACKET * OUT_PACKET_NUM))) - {/* Roll back to the start of buffer */ - IsocOutRdPtr = IsocOutBuff; - } - else - {/* Increment to the next sub-buffer */ - IsocOutRdPtr += AUDIO_OUT_PACKET; - } - - /* If all available buffers have been consumed, stop playing */ - if (IsocOutRdPtr == IsocOutWrPtr) - { - /* Pause the audio stream */ - AUDIO_OUT_fops.AudioCmd((uint8_t*)(IsocOutBuff), /* Samples buffer pointer */ - AUDIO_OUT_PACKET, /* Number of samples in Bytes */ - AUDIO_CMD_PAUSE); /* Command to be processed */ - - /* Stop entering play loop */ - PlayFlag = 0; - - /* Reset buffer pointers */ - IsocOutRdPtr = IsocOutBuff; - IsocOutWrPtr = IsocOutBuff; - } - } - - return USBD_OK; -} - -/** - * @brief usbd_audio_OUT_Incplt - * Handles the iso out incomplete event. - * @param pdev: instance - * @retval status - */ -static uint8_t usbd_audio_OUT_Incplt (void *pdev) -{ - return USBD_OK; -} - -/****************************************************************************** - AUDIO Class requests management -******************************************************************************/ -/** - * @brief AUDIO_Req_GetCurrent - * Handles the GET_CUR Audio control request. - * @param pdev: instance - * @param req: setup class request - * @retval status - */ -static void AUDIO_Req_GetCurrent(void *pdev, USB_SETUP_REQ *req) -{ - /* Send the current mute state */ - USBD_CtlSendData (pdev, - AudioCtl, - req->wLength); -} - -/** - * @brief AUDIO_Req_SetCurrent - * Handles the SET_CUR Audio control request. - * @param pdev: instance - * @param req: setup class request - * @retval status - */ -static void AUDIO_Req_SetCurrent(void *pdev, USB_SETUP_REQ *req) -{ - if (req->wLength) - { - /* Prepare the reception of the buffer over EP0 */ - USBD_CtlPrepareRx (pdev, - AudioCtl, - req->wLength); - - /* Set the global variables indicating current request and its length - to the function usbd_audio_EP0_RxReady() which will process the request */ - AudioCtlCmd = AUDIO_REQ_SET_CUR; /* Set the request value */ - AudioCtlLen = req->wLength; /* Set the request data length */ - AudioCtlUnit = HIBYTE(req->wIndex); /* Set the request target unit */ - } -} - -/** - * @brief USBD_audio_GetCfgDesc - * Returns configuration descriptor. - * @param speed : current device speed - * @param length : pointer data length - * @retval pointer to descriptor buffer - */ -static uint8_t *USBD_audio_GetCfgDesc (uint8_t speed, uint16_t *length) -{ - *length = sizeof (usbd_audio_CfgDesc); - return usbd_audio_CfgDesc; -} -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/audio/src/usbd_audio_out_if.c b/lib/main/STM32_USB_Device_Library/Class/audio/src/usbd_audio_out_if.c deleted file mode 100644 index 21d98394f5..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/audio/src/usbd_audio_out_if.c +++ /dev/null @@ -1,318 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_audio_out_if.c - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief This file provides the Audio Out (palyback) interface API. - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "usbd_audio_core.h" -#include "usbd_audio_out_if.h" - - - - -/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY - * @{ - */ - - -/** @defgroup usbd_audio_out_if - * @brief usbd out interface module - * @{ - */ - -/** @defgroup usbd_audio_out_if_Private_TypesDefinitions - * @{ - */ -/** - * @} - */ - - -/** @defgroup usbd_audio_out_if_Private_Defines - * @{ - */ -/** - * @} - */ - - -/** @defgroup usbd_audio_out_if_Private_Macros - * @{ - */ -/** - * @} - */ - - -/** @defgroup usbd_audio_out_if_Private_FunctionPrototypes - * @{ - */ -static uint8_t Init (uint32_t AudioFreq, uint32_t Volume, uint32_t options); -static uint8_t DeInit (uint32_t options); -static uint8_t AudioCmd (uint8_t* pbuf, uint32_t size, uint8_t cmd); -static uint8_t VolumeCtl (uint8_t vol); -static uint8_t MuteCtl (uint8_t cmd); -static uint8_t PeriodicTC (uint8_t cmd); -static uint8_t GetState (void); - -/** - * @} - */ - -/** @defgroup usbd_audio_out_if_Private_Variables - * @{ - */ -AUDIO_FOPS_TypeDef AUDIO_OUT_fops = -{ - Init, - DeInit, - AudioCmd, - VolumeCtl, - MuteCtl, - PeriodicTC, - GetState -}; - -static uint8_t AudioState = AUDIO_STATE_INACTIVE; - -/** - * @} - */ - -/** @defgroup usbd_audio_out_if_Private_Functions - * @{ - */ - -/** - * @brief Init - * Initialize and configures all required resources for audio play function. - * @param AudioFreq: Statrtup audio frequency. - * @param Volume: Startup volume to be set. - * @param options: specific options passed to low layer function. - * @retval AUDIO_OK if all operations succeed, AUDIO_FAIL else. - */ -static uint8_t Init (uint32_t AudioFreq, - uint32_t Volume, - uint32_t options) -{ - static uint32_t Initialized = 0; - - /* Check if the low layer has already been initialized */ - if (Initialized == 0) - { - /* Call low layer function */ - if (EVAL_AUDIO_Init(OUTPUT_DEVICE_AUTO, Volume, AudioFreq) != 0) - { - AudioState = AUDIO_STATE_ERROR; - return AUDIO_FAIL; - } - - /* Set the Initialization flag to prevent reinitializing the interface again */ - Initialized = 1; - } - - /* Update the Audio state machine */ - AudioState = AUDIO_STATE_ACTIVE; - - return AUDIO_OK; -} - -/** - * @brief DeInit - * Free all resources used by low layer and stops audio-play function. - * @param options: options passed to low layer function. - * @retval AUDIO_OK if all operations succeed, AUDIO_FAIL else. - */ -static uint8_t DeInit (uint32_t options) -{ - /* Update the Audio state machine */ - AudioState = AUDIO_STATE_INACTIVE; - - return AUDIO_OK; -} - -/** - * @brief AudioCmd - * Play, Stop, Pause or Resume current file. - * @param pbuf: address from which file shoud be played. - * @param size: size of the current buffer/file. - * @param cmd: command to be executed, can be AUDIO_CMD_PLAY , AUDIO_CMD_PAUSE, - * AUDIO_CMD_RESUME or AUDIO_CMD_STOP. - * @retval AUDIO_OK if all operations succeed, AUDIO_FAIL else. - */ -static uint8_t AudioCmd(uint8_t* pbuf, - uint32_t size, - uint8_t cmd) -{ - /* Check the current state */ - if ((AudioState == AUDIO_STATE_INACTIVE) || (AudioState == AUDIO_STATE_ERROR)) - { - AudioState = AUDIO_STATE_ERROR; - return AUDIO_FAIL; - } - - switch (cmd) - { - /* Process the PLAY command ----------------------------*/ - case AUDIO_CMD_PLAY: - /* If current state is Active or Stopped */ - if ((AudioState == AUDIO_STATE_ACTIVE) || \ - (AudioState == AUDIO_STATE_STOPPED) || \ - (AudioState == AUDIO_STATE_PLAYING)) - { - Audio_MAL_Play((uint32_t)pbuf, (size/2)); - AudioState = AUDIO_STATE_PLAYING; - return AUDIO_OK; - } - /* If current state is Paused */ - else if (AudioState == AUDIO_STATE_PAUSED) - { - if (EVAL_AUDIO_PauseResume(AUDIO_RESUME, (uint32_t)pbuf, (size/2)) != 0) - { - AudioState = AUDIO_STATE_ERROR; - return AUDIO_FAIL; - } - else - { - AudioState = AUDIO_STATE_PLAYING; - return AUDIO_OK; - } - } - else /* Not allowed command */ - { - return AUDIO_FAIL; - } - - /* Process the STOP command ----------------------------*/ - case AUDIO_CMD_STOP: - if (AudioState != AUDIO_STATE_PLAYING) - { - /* Unsupported command */ - return AUDIO_FAIL; - } - else if (EVAL_AUDIO_Stop(CODEC_PDWN_SW) != 0) - { - AudioState = AUDIO_STATE_ERROR; - return AUDIO_FAIL; - } - else - { - AudioState = AUDIO_STATE_STOPPED; - return AUDIO_OK; - } - - /* Process the PAUSE command ---------------------------*/ - case AUDIO_CMD_PAUSE: - if (AudioState != AUDIO_STATE_PLAYING) - { - /* Unsupported command */ - return AUDIO_FAIL; - } - else if (EVAL_AUDIO_PauseResume(AUDIO_PAUSE, (uint32_t)pbuf, (size/2)) != 0) - { - AudioState = AUDIO_STATE_ERROR; - return AUDIO_FAIL; - } - else - { - AudioState = AUDIO_STATE_PAUSED; - return AUDIO_OK; - } - - /* Unsupported command ---------------------------------*/ - default: - return AUDIO_FAIL; - } -} - -/** - * @brief VolumeCtl - * Set the volume level in % - * @param vol: volume level to be set in % (from 0% to 100%) - * @retval AUDIO_OK if all operations succeed, AUDIO_FAIL else. - */ -static uint8_t VolumeCtl (uint8_t vol) -{ - /* Call low layer volume setting function */ - if (EVAL_AUDIO_VolumeCtl(vol) != 0) - { - AudioState = AUDIO_STATE_ERROR; - return AUDIO_FAIL; - } - - return AUDIO_OK; -} - -/** - * @brief MuteCtl - * Mute or Unmute the audio current output - * @param cmd: can be 0 to unmute, or 1 to mute. - * @retval AUDIO_OK if all operations succeed, AUDIO_FAIL else. - */ -static uint8_t MuteCtl (uint8_t cmd) -{ - /* Call low layer mute setting function */ - if (EVAL_AUDIO_Mute(cmd) != 0) - { - AudioState = AUDIO_STATE_ERROR; - return AUDIO_FAIL; - } - - return AUDIO_OK; -} - -/** - * @brief - * - * @param - * @param - * @retval AUDIO_OK if all operations succeed, AUDIO_FAIL else. - */ -static uint8_t PeriodicTC (uint8_t cmd) -{ - - - return AUDIO_OK; -} - - -/** - * @brief GetState - * Return the current state of the audio machine - * @param None - * @retval Current State. - */ -static uint8_t GetState (void) -{ - return AudioState; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/cdc/inc/usbd_cdc_core.h b/lib/main/STM32_USB_Device_Library/Class/cdc/inc/usbd_cdc_core.h index f68ab5c669..b9afa7423d 100644 --- a/lib/main/STM32_USB_Device_Library/Class/cdc/inc/usbd_cdc_core.h +++ b/lib/main/STM32_USB_Device_Library/Class/cdc/inc/usbd_cdc_core.h @@ -2,20 +2,26 @@ ****************************************************************************** * @file usbd_cdc_core.h * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 + * @version V1.2.0 + * @date 09-November-2015 * @brief header file for the usbd_cdc_core.c file. ****************************************************************************** * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -41,10 +47,6 @@ */ #define USB_CDC_CONFIG_DESC_SIZ (67) #define USB_CDC_DESC_SIZ (67-9) -#define CDC_DATA_IN_PACKET_SIZE *(uint16_t *)(((USB_OTG_CORE_HANDLE *)pdev)->dev.pConfig_descriptor + 57) -#define CDC_DATA_OUT_PACKET_SIZE *(uint16_t *)(((USB_OTG_CORE_HANDLE *)pdev)->dev.pConfig_descriptor + 64) - -#define CDC_DESCRIPTOR_TYPE 0x21 #define DEVICE_CLASS_CDC 0x02 #define DEVICE_SUBCLASS_CDC 0x00 @@ -58,6 +60,9 @@ #define STANDARD_ENDPOINT_DESC_SIZE 0x09 +#define CDC_DATA_IN_PACKET_SIZE CDC_DATA_MAX_PACKET_SIZE + +#define CDC_DATA_OUT_PACKET_SIZE CDC_DATA_MAX_PACKET_SIZE /*---------------------------------------------------------------------*/ /* CDC definitions */ @@ -124,7 +129,7 @@ extern USBD_Class_cb_TypeDef USBD_CDC_cb; * @} */ -#endif // __USB_CDC_CORE_H_ +#endif /* __USB_CDC_CORE_H_ */ /** * @} */ @@ -133,4 +138,4 @@ extern USBD_Class_cb_TypeDef USBD_CDC_cb; * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/cdc/inc/usbd_cdc_if_template.h b/lib/main/STM32_USB_Device_Library/Class/cdc/inc/usbd_cdc_if_template.h deleted file mode 100644 index 1a12508e67..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/cdc/inc/usbd_cdc_if_template.h +++ /dev/null @@ -1,45 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_cdc_if_template.h - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief Header for dfu_mal.c file. - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USBD_CDC_IF_TEMPLATE_H -#define __USBD_CDC_IF_TEMPLATE_H - -/* Includes ------------------------------------------------------------------*/ -#ifdef STM32F2XX - #include "stm32f2xx.h" -#elif defined(STM32F10X_CL) - #include "stm32f10x.h" -#endif /* STM32F2XX */ - -#include "usbd_conf.h" -#include "usbd_cdc_core.h" - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ - -extern CDC_IF_Prop_TypeDef TEMPLATE_fops; - -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions ------------------------------------------------------- */ -#endif /* __USBD_CDC_IF_TEMPLATE_H */ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/cdc/src/usbd_cdc_core.c b/lib/main/STM32_USB_Device_Library/Class/cdc/src/usbd_cdc_core.c index ac441e7bc1..62f54262e0 100644 --- a/lib/main/STM32_USB_Device_Library/Class/cdc/src/usbd_cdc_core.c +++ b/lib/main/STM32_USB_Device_Library/Class/cdc/src/usbd_cdc_core.c @@ -2,8 +2,8 @@ ****************************************************************************** * @file usbd_cdc_core.c * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 + * @version V1.2.0 + * @date 09-November-2015 * @brief This file provides the high layer firmware functions to manage the * following functionalities of the USB CDC Class: * - Initialization and Configuration of high and low layer @@ -43,17 +43,23 @@ * * @endverbatim * - ****************************************************************************** + ****************************************************************************** * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -84,6 +90,11 @@ /** @defgroup usbd_cdc_Private_Defines * @{ */ + +#define USB_CDC_IDLE 0 +#define USB_CDC_BUSY 1 +#define USB_CDC_ZLP 2 + /** * @} */ @@ -104,13 +115,13 @@ /********************************************* CDC Device library callbacks *********************************************/ -static uint8_t usbd_cdc_Init (void *pdev, uint8_t cfgidx); -static uint8_t usbd_cdc_DeInit (void *pdev, uint8_t cfgidx); -static uint8_t usbd_cdc_Setup (void *pdev, USB_SETUP_REQ *req); -static uint8_t usbd_cdc_EP0_RxReady (void *pdev); -static uint8_t usbd_cdc_DataIn (void *pdev, uint8_t epnum); -static uint8_t usbd_cdc_DataOut (void *pdev, uint8_t epnum); -static uint8_t usbd_cdc_SOF (void *pdev); +uint8_t usbd_cdc_Init (void *pdev, uint8_t cfgidx); +uint8_t usbd_cdc_DeInit (void *pdev, uint8_t cfgidx); +uint8_t usbd_cdc_Setup (void *pdev, USB_SETUP_REQ *req); +uint8_t usbd_cdc_EP0_RxReady (void *pdev); +uint8_t usbd_cdc_DataIn (void *pdev, uint8_t epnum); +uint8_t usbd_cdc_DataOut (void *pdev, uint8_t epnum); +uint8_t usbd_cdc_SOF (void *pdev); /********************************************* CDC specific management functions @@ -163,7 +174,7 @@ __ALIGN_BEGIN uint8_t USB_Rx_Buffer [CDC_DATA_MAX_PACKET_SIZE] __ALIGN_END ; #pragma data_alignment=4 #endif #endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ -__ALIGN_BEGIN uint8_t APP_Rx_Buffer [APP_RX_DATA_SIZE] __ALIGN_END ; +__ALIGN_BEGIN uint8_t APP_Rx_Buffer [APP_RX_DATA_SIZE] __ALIGN_END ; #ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED @@ -177,7 +188,7 @@ uint32_t APP_Rx_ptr_in = 0; uint32_t APP_Rx_ptr_out = 0; uint32_t APP_Rx_length = 0; -volatile uint8_t USB_Tx_State = 0; +uint8_t USB_Tx_State = USB_CDC_IDLE; static uint32_t cdcCmd = 0xFF; static uint32_t cdcLen = 0; @@ -218,7 +229,7 @@ __ALIGN_BEGIN uint8_t usbd_cdc_CfgDesc[USB_CDC_CONFIG_DESC_SIZ] __ALIGN_END = 0x01, /* bConfigurationValue: Configuration value */ 0x00, /* iConfiguration: Index of string descriptor describing the configuration */ 0xC0, /* bmAttributes: self powered */ - 0xfa, /* MaxPower 500 mA */ + 0x32, /* MaxPower 0 mA */ /*---------------------------------------------------------------------------*/ @@ -314,7 +325,7 @@ __ALIGN_BEGIN uint8_t usbd_cdc_CfgDesc[USB_CDC_CONFIG_DESC_SIZ] __ALIGN_END = #endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ __ALIGN_BEGIN uint8_t usbd_cdc_OtherCfgDesc[USB_CDC_CONFIG_DESC_SIZ] __ALIGN_END = { - 0x09, /* bLength: Configuation Descriptor size */ + 0x09, /* bLength: Configuration Descriptor size */ USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION, USB_CDC_CONFIG_DESC_SIZ, 0x00, @@ -415,12 +426,12 @@ __ALIGN_BEGIN uint8_t usbd_cdc_OtherCfgDesc[USB_CDC_CONFIG_DESC_SIZ] __ALIGN_EN /** * @brief usbd_cdc_Init - * Initilaize the CDC interface + * Initialize the CDC interface * @param pdev: device instance * @param cfgidx: Configuration index * @retval status */ -static uint8_t usbd_cdc_Init (void *pdev, +uint8_t usbd_cdc_Init (void *pdev, uint8_t cfgidx) { uint8_t *pbuf; @@ -468,7 +479,7 @@ static uint8_t usbd_cdc_Init (void *pdev, * @param cfgidx: Configuration index * @retval status */ -static uint8_t usbd_cdc_DeInit (void *pdev, +uint8_t usbd_cdc_DeInit (void *pdev, uint8_t cfgidx) { (void)pdev; @@ -498,12 +509,9 @@ static uint8_t usbd_cdc_DeInit (void *pdev, * @param req: usb requests * @retval status */ -static uint8_t usbd_cdc_Setup (void *pdev, +uint8_t usbd_cdc_Setup (void *pdev, USB_SETUP_REQ *req) { - uint16_t len = 0; - uint8_t *pbuf; - switch (req->bmRequest & USB_REQ_TYPE_MASK) { /* CDC Class Requests -------------------------------*/ @@ -522,7 +530,7 @@ static uint8_t usbd_cdc_Setup (void *pdev, CmdBuff, req->wLength); } - else /* Host-to-Device requeset */ + else /* Host-to-Device request */ { /* Set the value of the current command to be processed */ cdcCmd = req->bRequest; @@ -548,27 +556,13 @@ static uint8_t usbd_cdc_Setup (void *pdev, USBD_CtlError (pdev, req); return USBD_FAIL; - - /* Standard Requests -------------------------------*/ case USB_REQ_TYPE_STANDARD: switch (req->bRequest) { case USB_REQ_GET_DESCRIPTOR: - if( (req->wValue >> 8) == CDC_DESCRIPTOR_TYPE) - { -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - pbuf = usbd_cdc_Desc; -#else - pbuf = usbd_cdc_CfgDesc + 9 + (9 * USBD_ITF_MAX_NUM); -#endif - len = MIN(USB_CDC_DESC_SIZ , req->wLength); - } - - USBD_CtlSendData (pdev, - pbuf, - len); - break; + USBD_CtlError (pdev, req); + return USBD_FAIL; case USB_REQ_GET_INTERFACE : USBD_CtlSendData (pdev, @@ -595,10 +589,10 @@ static uint8_t usbd_cdc_Setup (void *pdev, /** * @brief usbd_cdc_EP0_RxReady * Data received on control endpoint - * @param pdev: device device instance + * @param pdev: device instance * @retval status */ -static uint8_t usbd_cdc_EP0_RxReady (void *pdev) +uint8_t usbd_cdc_EP0_RxReady (void *pdev) { (void)pdev; if (cdcCmd != NO_CMD) @@ -613,6 +607,7 @@ static uint8_t usbd_cdc_EP0_RxReady (void *pdev) return USBD_OK; } + /** * @brief usbd_audio_DataIn * Data sent on non-control IN endpoint @@ -620,18 +615,18 @@ static uint8_t usbd_cdc_EP0_RxReady (void *pdev) * @param epnum: endpoint number * @retval status */ -static uint8_t usbd_cdc_DataIn (void *pdev, uint8_t epnum) +uint8_t usbd_cdc_DataIn (void *pdev, uint8_t epnum) { (void)pdev; (void)epnum; uint16_t USB_Tx_ptr; uint16_t USB_Tx_length; - - if (USB_Tx_State == 1) + + if (USB_Tx_State == USB_CDC_BUSY) { if (APP_Rx_length == 0) { - USB_Tx_State = 0; + USB_Tx_State = USB_CDC_IDLE; } else { @@ -649,6 +644,10 @@ static uint8_t usbd_cdc_DataIn (void *pdev, uint8_t epnum) APP_Rx_ptr_out += APP_Rx_length; APP_Rx_length = 0; + if(USB_Tx_length == CDC_DATA_IN_PACKET_SIZE) + { + USB_Tx_State = USB_CDC_ZLP; + } } /* Prepare the available data buffer to be sent on IN endpoint */ @@ -656,20 +655,32 @@ static uint8_t usbd_cdc_DataIn (void *pdev, uint8_t epnum) CDC_IN_EP, (uint8_t*)&APP_Rx_Buffer[USB_Tx_ptr], USB_Tx_length); + return USBD_OK; } } + /* Avoid any asynchronous transfer during ZLP */ + if (USB_Tx_State == USB_CDC_ZLP) + { + /*Send ZLP to indicate the end of the current transfer */ + DCD_EP_Tx (pdev, + CDC_IN_EP, + NULL, + 0); + + USB_Tx_State = USB_CDC_IDLE; + } return USBD_OK; } /** - * @brief usbd_audio_DataOut + * @brief usbd_cdc_DataOut * Data received on non-control Out endpoint * @param pdev: device instance * @param epnum: endpoint number * @retval status */ -static uint8_t usbd_cdc_DataOut (void *pdev, uint8_t epnum) +uint8_t usbd_cdc_DataOut (void *pdev, uint8_t epnum) { uint16_t USB_Rx_Cnt; @@ -677,7 +688,7 @@ static uint8_t usbd_cdc_DataOut (void *pdev, uint8_t epnum) USB_Rx_Cnt = ((USB_OTG_CORE_HANDLE*)pdev)->dev.out_ep[epnum].xfer_count; /* USB data will be immediately processed, this allow next USB traffic being - NAKed till the end of the application Xfer */ + NAKed till the end of the application Xfer */ APP_FOPS.pIf_DataRx(USB_Rx_Buffer, USB_Rx_Cnt); /* Prepare Out endpoint to receive next packet */ @@ -685,7 +696,7 @@ static uint8_t usbd_cdc_DataOut (void *pdev, uint8_t epnum) CDC_OUT_EP, (uint8_t*)(USB_Rx_Buffer), CDC_DATA_OUT_PACKET_SIZE); - + return USBD_OK; } @@ -696,7 +707,7 @@ static uint8_t usbd_cdc_DataOut (void *pdev, uint8_t epnum) * @param epnum: endpoint number * @retval status */ -static uint8_t usbd_cdc_SOF (void *pdev) +uint8_t usbd_cdc_SOF (void *pdev) { static uint32_t FrameCount = 0; @@ -723,29 +734,31 @@ static void Handle_USBAsynchXfer (void *pdev) uint16_t USB_Tx_ptr; uint16_t USB_Tx_length; - if(USB_Tx_State != 1) + if(USB_Tx_State == USB_CDC_IDLE) { if (APP_Rx_ptr_out == APP_RX_DATA_SIZE) { APP_Rx_ptr_out = 0; } - if(APP_Rx_ptr_out == APP_Rx_ptr_in) + if(APP_Rx_ptr_out == APP_Rx_ptr_in) { - USB_Tx_State = 0; + USB_Tx_State = USB_CDC_IDLE; return; } if(APP_Rx_ptr_out > APP_Rx_ptr_in) /* rollback */ { APP_Rx_length = APP_RX_DATA_SIZE - APP_Rx_ptr_out; + } else { APP_Rx_length = APP_Rx_ptr_in - APP_Rx_ptr_out; + } #ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - APP_Rx_length &= ~0x03; + APP_Rx_length &= ~0x03; #endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ if (APP_Rx_length > CDC_DATA_IN_PACKET_SIZE) @@ -755,6 +768,7 @@ static void Handle_USBAsynchXfer (void *pdev) APP_Rx_ptr_out += CDC_DATA_IN_PACKET_SIZE; APP_Rx_length -= CDC_DATA_IN_PACKET_SIZE; + USB_Tx_State = USB_CDC_BUSY; } else { @@ -763,15 +777,21 @@ static void Handle_USBAsynchXfer (void *pdev) APP_Rx_ptr_out += APP_Rx_length; APP_Rx_length = 0; + if(USB_Tx_length == CDC_DATA_IN_PACKET_SIZE) + { + USB_Tx_State = USB_CDC_ZLP; + } + else + { + USB_Tx_State = USB_CDC_BUSY; + } } - USB_Tx_State = 1; - + DCD_EP_Tx (pdev, CDC_IN_EP, (uint8_t*)&APP_Rx_Buffer[USB_Tx_ptr], USB_Tx_length); } - } /** @@ -814,4 +834,4 @@ static uint8_t *USBD_cdc_GetOtherCfgDesc (uint8_t speed, uint16_t *length) * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/cdc/src/usbd_cdc_if_template.c b/lib/main/STM32_USB_Device_Library/Class/cdc/src/usbd_cdc_if_template.c deleted file mode 100644 index 406f30a220..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/cdc/src/usbd_cdc_if_template.c +++ /dev/null @@ -1,202 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_cdc_if_template.c - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief Generic media access Layer. - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED -#pragma data_alignment = 4 -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ - -/* Includes ------------------------------------------------------------------*/ -#include "usbd_cdc_if_template.h" -#include "stm32_eval.h" - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* These are external variables imported from CDC core to be used for IN - transfer management. */ -extern uint8_t APP_Rx_Buffer []; /* Write CDC received data in this buffer. - These data will be sent over USB IN endpoint - in the CDC core functions. */ -extern uint32_t APP_Rx_ptr_in; /* Increment this pointer or roll it back to - start address when writing received data - in the buffer APP_Rx_Buffer. */ - -/* Private function prototypes -----------------------------------------------*/ -static uint16_t TEMPLATE_Init (void); -static uint16_t TEMPLATE_DeInit (void); -static uint16_t TEMPLATE_Ctrl (uint32_t Cmd, uint8_t* Buf, uint32_t Len); -static uint16_t TEMPLATE_DataTx (uint8_t* Buf, uint32_t Len); -static uint16_t TEMPLATE_DataRx (uint8_t* Buf, uint32_t Len); - -CDC_IF_Prop_TypeDef TEMPLATE_fops = -{ - TEMPLATE_Init, - TEMPLATE_DeInit, - TEMPLATE_Ctrl, - TEMPLATE_DataTx, - TEMPLATE_DataRx -}; - -/* Private functions ---------------------------------------------------------*/ - -/** - * @brief TEMPLATE_Init - * Initializes the CDC media low layer - * @param None - * @retval Result of the opeartion: USBD_OK if all operations are OK else USBD_FAIL - */ -static uint16_t TEMPLATE_Init(void) -{ - /* - Add your initialization code here - */ - return USBD_OK; -} - -/** - * @brief TEMPLATE_DeInit - * DeInitializes the CDC media low layer - * @param None - * @retval Result of the opeartion: USBD_OK if all operations are OK else USBD_FAIL - */ -static uint16_t TEMPLATE_DeInit(void) -{ - /* - Add your deinitialization code here - */ - return USBD_OK; -} - - -/** - * @brief TEMPLATE_Ctrl - * Manage the CDC class requests - * @param Cmd: Command code - * @param Buf: Buffer containing command data (request parameters) - * @param Len: Number of data to be sent (in bytes) - * @retval Result of the opeartion: USBD_OK if all operations are OK else USBD_FAIL - */ -static uint16_t TEMPLATE_Ctrl (uint32_t Cmd, uint8_t* Buf, uint32_t Len) -{ - switch (Cmd) - { - case SEND_ENCAPSULATED_COMMAND: - /* Add your code here */ - break; - - case GET_ENCAPSULATED_RESPONSE: - /* Add your code here */ - break; - - case SET_COMM_FEATURE: - /* Add your code here */ - break; - - case GET_COMM_FEATURE: - /* Add your code here */ - break; - - case CLEAR_COMM_FEATURE: - /* Add your code here */ - break; - - case SET_LINE_CODING: - /* Add your code here */ - break; - - case GET_LINE_CODING: - /* Add your code here */ - break; - - case SET_CONTROL_LINE_STATE: - /* Add your code here */ - break; - - case SEND_BREAK: - /* Add your code here */ - break; - - default: - break; - } - - return USBD_OK; -} - -/** - * @brief TEMPLATE_DataTx - * CDC received data to be send over USB IN endpoint are managed in - * this function. - * @param Buf: Buffer of data to be sent - * @param Len: Number of data to be sent (in bytes) - * @retval Result of the opeartion: USBD_OK if all operations are OK else USBD_FAIL - */ -static uint16_t TEMPLATE_DataTx (uint8_t* Buf, uint32_t Len) -{ - - /* Get the data to be sent */ - for (i = 0; i < Len; i++) - { - /* APP_Rx_Buffer[APP_Rx_ptr_in] = XXX_ReceiveData(XXX); */ - } - - /* Increment the in pointer */ - APP_Rx_ptr_in++; - - /* To avoid buffer overflow */ - if(APP_Rx_ptr_in == APP_RX_DATA_SIZE) - { - APP_Rx_ptr_in = 0; - } - - return USBD_OK; -} - -/** - * @brief TEMPLATE_DataRx - * Data received over USB OUT endpoint are sent over CDC interface - * through this function. - * - * @note - * This function will block any OUT packet reception on USB endpoint - * untill exiting this function. If you exit this function before transfer - * is complete on CDC interface (ie. using DMA controller) it will result - * in receiving more data while previous ones are still not sent. - * - * @param Buf: Buffer of data to be received - * @param Len: Number of data received (in bytes) - * @retval Result of the opeartion: USBD_OK if all operations are OK else USBD_FAIL - */ -static uint16_t TEMPLATE_DataRx (uint8_t* Buf, uint32_t Len) -{ - uint32_t i; - - /* Send the received buffer */ - for (i = 0; i < Len; i++) - { - /* XXXX_SendData(XXXX, *(Buf + i) ); */ - } - - return USBD_OK; -} - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/dfu/inc/usbd_dfu_core.h b/lib/main/STM32_USB_Device_Library/Class/dfu/inc/usbd_dfu_core.h deleted file mode 100644 index aadffb148a..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/dfu/inc/usbd_dfu_core.h +++ /dev/null @@ -1,187 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_dfu_core.h - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief header file for the usbd_dfu_core.c file. - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ - -#ifndef __USB_DFU_CORE_H_ -#define __USB_DFU_CORE_H_ - -#include "usbd_ioreq.h" -#include "usbd_dfu_mal.h" - -/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY - * @{ - */ - -/** @defgroup usbd_dfu - * @brief This file is the Header file for USBD_dfu.c - * @{ - */ - - -/** @defgroup usbd_dfu_Exported_Defines - * @{ - */ -#define USB_DFU_CONFIG_DESC_SIZ (18 + (9 * USBD_ITF_MAX_NUM)) -#define USB_DFU_DESC_SIZ 9 - -#define DFU_DESCRIPTOR_TYPE 0x21 - - -/*---------------------------------------------------------------------*/ -/* DFU definitions */ -/*---------------------------------------------------------------------*/ - - - -/**************************************************/ -/* DFU Requests DFU states */ -/**************************************************/ - - -#define STATE_appIDLE 0 -#define STATE_appDETACH 1 -#define STATE_dfuIDLE 2 -#define STATE_dfuDNLOAD_SYNC 3 -#define STATE_dfuDNBUSY 4 -#define STATE_dfuDNLOAD_IDLE 5 -#define STATE_dfuMANIFEST_SYNC 6 -#define STATE_dfuMANIFEST 7 -#define STATE_dfuMANIFEST_WAIT_RESET 8 -#define STATE_dfuUPLOAD_IDLE 9 -#define STATE_dfuERROR 10 - -/**************************************************/ -/* DFU Requests DFU status */ -/**************************************************/ - -#define STATUS_OK 0x00 -#define STATUS_ERRTARGET 0x01 -#define STATUS_ERRFILE 0x02 -#define STATUS_ERRWRITE 0x03 -#define STATUS_ERRERASE 0x04 -#define STATUS_ERRCHECK_ERASED 0x05 -#define STATUS_ERRPROG 0x06 -#define STATUS_ERRVERIFY 0x07 -#define STATUS_ERRADDRESS 0x08 -#define STATUS_ERRNOTDONE 0x09 -#define STATUS_ERRFIRMWARE 0x0A -#define STATUS_ERRVENDOR 0x0B -#define STATUS_ERRUSBR 0x0C -#define STATUS_ERRPOR 0x0D -#define STATUS_ERRUNKNOWN 0x0E -#define STATUS_ERRSTALLEDPKT 0x0F - -/**************************************************/ -/* DFU Requests DFU states Manifestation State */ -/**************************************************/ - -#define Manifest_complete 0x00 -#define Manifest_In_Progress 0x01 - - -/**************************************************/ -/* Special Commands with Download Request */ -/**************************************************/ - -#define CMD_GETCOMMANDS 0x00 -#define CMD_SETADDRESSPOINTER 0x21 -#define CMD_ERASE 0x41 - -/**************************************************/ -/* Other defines */ -/**************************************************/ -/* Bit Detach capable = bit 3 in bmAttributes field */ -#define DFU_DETACH_MASK (uint8_t)(1 << 4) -/** - * @} - */ - - -/** @defgroup USBD_CORE_Exported_TypesDefinitions - * @{ - */ -/**************************************************/ -/* DFU Requests */ -/**************************************************/ - -typedef enum _DFU_REQUESTS { - DFU_DETACH = 0, - DFU_DNLOAD = 1, - DFU_UPLOAD, - DFU_GETSTATUS, - DFU_CLRSTATUS, - DFU_GETSTATE, - DFU_ABORT -} DFU_REQUESTS; - -typedef void (*pFunction)(void); -/** - * @} - */ - - - -/** @defgroup USBD_CORE_Exported_Macros - * @{ - */ -/********** Descriptor of DFU interface 0 Alternate setting n ****************/ -#define USBD_DFU_IF_DESC(n) 0x09, /* bLength: Interface Descriptor size */ \ - USB_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */ \ - 0x00, /* bInterfaceNumber: Number of Interface */ \ - (n), /* bAlternateSetting: Alternate setting */ \ - 0x00, /* bNumEndpoints*/ \ - 0xFE, /* bInterfaceClass: Application Specific Class Code */ \ - 0x01, /* bInterfaceSubClass : Device Firmware Upgrade Code */ \ - 0x02, /* nInterfaceProtocol: DFU mode protocol */ \ - USBD_IDX_INTERFACE_STR + (n) + 1 /* iInterface: Index of string descriptor */ \ - /* 18 */ - -/** - * @} - */ - -/** @defgroup USBD_CORE_Exported_Variables - * @{ - */ - -extern USBD_Class_cb_TypeDef DFU_cb; -/** - * @} - */ - -/** @defgroup USB_CORE_Exported_Functions - * @{ - */ -/** - * @} - */ - -#endif // __USB_DFU_CORE_H_ -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/dfu/inc/usbd_dfu_mal.h b/lib/main/STM32_USB_Device_Library/Class/dfu/inc/usbd_dfu_mal.h deleted file mode 100644 index 9ed095b736..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/dfu/inc/usbd_dfu_mal.h +++ /dev/null @@ -1,79 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_dfu_mal.h - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief Header for usbd_dfu_mal.c file. - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __DFU_MAL_H -#define __DFU_MAL_H - -/* Includes ------------------------------------------------------------------*/ -#ifdef STM32F2XX - #include "stm32f2xx.h" -#elif defined(STM32F10X_CL) - #include "stm32f10x.h" -#endif /* STM32F2XX */ - -#include "usbd_conf.h" -#include "usbd_dfu_core.h" - -/* Exported types ------------------------------------------------------------*/ -typedef struct _DFU_MAL_PROP -{ - const uint8_t* pStrDesc; - uint16_t (*pMAL_Init) (void); - uint16_t (*pMAL_DeInit) (void); - uint16_t (*pMAL_Erase) (uint32_t Add); - uint16_t (*pMAL_Write) (uint32_t Add, uint32_t Len); - uint8_t *(*pMAL_Read) (uint32_t Add, uint32_t Len); - uint16_t (*pMAL_CheckAdd) (uint32_t Add); - const uint32_t EraseTiming; - const uint32_t WriteTiming; -} -DFU_MAL_Prop_TypeDef; - - -/* Exported constants --------------------------------------------------------*/ -#define MAL_OK 0 -#define MAL_FAIL 1 - -/* utils macro ---------------------------------------------------------------*/ -#define _1st_BYTE(x) (uint8_t)((x)&0xFF) /* 1st addressing cycle */ -#define _2nd_BYTE(x) (uint8_t)(((x)&0xFF00)>>8) /* 2nd addressing cycle */ -#define _3rd_BYTE(x) (uint8_t)(((x)&0xFF0000)>>16) /* 3rd addressing cycle */ -#define _4th_BYTE(x) (uint8_t)(((x)&0xFF000000)>>24) /* 4th addressing cycle */ - -/* Exported macro ------------------------------------------------------------*/ -#define SET_POLLING_TIMING(x) buffer[1] = _1st_BYTE(x);\ - buffer[2] = _2nd_BYTE(x);\ - buffer[3] = _3rd_BYTE(x); - -/* Exported functions ------------------------------------------------------- */ - -uint16_t MAL_Init (void); -uint16_t MAL_DeInit (void); -uint16_t MAL_Erase (uint32_t SectorAddress); -uint16_t MAL_Write (uint32_t SectorAddress, uint32_t DataLength); -uint8_t *MAL_Read (uint32_t SectorAddress, uint32_t DataLength); -uint16_t MAL_GetStatus(uint32_t SectorAddress ,uint8_t Cmd, uint8_t *buffer); - -extern uint8_t MAL_Buffer[XFERSIZE]; /* RAM Buffer for Downloaded Data */ -#endif /* __DFU_MAL_H */ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/dfu/inc/usbd_flash_if.h b/lib/main/STM32_USB_Device_Library/Class/dfu/inc/usbd_flash_if.h deleted file mode 100644 index 07e49dfb2b..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/dfu/inc/usbd_flash_if.h +++ /dev/null @@ -1,49 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_flash_if.h - * @author MCD Application Team - * @version V1.0.0RC1 - * @date 18-March-2011 - * @brief Header for usbd_flash_if.c file. - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __FLASH_IF_MAL_H -#define __FLASH_IF_MAL_H - -/* Includes ------------------------------------------------------------------*/ -#include "usbd_dfu_mal.h" - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -#define FLASH_START_ADD 0x08000000 - -#ifdef STM32F2XX - #define FLASH_END_ADD 0x08100000 - #define FLASH_IF_STRING "@Internal Flash /0x08000000/03*016Ka,01*016Kg,01*064Kg,07*128Kg" -#elif defined(STM32F10X_CL) - #define FLASH_END_ADD 0x08040000 - #define FLASH_IF_STRING "@Internal Flash /0x08000000/06*002Ka,122*002Kg" -#endif /* STM32F2XX */ - - -extern DFU_MAL_Prop_TypeDef DFU_Flash_cb; - -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions ------------------------------------------------------- */ - -#endif /* __FLASH_IF_MAL_H */ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/dfu/inc/usbd_mem_if_template.h b/lib/main/STM32_USB_Device_Library/Class/dfu/inc/usbd_mem_if_template.h deleted file mode 100644 index d1e0dda9a3..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/dfu/inc/usbd_mem_if_template.h +++ /dev/null @@ -1,46 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_mem_if_template.h - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief Header for usbd_mem_if_template.c file. - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __MEM_IF_MAL_H -#define __MEM_IF_MAL_H - -/* Includes ------------------------------------------------------------------*/ -#ifdef STM32F2XX - #include "stm32f2xx.h" -#endif /* STM32F2XX */ -#include "usbd_dfu_mal.h" - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -#define MEM_START_ADD 0x00000000 /* Dummy start address */ -#define MEM_END_ADD (uint32_t)(MEM_START_ADD + (5 * 1024)) /* Dummy Size = 5KB */ - -#define MEM_IF_STRING "@Dummy Memory /0x00000000/01*002Kg,03*001Kg" - -extern DFU_MAL_Prop_TypeDef DFU_Mem_cb; - -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions ------------------------------------------------------- */ - -#endif /* __MEM_IF_MAL_H */ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/dfu/inc/usbd_otp_if.h b/lib/main/STM32_USB_Device_Library/Class/dfu/inc/usbd_otp_if.h deleted file mode 100644 index ef7e06101b..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/dfu/inc/usbd_otp_if.h +++ /dev/null @@ -1,43 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_otp_if.h - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief Header for usbd_otp_if.c file. - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __OTP_IF_MAL_H -#define __OTP_IF_MAL_H - -/* Includes ------------------------------------------------------------------*/ -#include "usbd_dfu_mal.h" - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -#define OTP_START_ADD 0x1FFF7800 -#define OTP_END_ADD (uint32_t)(OTP_START_ADD + 528) - -#define OTP_IF_STRING "@OTP Area /0x1FFF7800/01*512 g,01*016 g" - -extern DFU_MAL_Prop_TypeDef DFU_Otp_cb; - -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions ------------------------------------------------------- */ - -#endif /* __OTP_IF_MAL_H */ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_dfu_core.c b/lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_dfu_core.c deleted file mode 100644 index 316031672c..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_dfu_core.c +++ /dev/null @@ -1,1046 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_dfu_core.c - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief This file provides the high layer firmware functions to manage the - * following functionalities of the USB DFU Class: - * - Initialization and Configuration of high and low layer - * - Enumeration as DFU Device (and enumeration for each implemented memory interface) - * - Transfers to/from memory interfaces - * - Easy-to-customize "plug-in-like" modules for adding/removing memory interfaces. - * - Error management - * - * @verbatim - * - * =================================================================== - * DFU Class Driver Description - * =================================================================== - * This driver manages the DFU class V1.1 following the "Device Class Specification for - * Device Firmware Upgrade Version 1.1 Aug 5, 2004". - * This driver implements the following aspects of the specification: - * - Device descriptor management - * - Configuration descriptor management - * - Enumeration as DFU device (in DFU mode only) - * - Requests management (supporting ST DFU sub-protocol) - * - Memory operations management (Download/Upload/Erase/Detach/GetState/GetStatus) - * - DFU state machine implementation. - * - * @note - * ST DFU sub-protocol is compliant with DFU protocol and use sub-requests to manage - * memory addressing, commands processing, specific memories operations (ie. Erase) ... - * As required by the DFU specification, only endpoint 0 is used in this application. - * Other endpoints and functions may be added to the application (ie. DFU ...) - * - * These aspects may be enriched or modified for a specific user application. - * - * This driver doesn't implement the following aspects of the specification - * (but it is possible to manage these features with some modifications on this driver): - * - Manifestation Tolerant mode - * - * @endverbatim - * - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "usbd_dfu_core.h" -#include "usbd_desc.h" -#include "usbd_req.h" -#include "usb_bsp.h" - - -/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY - * @{ - */ - - -/** @defgroup usbd_dfu - * @brief usbd core module - * @{ - */ - -/** @defgroup usbd_dfu_Private_TypesDefinitions - * @{ - */ -/** - * @} - */ - - -/** @defgroup usbd_dfu_Private_Defines - * @{ - */ -/** - * @} - */ - - -/** @defgroup usbd_dfu_Private_Macros - * @{ - */ -/** - * @} - */ - - -/** @defgroup usbd_dfu_Private_FunctionPrototypes - * @{ - */ - -/********************************************* - DFU Device library callbacks - *********************************************/ -static uint8_t usbd_dfu_Init (void *pdev, - uint8_t cfgidx); - -static uint8_t usbd_dfu_DeInit (void *pdev, - uint8_t cfgidx); - -static uint8_t usbd_dfu_Setup (void *pdev, - USB_SETUP_REQ *req); - -static uint8_t EP0_TxSent (void *pdev); - -static uint8_t EP0_RxReady (void *pdev); - - -static uint8_t *USBD_DFU_GetCfgDesc (uint8_t speed, - uint16_t *length); - - -#ifdef USB_OTG_HS_CORE -static uint8_t *USBD_DFU_GetOtherCfgDesc (uint8_t speed, - uint16_t *length); -#endif - -static uint8_t* USBD_DFU_GetUsrStringDesc (uint8_t speed, - uint8_t index , - uint16_t *length); - -/********************************************* - DFU Requests management functions - *********************************************/ -static void DFU_Req_DETACH (void *pdev, - USB_SETUP_REQ *req); - -static void DFU_Req_DNLOAD (void *pdev, - USB_SETUP_REQ *req); - -static void DFU_Req_UPLOAD (void *pdev, - USB_SETUP_REQ *req); - -static void DFU_Req_GETSTATUS (void *pdev); - -static void DFU_Req_CLRSTATUS (void *pdev); - -static void DFU_Req_GETSTATE (void *pdev); - -static void DFU_Req_ABORT (void *pdev); - -static void DFU_LeaveDFUMode (void *pdev); - -/** - * @} - */ - -/** @defgroup usbd_dfu_Private_Variables - * @{ - */ -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 - #endif -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ -__ALIGN_BEGIN uint8_t usbd_dfu_CfgDesc[USB_DFU_CONFIG_DESC_SIZ] __ALIGN_END ; - - -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 - #endif -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ -__ALIGN_BEGIN uint8_t usbd_dfu_OtherCfgDesc[USB_DFU_CONFIG_DESC_SIZ] __ALIGN_END ; - -/* The list of Interface String descriptor pointers is defined in usbd_dfu_mal.c - file. This list can be updated whenever a memory has to be added or removed */ -extern const uint8_t* usbd_dfu_StringDesc[]; - -/* State Machine variables */ -uint8_t DeviceState; -uint8_t DeviceStatus[6]; -uint32_t Manifest_State = Manifest_complete; -/* Data Management variables */ -static uint32_t wBlockNum = 0, wlength = 0; -static uint32_t Pointer = APP_DEFAULT_ADD; /* Base Address to Erase, Program or Read */ -static __IO uint32_t usbd_dfu_AltSet = 0; - -extern uint8_t MAL_Buffer[]; - -/* DFU interface class callbacks structure */ -USBD_Class_cb_TypeDef DFU_cb = -{ - usbd_dfu_Init, - usbd_dfu_DeInit, - usbd_dfu_Setup, - EP0_TxSent, - EP0_RxReady, - NULL, /* DataIn, */ - NULL, /* DataOut, */ - NULL, /*SOF */ - NULL, - NULL, - USBD_DFU_GetCfgDesc, -#ifdef USB_OTG_HS_CORE - USBD_DFU_GetOtherCfgDesc, /* use same cobfig as per FS */ -#endif - USBD_DFU_GetUsrStringDesc, -}; - -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 - #endif -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ -/* USB DFU device Configuration Descriptor */ -__ALIGN_BEGIN uint8_t usbd_dfu_CfgDesc[USB_DFU_CONFIG_DESC_SIZ] __ALIGN_END = -{ - 0x09, /* bLength: Configuation Descriptor size */ - USB_CONFIGURATION_DESCRIPTOR_TYPE, /* bDescriptorType: Configuration */ - USB_DFU_CONFIG_DESC_SIZ, - /* wTotalLength: Bytes returned */ - 0x00, - 0x01, /*bNumInterfaces: 1 interface*/ - 0x01, /*bConfigurationValue: Configuration value*/ - 0x02, /*iConfiguration: Index of string descriptor describing the configuration*/ - 0xC0, /*bmAttributes: bus powered and Supprts Remote Wakeup */ - 0x32, /*MaxPower 100 mA: this current is used for detecting Vbus*/ - /* 09 */ - - /********** Descriptor of DFU interface 0 Alternate setting 0 **************/ - USBD_DFU_IF_DESC(0), /* This interface is mandatory for all devices */ - -#if (USBD_ITF_MAX_NUM > 1) - /********** Descriptor of DFU interface 0 Alternate setting 1 **************/ - USBD_DFU_IF_DESC(1), -#endif /* (USBD_ITF_MAX_NUM > 1) */ - -#if (USBD_ITF_MAX_NUM > 2) - /********** Descriptor of DFU interface 0 Alternate setting 2 **************/ - USBD_DFU_IF_DESC(2), -#endif /* (USBD_ITF_MAX_NUM > 2) */ - -#if (USBD_ITF_MAX_NUM > 3) - /********** Descriptor of DFU interface 0 Alternate setting 3 **************/ - USBD_DFU_IF_DESC(3), -#endif /* (USBD_ITF_MAX_NUM > 3) */ - -#if (USBD_ITF_MAX_NUM > 4) - /********** Descriptor of DFU interface 0 Alternate setting 4 **************/ - USBD_DFU_IF_DESC(4), -#endif /* (USBD_ITF_MAX_NUM > 4) */ - -#if (USBD_ITF_MAX_NUM > 5) - /********** Descriptor of DFU interface 0 Alternate setting 5 **************/ - USBD_DFU_IF_DESC(5), -#endif /* (USBD_ITF_MAX_NUM > 5) */ - -#if (USBD_ITF_MAX_NUM > 6) -#error "ERROR: usbd_dfu_core.c: Modify the file to support more descriptors!" -#endif /* (USBD_ITF_MAX_NUM > 6) */ - - /******************** DFU Functional Descriptor********************/ - 0x09, /*blength = 9 Bytes*/ - DFU_DESCRIPTOR_TYPE, /* DFU Functional Descriptor*/ - 0x0B, /*bmAttribute - bitCanDnload = 1 (bit 0) - bitCanUpload = 1 (bit 1) - bitManifestationTolerant = 0 (bit 2) - bitWillDetach = 1 (bit 3) - Reserved (bit4-6) - bitAcceleratedST = 0 (bit 7)*/ - 0xFF, /*DetachTimeOut= 255 ms*/ - 0x00, - /*WARNING: In DMA mode the multiple MPS packets feature is still not supported - ==> In this case, when using DMA XFERSIZE should be set to 64 in usbd_conf.h */ - TRANSFER_SIZE_BYTES(XFERSIZE), /* TransferSize = 1024 Byte*/ - 0x1A, /* bcdDFUVersion*/ - 0x01 - /***********************************************************/ - /* 9*/ -} ; - -#ifdef USE_USB_OTG_HS -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 - #endif -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ - -__ALIGN_BEGIN uint8_t usbd_dfu_OtherCfgDesc[USB_DFU_CONFIG_DESC_SIZ] __ALIGN_END = -{ - 0x09, /* bLength: Configuation Descriptor size */ - USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION, /* bDescriptorType: Configuration */ - USB_DFU_CONFIG_DESC_SIZ, - /* wTotalLength: Bytes returned */ - 0x00, - 0x01, /*bNumInterfaces: 1 interface*/ - 0x01, /*bConfigurationValue: Configuration value*/ - 0x02, /*iConfiguration: Index of string descriptor describing the configuration*/ - 0xC0, /*bmAttributes: bus powered and Supprts Remote Wakeup */ - 0x32, /*MaxPower 100 mA: this current is used for detecting Vbus*/ - /* 09 */ - - /********** Descriptor of DFU interface 0 Alternate setting 0 **************/ - USBD_DFU_IF_DESC(0), /* This interface is mandatory for all devices */ - -#if (USBD_ITF_MAX_NUM > 1) - /********** Descriptor of DFU interface 0 Alternate setting 1 **************/ - USBD_DFU_IF_DESC(1), -#endif /* (USBD_ITF_MAX_NUM > 1) */ - -#if (USBD_ITF_MAX_NUM > 2) - /********** Descriptor of DFU interface 0 Alternate setting 2 **************/ - USBD_DFU_IF_DESC(2), -#endif /* (USBD_ITF_MAX_NUM > 2) */ - -#if (USBD_ITF_MAX_NUM > 3) - /********** Descriptor of DFU interface 0 Alternate setting 3 **************/ - USBD_DFU_IF_DESC(3), -#endif /* (USBD_ITF_MAX_NUM > 3) */ - -#if (USBD_ITF_MAX_NUM > 4) - /********** Descriptor of DFU interface 0 Alternate setting 4 **************/ - USBD_DFU_IF_DESC(4), -#endif /* (USBD_ITF_MAX_NUM > 4) */ - -#if (USBD_ITF_MAX_NUM > 5) - /********** Descriptor of DFU interface 0 Alternate setting 5 **************/ - USBD_DFU_IF_DESC(5), -#endif /* (USBD_ITF_MAX_NUM > 5) */ - -#if (USBD_ITF_MAX_NUM > 6) -#error "ERROR: usbd_dfu_core.c: Modify the file to support more descriptors!" -#endif /* (USBD_ITF_MAX_NUM > 6) */ - - /******************** DFU Functional Descriptor********************/ - 0x09, /*blength = 9 Bytes*/ - DFU_DESCRIPTOR_TYPE, /* DFU Functional Descriptor*/ - 0x0B, /*bmAttribute - bitCanDnload = 1 (bit 0) - bitCanUpload = 1 (bit 1) - bitManifestationTolerant = 0 (bit 2) - bitWillDetach = 1 (bit 3) - Reserved (bit4-6) - bitAcceleratedST = 0 (bit 7)*/ - 0xFF, /*DetachTimeOut= 255 ms*/ - 0x00, - /*WARNING: In DMA mode the multiple MPS packets feature is still not supported - ==> In this case, when using DMA XFERSIZE should be set to 64 in usbd_conf.h */ - TRANSFER_SIZE_BYTES(XFERSIZE), /* TransferSize = 1024 Byte*/ - 0x1A, /* bcdDFUVersion*/ - 0x01 - /***********************************************************/ - /* 9*/ -}; -#endif /* USE_USB_OTG_HS */ - -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 - #endif - -__ALIGN_BEGIN static uint8_t usbd_dfu_Desc[USB_DFU_DESC_SIZ] __ALIGN_END = -{ - 0x09, /*blength = 9 Bytes*/ - DFU_DESCRIPTOR_TYPE, /* DFU Functional Descriptor*/ - 0x0B, /*bmAttribute - bitCanDnload = 1 (bit 0) - bitCanUpload = 1 (bit 1) - bitManifestationTolerant = 0 (bit 2) - bitWillDetach = 1 (bit 3) - Reserved (bit4-6) - bitAcceleratedST = 0 (bit 7)*/ - 0xFF, /*DetachTimeOut= 255 ms*/ - 0x00, - /*WARNING: In DMA mode the multiple MPS packets feature is still not supported - ==> In this case, when using DMA XFERSIZE should be set to 64 in usbd_conf.h */ - TRANSFER_SIZE_BYTES(XFERSIZE), /* TransferSize = 1024 Byte*/ - 0x1A, /* bcdDFUVersion*/ - 0x01 -}; -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ - -/** - * @} - */ - -/** @defgroup usbd_dfu_Private_Functions - * @{ - */ - -/** - * @brief usbd_dfu_Init - * Initializes the DFU interface. - * @param pdev: device instance - * @param cfgidx: Configuration index - * @retval status - */ -static uint8_t usbd_dfu_Init (void *pdev, - uint8_t cfgidx) -{ - /* Initilialize the MAL(Media Access Layer) */ - MAL_Init(); - - /* Initialize the state of the DFU interface */ - DeviceState = STATE_dfuIDLE; - DeviceStatus[0] = STATUS_OK; - DeviceStatus[4] = DeviceState; - - return USBD_OK; -} - -/** - * @brief usbd_dfu_Init - * De-initializes the DFU layer. - * @param pdev: device instance - * @param cfgidx: Configuration index - * @retval status - */ -static uint8_t usbd_dfu_DeInit (void *pdev, - uint8_t cfgidx) -{ - /* Restore default state */ - DeviceState = STATE_dfuIDLE; - DeviceStatus[0] = STATUS_OK; - DeviceStatus[4] = DeviceState; - wBlockNum = 0; - wlength = 0; - - /* DeInitilialize the MAL(Media Access Layer) */ - MAL_DeInit(); - - return USBD_OK; -} - -/** - * @brief usbd_dfu_Setup - * Handles the DFU request parsing. - * @param pdev: instance - * @param req: usb requests - * @retval status - */ -static uint8_t usbd_dfu_Setup (void *pdev, - USB_SETUP_REQ *req) -{ - uint16_t len = 0; - uint8_t *pbuf = NULL; - - switch (req->bmRequest & USB_REQ_TYPE_MASK) - { - /* DFU Class Requests -------------------------------*/ - case USB_REQ_TYPE_CLASS : - switch (req->bRequest) - { - case DFU_DNLOAD: - DFU_Req_DNLOAD(pdev, req); - break; - - case DFU_UPLOAD: - DFU_Req_UPLOAD(pdev, req); - break; - - case DFU_GETSTATUS: - DFU_Req_GETSTATUS(pdev); - break; - - case DFU_CLRSTATUS: - DFU_Req_CLRSTATUS(pdev); - break; - - case DFU_GETSTATE: - DFU_Req_GETSTATE(pdev); - break; - - case DFU_ABORT: - DFU_Req_ABORT(pdev); - break; - - case DFU_DETACH: - DFU_Req_DETACH(pdev, req); - break; - - default: - USBD_CtlError (pdev, req); - return USBD_FAIL; - } - break; - - /* Standard Requests -------------------------------*/ - case USB_REQ_TYPE_STANDARD: - switch (req->bRequest) - { - case USB_REQ_GET_DESCRIPTOR: - if( (req->wValue >> 8) == DFU_DESCRIPTOR_TYPE) - { -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - pbuf = usbd_dfu_Desc; -#else - pbuf = usbd_dfu_CfgDesc + 9 + (9 * USBD_ITF_MAX_NUM); -#endif - len = MIN(USB_DFU_DESC_SIZ , req->wLength); - } - - USBD_CtlSendData (pdev, - pbuf, - len); - break; - - case USB_REQ_GET_INTERFACE : - USBD_CtlSendData (pdev, - (uint8_t *)&usbd_dfu_AltSet, - 1); - break; - - case USB_REQ_SET_INTERFACE : - if ((uint8_t)(req->wValue) < USBD_ITF_MAX_NUM) - { - usbd_dfu_AltSet = (uint8_t)(req->wValue); - } - else - { - /* Call the error management function (command will be nacked */ - USBD_CtlError (pdev, req); - } - break; - } - } - return USBD_OK; -} - -/** - * @brief EP0_TxSent - * Handles the DFU control endpoint data IN stage. - * @param pdev: device instance - * @retval status - */ -static uint8_t EP0_TxSent (void *pdev) -{ - uint32_t Addr; - USB_SETUP_REQ req; - - if (DeviceState == STATE_dfuDNBUSY) - { - /* Decode the Special Command*/ - if (wBlockNum == 0) - { - if ((MAL_Buffer[0] == CMD_GETCOMMANDS) && (wlength == 1)) - {} - else if (( MAL_Buffer[0] == CMD_SETADDRESSPOINTER ) && (wlength == 5)) - { - Pointer = MAL_Buffer[1]; - Pointer += MAL_Buffer[2] << 8; - Pointer += MAL_Buffer[3] << 16; - Pointer += MAL_Buffer[4] << 24; - } - else if (( MAL_Buffer[0] == CMD_ERASE ) && (wlength == 5)) - { - Pointer = MAL_Buffer[1]; - Pointer += MAL_Buffer[2] << 8; - Pointer += MAL_Buffer[3] << 16; - Pointer += MAL_Buffer[4] << 24; - MAL_Erase(Pointer); - } - else - { - /* Reset the global length and block number */ - wlength = 0; - wBlockNum = 0; - /* Call the error management function (command will be nacked) */ - req.bmRequest = 0; - req.wLength = 1; - USBD_CtlError (pdev, &req); - } - } - /* Regular Download Command */ - else if (wBlockNum > 1) - { - /* Decode the required address */ - Addr = ((wBlockNum - 2) * XFERSIZE) + Pointer; - - /* Preform the write operation */ - MAL_Write(Addr, wlength); - } - /* Reset the global lenght and block number */ - wlength = 0; - wBlockNum = 0; - - /* Update the state machine */ - DeviceState = STATE_dfuDNLOAD_SYNC; - DeviceStatus[4] = DeviceState; - DeviceStatus[1] = 0; - DeviceStatus[2] = 0; - DeviceStatus[3] = 0; - return USBD_OK; - } - else if (DeviceState == STATE_dfuMANIFEST)/* Manifestation in progress*/ - { - /* Start leaving DFU mode */ - DFU_LeaveDFUMode(pdev); - } - - return USBD_OK; -} - -/** - * @brief EP0_RxReady - * Handles the DFU control endpoint data OUT stage. - * @param pdev: device instance - * @retval status - */ -static uint8_t EP0_RxReady (void *pdev) -{ - return USBD_OK; -} - - -/****************************************************************************** - DFU Class requests management -******************************************************************************/ -/** - * @brief DFU_Req_DETACH - * Handles the DFU DETACH request. - * @param pdev: device instance - * @param req: pointer to the request structure. - * @retval None. - */ -static void DFU_Req_DETACH(void *pdev, USB_SETUP_REQ *req) -{ - if (DeviceState == STATE_dfuIDLE || DeviceState == STATE_dfuDNLOAD_SYNC - || DeviceState == STATE_dfuDNLOAD_IDLE || DeviceState == STATE_dfuMANIFEST_SYNC - || DeviceState == STATE_dfuUPLOAD_IDLE ) - { - /* Update the state machine */ - DeviceState = STATE_dfuIDLE; - DeviceStatus[0] = STATUS_OK; - DeviceStatus[1] = 0; - DeviceStatus[2] = 0; - DeviceStatus[3] = 0; /*bwPollTimeout=0ms*/ - DeviceStatus[4] = DeviceState; - DeviceStatus[5] = 0; /*iString*/ - wBlockNum = 0; - wlength = 0; - } - - /* Check the detach capability in the DFU functional descriptor */ - if ((usbd_dfu_CfgDesc[12 + (9 * USBD_ITF_MAX_NUM)]) & DFU_DETACH_MASK) - { - /* Perform an Attach-Detach operation on USB bus */ - DCD_DevDisconnect (pdev); - DCD_DevConnect (pdev); - } - else - { - /* Wait for the period of time specified in Detach request */ - USB_OTG_BSP_mDelay (req->wValue); - } -} - -/** - * @brief DFU_Req_DNLOAD - * Handles the DFU DNLOAD request. - * @param pdev: device instance - * @param req: pointer to the request structure - * @retval None - */ -static void DFU_Req_DNLOAD(void *pdev, USB_SETUP_REQ *req) -{ - /* Data setup request */ - if (req->wLength > 0) - { - if ((DeviceState == STATE_dfuIDLE) || (DeviceState == STATE_dfuDNLOAD_IDLE)) - { - /* Update the global length and block number */ - wBlockNum = req->wValue; - wlength = req->wLength; - - /* Update the state machine */ - DeviceState = STATE_dfuDNLOAD_SYNC; - DeviceStatus[4] = DeviceState; - - /* Prepare the reception of the buffer over EP0 */ - USBD_CtlPrepareRx (pdev, - (uint8_t*)MAL_Buffer, - wlength); - } - /* Unsupported state */ - else - { - /* Call the error management function (command will be nacked */ - USBD_CtlError (pdev, req); - } - } - /* 0 Data DNLOAD request */ - else - { - /* End of DNLOAD operation*/ - if (DeviceState == STATE_dfuDNLOAD_IDLE || DeviceState == STATE_dfuIDLE ) - { - Manifest_State = Manifest_In_Progress; - DeviceState = STATE_dfuMANIFEST_SYNC; - DeviceStatus[1] = 0; - DeviceStatus[2] = 0; - DeviceStatus[3] = 0; - DeviceStatus[4] = DeviceState; - } - else - { - /* Call the error management function (command will be nacked */ - USBD_CtlError (pdev, req); - } - } -} - -/** - * @brief DFU_Req_UPLOAD - * Handles the DFU UPLOAD request. - * @param pdev: instance - * @param req: pointer to the request structure - * @retval status - */ -static void DFU_Req_UPLOAD(void *pdev, USB_SETUP_REQ *req) -{ - uint8_t *Phy_Addr = NULL; - uint32_t Addr = 0; - - /* Data setup request */ - if (req->wLength > 0) - { - if ((DeviceState == STATE_dfuIDLE) || (DeviceState == STATE_dfuUPLOAD_IDLE)) - { - /* Update the global langth and block number */ - wBlockNum = req->wValue; - wlength = req->wLength; - - /* DFU Get Command */ - if (wBlockNum == 0) - { - /* Update the state machine */ - DeviceState = (wlength > 3)? STATE_dfuIDLE:STATE_dfuUPLOAD_IDLE; - DeviceStatus[4] = DeviceState; - DeviceStatus[1] = 0; - DeviceStatus[2] = 0; - DeviceStatus[3] = 0; - - /* Store the values of all supported commands */ - MAL_Buffer[0] = CMD_GETCOMMANDS; - MAL_Buffer[1] = CMD_SETADDRESSPOINTER; - MAL_Buffer[2] = CMD_ERASE; - - /* Send the status data over EP0 */ - USBD_CtlSendData (pdev, - (uint8_t *)(&(MAL_Buffer[0])), - 3); - } - else if (wBlockNum > 1) - { - DeviceState = STATE_dfuUPLOAD_IDLE ; - DeviceStatus[4] = DeviceState; - DeviceStatus[1] = 0; - DeviceStatus[2] = 0; - DeviceStatus[3] = 0; - Addr = ((wBlockNum - 2) * XFERSIZE) + Pointer; /* Change is Accelerated*/ - - /* Return the physical address where data are stored */ - Phy_Addr = MAL_Read(Addr, wlength); - - /* Send the status data over EP0 */ - USBD_CtlSendData (pdev, - Phy_Addr, - wlength); - } - else /* unsupported wBlockNum */ - { - DeviceState = STATUS_ERRSTALLEDPKT; - DeviceStatus[4] = DeviceState; - DeviceStatus[1] = 0; - DeviceStatus[2] = 0; - DeviceStatus[3] = 0; - - /* Call the error management function (command will be nacked */ - USBD_CtlError (pdev, req); - } - } - /* Unsupported state */ - else - { - wlength = 0; - wBlockNum = 0; - /* Call the error management function (command will be nacked */ - USBD_CtlError (pdev, req); - } - } - /* No Data setup request */ - else - { - DeviceState = STATE_dfuIDLE; - DeviceStatus[1] = 0; - DeviceStatus[2] = 0; - DeviceStatus[3] = 0; - DeviceStatus[4] = DeviceState; - } -} - -/** - * @brief DFU_Req_GETSTATUS - * Handles the DFU GETSTATUS request. - * @param pdev: instance - * @retval status - */ -static void DFU_Req_GETSTATUS(void *pdev) -{ - switch (DeviceState) - { - case STATE_dfuDNLOAD_SYNC: - if (wlength != 0) - { - DeviceState = STATE_dfuDNBUSY; - DeviceStatus[4] = DeviceState; - if ((wBlockNum == 0) && (MAL_Buffer[0] == CMD_ERASE)) - { - MAL_GetStatus(Pointer, 0, DeviceStatus); - } - else - { - MAL_GetStatus(Pointer, 1, DeviceStatus); - } - } - else /* (wlength==0)*/ - { - DeviceState = STATE_dfuDNLOAD_IDLE; - DeviceStatus[4] = DeviceState; - DeviceStatus[1] = 0; - DeviceStatus[2] = 0; - DeviceStatus[3] = 0; - } - break; - - case STATE_dfuMANIFEST_SYNC : - if (Manifest_State == Manifest_In_Progress) - { - DeviceState = STATE_dfuMANIFEST; - DeviceStatus[4] = DeviceState; - DeviceStatus[1] = 1; /*bwPollTimeout = 1ms*/ - DeviceStatus[2] = 0; - DeviceStatus[3] = 0; - //break; - } - else if ((Manifest_State == Manifest_complete) && \ - ((usbd_dfu_CfgDesc[(11 + (9 * USBD_ITF_MAX_NUM))]) & 0x04)) - { - DeviceState = STATE_dfuIDLE; - DeviceStatus[4] = DeviceState; - DeviceStatus[1] = 0; - DeviceStatus[2] = 0; - DeviceStatus[3] = 0; - //break; - } - break; - - default : - break; - } - - /* Send the status data over EP0 */ - USBD_CtlSendData (pdev, - (uint8_t *)(&(DeviceStatus[0])), - 6); -} - -/** - * @brief DFU_Req_CLRSTATUS - * Handles the DFU CLRSTATUS request. - * @param pdev: device instance - * @retval status - */ -static void DFU_Req_CLRSTATUS(void *pdev) -{ - if (DeviceState == STATE_dfuERROR) - { - DeviceState = STATE_dfuIDLE; - DeviceStatus[0] = STATUS_OK;/*bStatus*/ - DeviceStatus[1] = 0; - DeviceStatus[2] = 0; - DeviceStatus[3] = 0; /*bwPollTimeout=0ms*/ - DeviceStatus[4] = DeviceState;/*bState*/ - DeviceStatus[5] = 0;/*iString*/ - } - else - { /*State Error*/ - DeviceState = STATE_dfuERROR; - DeviceStatus[0] = STATUS_ERRUNKNOWN;/*bStatus*/ - DeviceStatus[1] = 0; - DeviceStatus[2] = 0; - DeviceStatus[3] = 0; /*bwPollTimeout=0ms*/ - DeviceStatus[4] = DeviceState;/*bState*/ - DeviceStatus[5] = 0;/*iString*/ - } -} - -/** - * @brief DFU_Req_GETSTATE - * Handles the DFU GETSTATE request. - * @param pdev: device instance - * @retval None - */ -static void DFU_Req_GETSTATE(void *pdev) -{ - /* Return the current state of the DFU interface */ - USBD_CtlSendData (pdev, - &DeviceState, - 1); -} - -/** - * @brief DFU_Req_ABORT - * Handles the DFU ABORT request. - * @param pdev: device instance - * @retval None - */ -static void DFU_Req_ABORT(void *pdev) -{ - if (DeviceState == STATE_dfuIDLE || DeviceState == STATE_dfuDNLOAD_SYNC - || DeviceState == STATE_dfuDNLOAD_IDLE || DeviceState == STATE_dfuMANIFEST_SYNC - || DeviceState == STATE_dfuUPLOAD_IDLE ) - { - DeviceState = STATE_dfuIDLE; - DeviceStatus[0] = STATUS_OK; - DeviceStatus[1] = 0; - DeviceStatus[2] = 0; - DeviceStatus[3] = 0; /*bwPollTimeout=0ms*/ - DeviceStatus[4] = DeviceState; - DeviceStatus[5] = 0; /*iString*/ - wBlockNum = 0; - wlength = 0; - } -} - -/** - * @brief DFU_LeaveDFUMode - * Handles the sub-protocol DFU leave DFU mode request (leaves DFU mode - * and resets device to jump to user loaded code). - * @param pdev: device instance - * @retval None - */ -void DFU_LeaveDFUMode(void *pdev) -{ - Manifest_State = Manifest_complete; - - if ((usbd_dfu_CfgDesc[(11 + (9 * USBD_ITF_MAX_NUM))]) & 0x04) - { - DeviceState = STATE_dfuMANIFEST_SYNC; - DeviceStatus[4] = DeviceState; - DeviceStatus[1] = 0; - DeviceStatus[2] = 0; - DeviceStatus[3] = 0; - return; - } - else - { - DeviceState = STATE_dfuMANIFEST_WAIT_RESET; - DeviceStatus[4] = DeviceState; - DeviceStatus[1] = 0; - DeviceStatus[2] = 0; - DeviceStatus[3] = 0; - - /* Disconnect the USB device */ - DCD_DevDisconnect (pdev); - - /* DeInitilialize the MAL(Media Access Layer) */ - MAL_DeInit(); - - /* Generate system reset to allow jumping to the user code */ - NVIC_SystemReset(); - - /* This instruction will not be reached (system reset) */ - return; - } -} - -/** - * @brief USBD_DFU_GetCfgDesc - * Returns configuration descriptor - * @param speed : current device speed - * @param length : pointer data length - * @retval pointer to descriptor buffer - */ -static uint8_t *USBD_DFU_GetCfgDesc (uint8_t speed, uint16_t *length) -{ - *length = sizeof (usbd_dfu_CfgDesc); - return usbd_dfu_CfgDesc; -} - -#ifdef USB_OTG_HS_CORE -/** - * @brief USBD_DFU_GetOtherCfgDesc - * Returns other speed configuration descriptor. - * @param speed : current device speed - * @param length : pointer data length - * @retval pointer to descriptor buffer - */ -static uint8_t *USBD_DFU_GetOtherCfgDesc (uint8_t speed, uint16_t *length) -{ - *length = sizeof (usbd_dfu_OtherCfgDesc); - return usbd_dfu_OtherCfgDesc; -} -#endif - -/** - * @brief USBD_DFU_GetUsrStringDesc - * Manages the transfer of memory interfaces string descriptors. - * @param speed : current device speed - * @param index: desciptor index - * @param length : pointer data length - * @retval pointer to the descriptor table or NULL if the descriptor is not supported. - */ -static uint8_t* USBD_DFU_GetUsrStringDesc (uint8_t speed, uint8_t index , uint16_t *length) -{ - /* Check if the requested string interface is supported */ - if (index <= (USBD_IDX_INTERFACE_STR + USBD_ITF_MAX_NUM)) - { - - - USBD_GetString ((uint8_t *)usbd_dfu_StringDesc[index - USBD_IDX_INTERFACE_STR - 1], USBD_StrDesc, length); - return USBD_StrDesc; - } - /* Not supported Interface Descriptor index */ - else - { - return NULL; - } -} -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_dfu_mal.c b/lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_dfu_mal.c deleted file mode 100644 index 3d301e93c1..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_dfu_mal.c +++ /dev/null @@ -1,281 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_dfu_mal.c - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief Generic media access Layer. - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "usbd_dfu_mal.h" - -#include "usbd_flash_if.h" - -#ifdef DFU_MAL_SUPPORT_OTP - #include "usbd_otp_if.h" -#endif - -#ifdef DFU_MAL_SUPPORT_MEM - #include "usbd_mem_if_template.h" -#endif - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Global Memories callback and string descriptors reference tables. - To add a new memory, modify the value of MAX_USED_MEDIA in usbd_dfu_mal.h - and add the pointer to the callback structure in this table. - Then add the pointer to the memory string descriptor in usbd_dfu_StringDesc table. - No other operation is required. */ -DFU_MAL_Prop_TypeDef* tMALTab[MAX_USED_MEDIA] = { - &DFU_Flash_cb -#ifdef DFU_MAL_SUPPORT_OTP - , &DFU_Otp_cb -#endif -#ifdef DFU_MAL_SUPPORT_MEM - , &DFU_Mem_cb -#endif -}; - -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 - #endif -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ - -__ALIGN_BEGIN const uint8_t* usbd_dfu_StringDesc[MAX_USED_MEDIA] __ALIGN_END = { - FLASH_IF_STRING -#ifdef DFU_MAL_SUPPORT_OTP - , OTP_IF_STRING -#endif -#ifdef DFU_MAL_SUPPORT_MEM - , MEM_IF_STRING -#endif -}; - -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 - #endif -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ -/* RAM Buffer for Downloaded Data */ -__ALIGN_BEGIN uint8_t MAL_Buffer[XFERSIZE] __ALIGN_END ; - -/* Private function prototypes -----------------------------------------------*/ -static uint8_t MAL_CheckAdd (uint32_t Add); -/* Private functions ---------------------------------------------------------*/ - -/** - * @brief MAL_Init - * Initializes the Media on the STM32 - * @param None - * @retval Result of the opeartion (MAL_OK in all cases) - */ -uint16_t MAL_Init(void) -{ - uint32_t memIdx = 0; - - /* Init all supported memories */ - for(memIdx = 0; memIdx < MAX_USED_MEDIA; memIdx++) - { - /* If the check addres is positive, exit with the memory index */ - if (tMALTab[memIdx]->pMAL_Init != NULL) - { - tMALTab[memIdx]->pMAL_Init(); - } - } - - return MAL_OK; -} - -/** - * @brief MAL_DeInit - * DeInitializes the Media on the STM32 - * @param None - * @retval Result of the opeartion (MAL_OK in all cases) - */ -uint16_t MAL_DeInit(void) -{ - uint32_t memIdx = 0; - - /* Init all supported memories */ - for(memIdx = 0; memIdx < MAX_USED_MEDIA; memIdx++) - { - /* Check if the command is supported */ - if (tMALTab[memIdx]->pMAL_DeInit != NULL) - { - tMALTab[memIdx]->pMAL_DeInit(); - } - } - - return MAL_OK; -} - -/** - * @brief MAL_Erase - * Erase a sector of memory. - * @param Add: Sector address/code - * @retval Result of the opeartion: MAL_OK if all operations are OK else MAL_FAIL - */ -uint16_t MAL_Erase(uint32_t Add) -{ - uint32_t memIdx = MAL_CheckAdd(Add); - - /* Check if the area is protected */ - if (DFU_MAL_IS_PROTECTED_AREA(Add)) - { - return MAL_FAIL; - } - - if (memIdx < MAX_USED_MEDIA) - { - /* Check if the command is supported */ - if (tMALTab[memIdx]->pMAL_Erase != NULL) - { - return tMALTab[memIdx]->pMAL_Erase(Add); - } - else - { - return MAL_FAIL; - } - } - else - { - return MAL_FAIL; - } -} - -/** - * @brief MAL_Write - * Write sectors of memory. - * @param Add: Sector address/code - * @param Len: Number of data to be written (in bytes) - * @retval Result of the opeartion: MAL_OK if all operations are OK else MAL_FAIL - */ -uint16_t MAL_Write (uint32_t Add, uint32_t Len) -{ - uint32_t memIdx = MAL_CheckAdd(Add); - - /* Check if the area is protected */ - if (DFU_MAL_IS_PROTECTED_AREA(Add)) - { - return MAL_FAIL; - } - - if (memIdx < MAX_USED_MEDIA) - { - /* Check if the command is supported */ - if (tMALTab[memIdx]->pMAL_Write != NULL) - { - return tMALTab[memIdx]->pMAL_Write(Add, Len); - } - else - { - return MAL_FAIL; - } - } - else - { - return MAL_FAIL; - } -} - -/** - * @brief MAL_Read - * Read sectors of memory. - * @param Add: Sector address/code - * @param Len: Number of data to be written (in bytes) - * @retval Buffer pointer - */ -uint8_t *MAL_Read (uint32_t Add, uint32_t Len) -{ - uint32_t memIdx = MAL_CheckAdd(Add); - - if (memIdx < MAX_USED_MEDIA) - { - /* Check if the command is supported */ - if (tMALTab[memIdx]->pMAL_Read != NULL) - { - return tMALTab[memIdx]->pMAL_Read(Add, Len); - } - else - { - return MAL_Buffer; - } - } - else - { - return MAL_Buffer; - } -} - -/** - * @brief MAL_GetStatus - * Get the status of a given memory. - * @param Add: Sector address/code (allow to determine which memory will be addressed) - * @param Cmd: 0 for erase and 1 for write - * @param buffer: pointer to the buffer where the status data will be stored. - * @retval Buffer pointer - */ -uint16_t MAL_GetStatus(uint32_t Add , uint8_t Cmd, uint8_t *buffer) -{ - uint32_t memIdx = MAL_CheckAdd(Add); - - if (memIdx < MAX_USED_MEDIA) - { - if (Cmd & 0x01) - { - SET_POLLING_TIMING(tMALTab[memIdx]->EraseTiming); - } - else - { - SET_POLLING_TIMING(tMALTab[memIdx]->WriteTiming); - } - - return MAL_OK; - } - else - { - return MAL_FAIL; - } -} - -/** - * @brief MAL_CheckAdd - * Determine which memory should be managed. - * @param Add: Sector address/code (allow to determine which memory will be addressed) - * @retval Index of the addressed memory. - */ -static uint8_t MAL_CheckAdd(uint32_t Add) -{ - uint32_t memIdx = 0; - - /* Check with all supported memories */ - for(memIdx = 0; memIdx < MAX_USED_MEDIA; memIdx++) - { - /* If the check addres is positive, exit with the memory index */ - if (tMALTab[memIdx]->pMAL_CheckAdd(Add) == MAL_OK) - { - return memIdx; - } - } - /* If no memory found, return MAX_USED_MEDIA */ - return (MAX_USED_MEDIA); -} - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_flash_if.c b/lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_flash_if.c deleted file mode 100644 index d5604d8377..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_flash_if.c +++ /dev/null @@ -1,221 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_flash_if.c - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief Specific media access Layer for internal flash. - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "usbd_flash_if.h" -#include "usbd_dfu_mal.h" - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ - -/* Private function prototypes -----------------------------------------------*/ -uint16_t FLASH_If_Init(void); -uint16_t FLASH_If_Erase (uint32_t Add); -uint16_t FLASH_If_Write (uint32_t Add, uint32_t Len); -uint8_t *FLASH_If_Read (uint32_t Add, uint32_t Len); -uint16_t FLASH_If_DeInit(void); -uint16_t FLASH_If_CheckAdd(uint32_t Add); - - -/* Private variables ---------------------------------------------------------*/ -DFU_MAL_Prop_TypeDef DFU_Flash_cb = - { - FLASH_IF_STRING, - FLASH_If_Init, - FLASH_If_DeInit, - FLASH_If_Erase, - FLASH_If_Write, - FLASH_If_Read, - FLASH_If_CheckAdd, - 50, /* Erase Time in ms */ - 50 /* Programming Time in ms */ - }; - -/* Private functions ---------------------------------------------------------*/ - -/** - * @brief FLASH_If_Init - * Memory initialization routine. - * @param None - * @retval MAL_OK if operation is successeful, MAL_FAIL else. - */ -uint16_t FLASH_If_Init(void) -{ - /* Unlock the internal flash */ - FLASH_Unlock(); - - return MAL_OK; -} - -/** - * @brief FLASH_If_DeInit - * Memory deinitialization routine. - * @param None - * @retval MAL_OK if operation is successeful, MAL_FAIL else. - */ -uint16_t FLASH_If_DeInit(void) -{ - /* Lock the internal flash */ - FLASH_Lock(); - - return MAL_OK; -} - -/******************************************************************************* -* Function Name : FLASH_If_Erase -* Description : Erase sector -* Input : None -* Output : None -* Return : None -*******************************************************************************/ -uint16_t FLASH_If_Erase(uint32_t Add) -{ -#ifdef STM32F2XX - /* Check which sector has to be erased */ - if (Add < 0x08004000) - { - FLASH_EraseSector(FLASH_Sector_0, VoltageRange_3); - } - else if (Add < 0x08008000) - { - FLASH_EraseSector(FLASH_Sector_1, VoltageRange_3); - } - else if (Add < 0x0800C000) - { - FLASH_EraseSector(FLASH_Sector_2, VoltageRange_3); - } - else if (Add < 0x08010000) - { - FLASH_EraseSector(FLASH_Sector_3, VoltageRange_3); - } - else if (Add < 0x08020000) - { - FLASH_EraseSector(FLASH_Sector_4, VoltageRange_3); - } - else if (Add < 0x08040000) - { - FLASH_EraseSector(FLASH_Sector_5, VoltageRange_3); - } - else if (Add < 0x08060000) - { - FLASH_EraseSector(FLASH_Sector_6, VoltageRange_3); - } - else if (Add < 0x08080000) - { - FLASH_EraseSector(FLASH_Sector_7, VoltageRange_3); - } - else if (Add < 0x080A0000) - { - FLASH_EraseSector(FLASH_Sector_8, VoltageRange_3); - } - else if (Add < 0x080C0000) - { - FLASH_EraseSector(FLASH_Sector_9, VoltageRange_3); - } - else if (Add < 0x080E0000) - { - FLASH_EraseSector(FLASH_Sector_10, VoltageRange_3); - } - else if (Add < 0x08100000) - { - FLASH_EraseSector(FLASH_Sector_11, VoltageRange_3); - } - else - { - return MAL_FAIL; - } -#elif defined(STM32F10X_CL) - /* Call the standard Flash erase function */ - FLASH_ErasePage(Add); -#endif /* STM32F2XX */ - - return MAL_OK; -} - -/** - * @brief FLASH_If_Write - * Memory write routine. - * @param Add: Address to be written to. - * @param Len: Number of data to be written (in bytes). - * @retval MAL_OK if operation is successeful, MAL_FAIL else. - */ -uint16_t FLASH_If_Write(uint32_t Add, uint32_t Len) -{ - uint32_t idx = 0; - - if (Len & 0x3) /* Not an aligned data */ - { - for (idx = Len; idx < ((Len & 0xFFFC) + 4); idx++) - { - MAL_Buffer[idx] = 0xFF; - } - } - - /* Data received are Word multiple */ - for (idx = 0; idx < Len; idx = idx + 4) - { - FLASH_ProgramWord(Add, *(uint32_t *)(MAL_Buffer + idx)); - Add += 4; - } - return MAL_OK; -} - -/** - * @brief FLASH_If_Read - * Memory read routine. - * @param Add: Address to be read from. - * @param Len: Number of data to be read (in bytes). - * @retval Pointer to the phyisical address where data should be read. - */ -uint8_t *FLASH_If_Read (uint32_t Add, uint32_t Len) -{ -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - uint32_t idx = 0; - for (idx = 0; idx < Len; idx += 4) - { - *(uint32_t*)(MAL_Buffer + idx) = *(uint32_t *)(Add + idx); - } - return (uint8_t*)(MAL_Buffer); -#else - return (uint8_t *)(Add); -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ -} - -/** - * @brief FLASH_If_CheckAdd - * Check if the address is an allowed address for this memory. - * @param Add: Address to be checked. - * @param Len: Number of data to be read (in bytes). - * @retval MAL_OK if the address is allowed, MAL_FAIL else. - */ -uint16_t FLASH_If_CheckAdd(uint32_t Add) -{ - if ((Add >= FLASH_START_ADD) && (Add < FLASH_END_ADD)) - { - return MAL_OK; - } - else - { - return MAL_FAIL; - } -} -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_mem_if_template.c b/lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_mem_if_template.c deleted file mode 100644 index 4295e40ff4..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_mem_if_template.c +++ /dev/null @@ -1,133 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_mem_if_template.c - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief Specific media access Layer for a template memory. This file is - provided as template example showing how to implement a new memory - interface based on pre-defined API. - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "usbd_mem_if_template.h" -#include "usbd_dfu_mal.h" - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ - -/* Private function prototypes -----------------------------------------------*/ -uint16_t MEM_If_Init(void); -uint16_t MEM_If_Erase (uint32_t Add); -uint16_t MEM_If_Write (uint32_t Add, uint32_t Len); -uint8_t *MEM_If_Read (uint32_t Add, uint32_t Len); -uint16_t MEM_If_DeInit(void); -uint16_t MEM_If_CheckAdd(uint32_t Add); - - -/* Private variables ---------------------------------------------------------*/ -DFU_MAL_Prop_TypeDef DFU_Mem_cb = - { - MEM_IF_STRING, - MEM_If_Init, - MEM_If_DeInit, - MEM_If_Erase, - MEM_If_Write, - MEM_If_Read, - MEM_If_CheckAdd, - 10, /* Erase Time in ms */ - 10 /* Programming Time in ms */ - }; - -/* Private functions ---------------------------------------------------------*/ - -/** - * @brief MEM_If_Init - * Memory initialization routine. - * @param None - * @retval MAL_OK if operation is successeful, MAL_FAIL else. - */ -uint16_t MEM_If_Init(void) -{ - return MAL_OK; -} - -/** - * @brief MEM_If_DeInit - * Memory deinitialization routine. - * @param None - * @retval MAL_OK if operation is successeful, MAL_FAIL else. - */ -uint16_t MEM_If_DeInit(void) -{ - return MAL_OK; -} - -/** - * @brief MEM_If_Erase - * Erase sector. - * @param Add: Address of sector to be erased. - * @retval MAL_OK if operation is successeful, MAL_FAIL else. - */ -uint16_t MEM_If_Erase(uint32_t Add) -{ - return MAL_OK; -} - -/** - * @brief MEM_If_Write - * Memory write routine. - * @param Add: Address to be written to. - * @param Len: Number of data to be written (in bytes). - * @retval MAL_OK if operation is successeful, MAL_FAIL else. - */ -uint16_t MEM_If_Write(uint32_t Add, uint32_t Len) -{ - return MAL_OK; -} - -/** - * @brief MEM_If_Read - * Memory read routine. - * @param Add: Address to be read from. - * @param Len: Number of data to be read (in bytes). - * @retval Pointer to the phyisical address where data should be read. - */ -uint8_t *MEM_If_Read (uint32_t Add, uint32_t Len) -{ - /* Return a valid address to avoid HardFault */ - return (uint8_t*)(MAL_Buffer); -} - -/** - * @brief MEM_If_CheckAdd - * Check if the address is an allowed address for this memory. - * @param Add: Address to be checked. - * @param Len: Number of data to be read (in bytes). - * @retval MAL_OK if the address is allowed, MAL_FAIL else. - */ -uint16_t MEM_If_CheckAdd(uint32_t Add) -{ - if ((Add >= MEM_START_ADD) && (Add < MEM_END_ADD)) - { - return MAL_OK; - } - else - { - return MAL_FAIL; - } -} -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_otp_if.c b/lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_otp_if.c deleted file mode 100644 index 5970c0ea33..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_otp_if.c +++ /dev/null @@ -1,120 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_otp_if.c - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief Specific media access Layer for OTP (One Time Programming) memory. - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "usbd_otp_if.h" -#include "usbd_dfu_mal.h" - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ - -/* Private function prototypes -----------------------------------------------*/ -uint16_t OTP_If_Write (uint32_t Add, uint32_t Len); -uint8_t *OTP_If_Read (uint32_t Add, uint32_t Len); -uint16_t OTP_If_DeInit(void); -uint16_t OTP_If_CheckAdd(uint32_t Add); - - -/* Private variables ---------------------------------------------------------*/ -DFU_MAL_Prop_TypeDef DFU_Otp_cb = - { - OTP_IF_STRING, - NULL, /* Init not supported*/ - NULL, /* DeInit not supported */ - NULL, /* Erase not supported */ - OTP_If_Write, - OTP_If_Read, - OTP_If_CheckAdd, - 1, /* Erase Time in ms */ - 10 /* Programming Time in ms */ - }; - -/* Private functions ---------------------------------------------------------*/ - -/** - * @brief OTP_If_Write - * Memory write routine. - * @param Add: Address to be written to. - * @param Len: Number of data to be written (in bytes). - * @retval MAL_OK if operation is successeful, MAL_FAIL else. - */ -uint16_t OTP_If_Write(uint32_t Add, uint32_t Len) -{ - uint32_t idx = 0; - - if (Len & 0x3) /* Not an aligned data */ - { - for (idx = Len; idx < ((Len & 0xFFFC) + 4); idx++) - { - MAL_Buffer[idx] = 0xFF; - } - } - - /* Data received are Word multiple */ - for (idx = 0; idx < Len; idx = idx + 4) - { - FLASH_ProgramWord(Add, *(uint32_t *)(MAL_Buffer + idx)); - Add += 4; - } - return MAL_OK; -} - -/** - * @brief OTP_If_Read - * Memory read routine. - * @param Add: Address to be read from. - * @param Len: Number of data to be read (in bytes). - * @retval Pointer to the phyisical address where data should be read. - */ -uint8_t *OTP_If_Read (uint32_t Add, uint32_t Len) -{ -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - uint32_t idx = 0; - for (idx = 0; idx < Len; idx += 4) - { - *(uint32_t*)(MAL_Buffer + idx) = *(uint32_t *)(Add + idx); - } - return (uint8_t*)(MAL_Buffer); -#else - return (uint8_t*)(Add); -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ -} - -/** - * @brief OTP_If_CheckAdd - * Check if the address is an allowed address for this memory. - * @param Add: Address to be checked. - * @param Len: Number of data to be read (in bytes). - * @retval MAL_OK if the address is allowed, MAL_FAIL else. - */ -uint16_t OTP_If_CheckAdd(uint32_t Add) -{ - if ((Add >= OTP_START_ADD) && (Add < OTP_END_ADD)) - { - return MAL_OK; - } - else - { - return MAL_FAIL; - } -} -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/hid/inc/usbd_hid_core.h b/lib/main/STM32_USB_Device_Library/Class/hid/inc/usbd_hid_core.h deleted file mode 100644 index d93fc77d68..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/hid/inc/usbd_hid_core.h +++ /dev/null @@ -1,110 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_hid_core.h - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief header file for the usbd_hid_core.c file. - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ - -#ifndef __USB_HID_CORE_H_ -#define __USB_HID_CORE_H_ - -#include "usbd_ioreq.h" - -/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY - * @{ - */ - -/** @defgroup USBD_HID - * @brief This file is the Header file for USBD_msc.c - * @{ - */ - - -/** @defgroup USBD_HID_Exported_Defines - * @{ - */ -#define USB_HID_CONFIG_DESC_SIZ 34 -#define USB_HID_DESC_SIZ 9 -#define HID_MOUSE_REPORT_DESC_SIZE 74 - -#define HID_DESCRIPTOR_TYPE 0x21 -#define HID_REPORT_DESC 0x22 - - -#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 -/** - * @} - */ - - -/** @defgroup USBD_CORE_Exported_TypesDefinitions - * @{ - */ - - -/** - * @} - */ - - - -/** @defgroup USBD_CORE_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup USBD_CORE_Exported_Variables - * @{ - */ - -extern USBD_Class_cb_TypeDef USBD_HID_cb; -/** - * @} - */ - -/** @defgroup USB_CORE_Exported_Functions - * @{ - */ -uint8_t USBD_HID_SendReport (USB_OTG_CORE_HANDLE *pdev, - uint8_t *report, - uint16_t len); -/** - * @} - */ - -#endif // __USB_HID_CORE_H_ -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/hid/src/usbd_hid_core.c b/lib/main/STM32_USB_Device_Library/Class/hid/src/usbd_hid_core.c deleted file mode 100644 index a56c5ed498..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/hid/src/usbd_hid_core.c +++ /dev/null @@ -1,460 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_hid_core.c - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief This file provides the HID core functions. - * - * @verbatim - * - * =================================================================== - * HID Class Description - * =================================================================== - * This module manages the HID class V1.11 following the "Device Class Definition - * for Human Interface Devices (HID) Version 1.11 Jun 27, 2001". - * This driver implements the following aspects of the specification: - * - The Boot Interface Subclass - * - The Mouse protocol - * - Usage Page : Generic Desktop - * - Usage : Joystick) - * - Collection : Application - * - * @note In HS mode and when the DMA is used, all variables and data structures - * dealing with the DMA during the transaction process should be 32-bit aligned. - * - * - * @endverbatim - * - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "usbd_hid_core.h" -#include "usbd_desc.h" -#include "usbd_req.h" - - -/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY - * @{ - */ - - -/** @defgroup USBD_HID - * @brief usbd core module - * @{ - */ - -/** @defgroup USBD_HID_Private_TypesDefinitions - * @{ - */ -/** - * @} - */ - - -/** @defgroup USBD_HID_Private_Defines - * @{ - */ - -/** - * @} - */ - - -/** @defgroup USBD_HID_Private_Macros - * @{ - */ -/** - * @} - */ - - - - -/** @defgroup USBD_HID_Private_FunctionPrototypes - * @{ - */ - - -static uint8_t USBD_HID_Init (void *pdev, - uint8_t cfgidx); - -static uint8_t USBD_HID_DeInit (void *pdev, - uint8_t cfgidx); - -static uint8_t USBD_HID_Setup (void *pdev, - USB_SETUP_REQ *req); - -static uint8_t *USBD_HID_GetCfgDesc (uint8_t speed, uint16_t *length); - -static uint8_t USBD_HID_DataIn (void *pdev, uint8_t epnum); -/** - * @} - */ - -/** @defgroup USBD_HID_Private_Variables - * @{ - */ - -USBD_Class_cb_TypeDef USBD_HID_cb = -{ - USBD_HID_Init, - USBD_HID_DeInit, - USBD_HID_Setup, - NULL, /*EP0_TxSent*/ - NULL, /*EP0_RxReady*/ - USBD_HID_DataIn, /*DataIn*/ - NULL, /*DataOut*/ - NULL, /*SOF */ - NULL, - NULL, - USBD_HID_GetCfgDesc, -#ifdef USB_OTG_HS_CORE - USBD_HID_GetCfgDesc, /* use same config as per FS */ -#endif -}; - -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 - #endif -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ -__ALIGN_BEGIN static uint32_t USBD_HID_AltSet __ALIGN_END = 0; - -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 - #endif -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ -__ALIGN_BEGIN static uint32_t USBD_HID_Protocol __ALIGN_END = 0; - -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 - #endif -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ -__ALIGN_BEGIN static uint32_t USBD_HID_IdleState __ALIGN_END = 0; - -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 - #endif -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ -/* USB HID device Configuration Descriptor */ -__ALIGN_BEGIN static uint8_t USBD_HID_CfgDesc[USB_HID_CONFIG_DESC_SIZ] __ALIGN_END = -{ - 0x09, /* bLength: Configuration Descriptor size */ - USB_CONFIGURATION_DESCRIPTOR_TYPE, /* bDescriptorType: Configuration */ - USB_HID_CONFIG_DESC_SIZ, - /* wTotalLength: Bytes returned */ - 0x00, - 0x01, /*bNumInterfaces: 1 interface*/ - 0x01, /*bConfigurationValue: Configuration value*/ - 0x00, /*iConfiguration: Index of string descriptor describing - the configuration*/ - 0xE0, /*bmAttributes: bus powered and Support Remote Wake-up */ - 0x32, /*MaxPower 100 mA: this current is used for detecting Vbus*/ - - /************** Descriptor of Joystick Mouse interface ****************/ - /* 09 */ - 0x09, /*bLength: Interface Descriptor size*/ - USB_INTERFACE_DESCRIPTOR_TYPE,/*bDescriptorType: Interface descriptor type*/ - 0x00, /*bInterfaceNumber: Number of Interface*/ - 0x00, /*bAlternateSetting: Alternate setting*/ - 0x01, /*bNumEndpoints*/ - 0x03, /*bInterfaceClass: HID*/ - 0x01, /*bInterfaceSubClass : 1=BOOT, 0=no boot*/ - 0x02, /*nInterfaceProtocol : 0=none, 1=keyboard, 2=mouse*/ - 0, /*iInterface: Index of string descriptor*/ - /******************** Descriptor of Joystick Mouse HID ********************/ - /* 18 */ - 0x09, /*bLength: HID Descriptor size*/ - HID_DESCRIPTOR_TYPE, /*bDescriptorType: HID*/ - 0x11, /*bcdHID: HID Class Spec release number*/ - 0x01, - 0x00, /*bCountryCode: Hardware target country*/ - 0x01, /*bNumDescriptors: Number of HID class descriptors to follow*/ - 0x22, /*bDescriptorType*/ - HID_MOUSE_REPORT_DESC_SIZE,/*wItemLength: Total length of Report descriptor*/ - 0x00, - /******************** Descriptor of Mouse endpoint ********************/ - /* 27 */ - 0x07, /*bLength: Endpoint Descriptor size*/ - USB_ENDPOINT_DESCRIPTOR_TYPE, /*bDescriptorType:*/ - - HID_IN_EP, /*bEndpointAddress: Endpoint Address (IN)*/ - 0x03, /*bmAttributes: Interrupt endpoint*/ - HID_IN_PACKET, /*wMaxPacketSize: 4 Byte max */ - 0x00, - 0x0A, /*bInterval: Polling Interval (10 ms)*/ - /* 34 */ -} ; - -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 - #endif -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ -__ALIGN_BEGIN static uint8_t HID_MOUSE_ReportDesc[HID_MOUSE_REPORT_DESC_SIZE] __ALIGN_END = -{ - 0x05, 0x01, - 0x09, 0x02, - 0xA1, 0x01, - 0x09, 0x01, - - 0xA1, 0x00, - 0x05, 0x09, - 0x19, 0x01, - 0x29, 0x03, - - 0x15, 0x00, - 0x25, 0x01, - 0x95, 0x03, - 0x75, 0x01, - - 0x81, 0x02, - 0x95, 0x01, - 0x75, 0x05, - 0x81, 0x01, - - 0x05, 0x01, - 0x09, 0x30, - 0x09, 0x31, - 0x09, 0x38, - - 0x15, 0x81, - 0x25, 0x7F, - 0x75, 0x08, - 0x95, 0x03, - - 0x81, 0x06, - 0xC0, 0x09, - 0x3c, 0x05, - 0xff, 0x09, - - 0x01, 0x15, - 0x00, 0x25, - 0x01, 0x75, - 0x01, 0x95, - - 0x02, 0xb1, - 0x22, 0x75, - 0x06, 0x95, - 0x01, 0xb1, - - 0x01, 0xc0 -}; - -/** - * @} - */ - -/** @defgroup USBD_HID_Private_Functions - * @{ - */ - -/** - * @brief USBD_HID_Init - * Initialize the HID interface - * @param pdev: device instance - * @param cfgidx: Configuration index - * @retval status - */ -static uint8_t USBD_HID_Init (void *pdev, - uint8_t cfgidx) -{ - - /* Open EP IN */ - DCD_EP_Open(pdev, - HID_IN_EP, - HID_IN_PACKET, - USB_OTG_EP_INT); - - /* Open EP OUT */ - DCD_EP_Open(pdev, - HID_OUT_EP, - HID_OUT_PACKET, - USB_OTG_EP_INT); - - return USBD_OK; -} - -/** - * @brief USBD_HID_Init - * DeInitialize the HID layer - * @param pdev: device instance - * @param cfgidx: Configuration index - * @retval status - */ -static uint8_t USBD_HID_DeInit (void *pdev, - uint8_t cfgidx) -{ - /* Close HID EPs */ - DCD_EP_Close (pdev , HID_IN_EP); - DCD_EP_Close (pdev , HID_OUT_EP); - - - return USBD_OK; -} - -/** - * @brief USBD_HID_Setup - * Handle the HID specific requests - * @param pdev: instance - * @param req: usb requests - * @retval status - */ -static uint8_t USBD_HID_Setup (void *pdev, - USB_SETUP_REQ *req) -{ - uint16_t len = 0; - uint8_t *pbuf = NULL; - - switch (req->bmRequest & USB_REQ_TYPE_MASK) - { - case USB_REQ_TYPE_CLASS : - switch (req->bRequest) - { - - - case HID_REQ_SET_PROTOCOL: - USBD_HID_Protocol = (uint8_t)(req->wValue); - break; - - case HID_REQ_GET_PROTOCOL: - USBD_CtlSendData (pdev, - (uint8_t *)&USBD_HID_Protocol, - 1); - break; - - case HID_REQ_SET_IDLE: - USBD_HID_IdleState = (uint8_t)(req->wValue >> 8); - break; - - case HID_REQ_GET_IDLE: - USBD_CtlSendData (pdev, - (uint8_t *)&USBD_HID_IdleState, - 1); - break; - - default: - USBD_CtlError (pdev, req); - return USBD_FAIL; - } - break; - - case USB_REQ_TYPE_STANDARD: - switch (req->bRequest) - { - case USB_REQ_GET_DESCRIPTOR: - if( req->wValue >> 8 == HID_REPORT_DESC) - { - len = MIN(HID_MOUSE_REPORT_DESC_SIZE , req->wLength); - pbuf = HID_MOUSE_ReportDesc; - } - else if( req->wValue >> 8 == HID_DESCRIPTOR_TYPE) - { - -//#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED -// pbuf = USBD_HID_Desc; -//#else - pbuf = USBD_HID_CfgDesc + 0x12; -//#endif - len = MIN(USB_HID_DESC_SIZ , req->wLength); - } - - USBD_CtlSendData (pdev, - pbuf, - len); - - break; - - case USB_REQ_GET_INTERFACE : - USBD_CtlSendData (pdev, - (uint8_t *)&USBD_HID_AltSet, - 1); - break; - - case USB_REQ_SET_INTERFACE : - USBD_HID_AltSet = (uint8_t)(req->wValue); - break; - } - } - return USBD_OK; -} - -/** - * @brief USBD_HID_SendReport - * Send HID Report - * @param pdev: device instance - * @param buff: pointer to report - * @retval status - */ -uint8_t USBD_HID_SendReport (USB_OTG_CORE_HANDLE *pdev, - uint8_t *report, - uint16_t len) -{ - if (pdev->dev.device_status == USB_OTG_CONFIGURED ) - { - DCD_EP_Tx (pdev, HID_IN_EP, report, len); - } - return USBD_OK; -} - -/** - * @brief USBD_HID_GetCfgDesc - * return configuration descriptor - * @param speed : current device speed - * @param length : pointer data length - * @retval pointer to descriptor buffer - */ -static uint8_t *USBD_HID_GetCfgDesc (uint8_t speed, uint16_t *length) -{ - *length = sizeof (USBD_HID_CfgDesc); - return USBD_HID_CfgDesc; -} - -/** - * @brief USBD_HID_DataIn - * handle data IN Stage - * @param pdev: device instance - * @param epnum: endpoint index - * @retval status - */ -static uint8_t USBD_HID_DataIn (void *pdev, - uint8_t epnum) -{ - - /* Ensure that the FIFO is empty before a new transfer, this condition could - be caused by a new transfer before the end of the previous transfer */ - DCD_EP_Flush(pdev, HID_IN_EP); - return USBD_OK; -} - -/** - * @} - */ - - -/** - * @} - */ - - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/msc/inc/usbd_msc_bot.h b/lib/main/STM32_USB_Device_Library/Class/msc/inc/usbd_msc_bot.h deleted file mode 100644 index 64b6d262c2..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/msc/inc/usbd_msc_bot.h +++ /dev/null @@ -1,147 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_msc_bot.h - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief header for the usbd_msc_bot.c file - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ - -#include "usbd_core.h" - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USBD_MSC_BOT_H -#define __USBD_MSC_BOT_H - -/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY - * @{ - */ - -/** @defgroup MSC_BOT - * @brief This file is the Header file for usbd_bot.c - * @{ - */ - - -/** @defgroup USBD_CORE_Exported_Defines - * @{ - */ -#define BOT_IDLE 0 /* Idle state */ -#define BOT_DATA_OUT 1 /* Data Out state */ -#define BOT_DATA_IN 2 /* Data In state */ -#define BOT_LAST_DATA_IN 3 /* Last Data In Last */ -#define BOT_SEND_DATA 4 /* Send Immediate data */ - -#define BOT_CBW_SIGNATURE 0x43425355 -#define BOT_CSW_SIGNATURE 0x53425355 -#define BOT_CBW_LENGTH 31 -#define BOT_CSW_LENGTH 13 - -/* CSW Status Definitions */ -#define CSW_CMD_PASSED 0x00 -#define CSW_CMD_FAILED 0x01 -#define CSW_PHASE_ERROR 0x02 - -/* BOT Status */ -#define BOT_STATE_NORMAL 0 -#define BOT_STATE_RECOVERY 1 -#define BOT_STATE_ERROR 2 - - -#define DIR_IN 0 -#define DIR_OUT 1 -#define BOTH_DIR 2 - -/** - * @} - */ - -/** @defgroup MSC_CORE_Private_TypesDefinitions - * @{ - */ - -typedef struct _MSC_BOT_CBW -{ - uint32_t dSignature; - uint32_t dTag; - uint32_t dDataLength; - uint8_t bmFlags; - uint8_t bLUN; - uint8_t bCBLength; - uint8_t CB[16]; -} -MSC_BOT_CBW_TypeDef; - - -typedef struct _MSC_BOT_CSW -{ - uint32_t dSignature; - uint32_t dTag; - uint32_t dDataResidue; - uint8_t bStatus; -} -MSC_BOT_CSW_TypeDef; - -/** - * @} - */ - - -/** @defgroup USBD_CORE_Exported_Types - * @{ - */ - -extern uint8_t MSC_BOT_Data[]; -extern uint16_t MSC_BOT_DataLen; -extern uint8_t MSC_BOT_State; -extern uint8_t MSC_BOT_BurstMode; -extern MSC_BOT_CBW_TypeDef MSC_BOT_cbw; -extern MSC_BOT_CSW_TypeDef MSC_BOT_csw; -/** - * @} - */ -/** @defgroup USBD_CORE_Exported_FunctionsPrototypes - * @{ - */ -void MSC_BOT_Init (USB_OTG_CORE_HANDLE *pdev); -void MSC_BOT_Reset (USB_OTG_CORE_HANDLE *pdev); -void MSC_BOT_DeInit (USB_OTG_CORE_HANDLE *pdev); -void MSC_BOT_DataIn (USB_OTG_CORE_HANDLE *pdev, - uint8_t epnum); - -void MSC_BOT_DataOut (USB_OTG_CORE_HANDLE *pdev, - uint8_t epnum); - -void MSC_BOT_SendCSW (USB_OTG_CORE_HANDLE *pdev, - uint8_t CSW_Status); - -void MSC_BOT_CplClrFeature (USB_OTG_CORE_HANDLE *pdev, - uint8_t epnum); -/** - * @} - */ - -#endif /* __USBD_MSC_BOT_H */ -/** - * @} - */ - -/** -* @} -*/ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ - diff --git a/lib/main/STM32_USB_Device_Library/Class/msc/inc/usbd_msc_core.h b/lib/main/STM32_USB_Device_Library/Class/msc/inc/usbd_msc_core.h deleted file mode 100644 index be1d401e27..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/msc/inc/usbd_msc_core.h +++ /dev/null @@ -1,72 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_msc_core.h - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief header for the usbd_msc_core.c file - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef _USB_MSC_CORE_H_ -#define _USB_MSC_CORE_H_ - -#include "usbd_ioreq.h" - -/** @addtogroup USBD_MSC_BOT - * @{ - */ - -/** @defgroup USBD_MSC - * @brief This file is the Header file for USBD_msc.c - * @{ - */ - - -/** @defgroup USBD_BOT_Exported_Defines - * @{ - */ - - -#define BOT_GET_MAX_LUN 0xFE -#define BOT_RESET 0xFF -#define USB_MSC_CONFIG_DESC_SIZ 32 - -#define MSC_EPIN_SIZE *(uint16_t *)(((USB_OTG_CORE_HANDLE *)pdev)->dev.pConfig_descriptor + 22) - -#define MSC_EPOUT_SIZE *(uint16_t *)(((USB_OTG_CORE_HANDLE *)pdev)->dev.pConfig_descriptor + 29) - -/** - * @} - */ - -/** @defgroup USB_CORE_Exported_Types - * @{ - */ - -extern USBD_Class_cb_TypeDef USBD_MSC_cb; -/** - * @} - */ - -/** - * @} - */ -#endif // _USB_MSC_CORE_H_ -/** - * @} - */ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/msc/inc/usbd_msc_data.h b/lib/main/STM32_USB_Device_Library/Class/msc/inc/usbd_msc_data.h deleted file mode 100644 index e0a677f887..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/msc/inc/usbd_msc_data.h +++ /dev/null @@ -1,98 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_msc_data.h - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief header for the usbd_msc_data.c file - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ - -#ifndef _USBD_MSC_DATA_H_ -#define _USBD_MSC_DATA_H_ - -/* Includes ------------------------------------------------------------------*/ -#include "usbd_conf.h" - -/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY - * @{ - */ - -/** @defgroup USB_INFO - * @brief general defines for the usb device library file - * @{ - */ - -/** @defgroup USB_INFO_Exported_Defines - * @{ - */ -#define MODE_SENSE6_LEN 8 -#define MODE_SENSE10_LEN 8 -#define LENGTH_INQUIRY_PAGE00 7 -#define LENGTH_FORMAT_CAPACITIES 20 - -/** - * @} - */ - - -/** @defgroup USBD_INFO_Exported_TypesDefinitions - * @{ - */ -/** - * @} - */ - - - -/** @defgroup USBD_INFO_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup USBD_INFO_Exported_Variables - * @{ - */ -extern const uint8_t MSC_Page00_Inquiry_Data[]; -extern const uint8_t MSC_Mode_Sense6_data[]; -extern const uint8_t MSC_Mode_Sense10_data[] ; - -/** - * @} - */ - -/** @defgroup USBD_INFO_Exported_FunctionsPrototype - * @{ - */ - -/** - * @} - */ - -#endif /* _USBD_MSC_DATA_H_ */ - -/** - * @} - */ - -/** -* @} -*/ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/msc/inc/usbd_msc_mem.h b/lib/main/STM32_USB_Device_Library/Class/msc/inc/usbd_msc_mem.h deleted file mode 100644 index 811e9ee8b0..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/msc/inc/usbd_msc_mem.h +++ /dev/null @@ -1,106 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_msc_mem.h - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief header for the STORAGE DISK file file - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ - -#ifndef __USBD_MEM_H -#define __USBD_MEM_H -/* Includes ------------------------------------------------------------------*/ -#include "usbd_def.h" - - -/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY - * @{ - */ - -/** @defgroup USBD_MEM - * @brief header file for the storage disk file - * @{ - */ - -/** @defgroup USBD_MEM_Exported_Defines - * @{ - */ -#define USBD_STD_INQUIRY_LENGTH 36 -/** - * @} - */ - - -/** @defgroup USBD_MEM_Exported_TypesDefinitions - * @{ - */ - -typedef struct _USBD_STORAGE -{ - int8_t (* Init) (uint8_t lun); - int8_t (* GetCapacity) (uint8_t lun, uint32_t *block_num, uint32_t *block_size); - int8_t (* IsReady) (uint8_t lun); - int8_t (* IsWriteProtected) (uint8_t lun); - int8_t (* Read) (uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len); - int8_t (* Write)(uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len); - int8_t (* GetMaxLun)(void); - int8_t *pInquiry; - -}USBD_STORAGE_cb_TypeDef; -/** - * @} - */ - - - -/** @defgroup USBD_MEM_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup USBD_MEM_Exported_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup USBD_MEM_Exported_FunctionsPrototype - * @{ - */ -extern USBD_STORAGE_cb_TypeDef *USBD_STORAGE_fops; -/** - * @} - */ - -#endif /* __USBD_MEM_H */ -/** - * @} - */ - -/** - * @} - */ - -/** -* @} -*/ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/msc/inc/usbd_msc_scsi.h b/lib/main/STM32_USB_Device_Library/Class/msc/inc/usbd_msc_scsi.h deleted file mode 100644 index 5ba83ad1d6..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/msc/inc/usbd_msc_scsi.h +++ /dev/null @@ -1,189 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_msc_scsi.h - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief header for the usbd_msc_scsi.c file - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USBD_MSC_SCSI_H -#define __USBD_MSC_SCSI_H - -/* Includes ------------------------------------------------------------------*/ -#include "usbd_def.h" - -/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY - * @{ - */ - -/** @defgroup USBD_SCSI - * @brief header file for the storage disk file - * @{ - */ - -/** @defgroup USBD_SCSI_Exported_Defines - * @{ - */ - -#define SENSE_LIST_DEEPTH 4 - -/* SCSI Commands */ -#define SCSI_FORMAT_UNIT 0x04 -#define SCSI_INQUIRY 0x12 -#define SCSI_MODE_SELECT6 0x15 -#define SCSI_MODE_SELECT10 0x55 -#define SCSI_MODE_SENSE6 0x1A -#define SCSI_MODE_SENSE10 0x5A -#define SCSI_ALLOW_MEDIUM_REMOVAL 0x1E -#define SCSI_READ6 0x08 -#define SCSI_READ10 0x28 -#define SCSI_READ12 0xA8 -#define SCSI_READ16 0x88 - -#define SCSI_READ_CAPACITY10 0x25 -#define SCSI_READ_CAPACITY16 0x9E - -#define SCSI_REQUEST_SENSE 0x03 -#define SCSI_START_STOP_UNIT 0x1B -#define SCSI_TEST_UNIT_READY 0x00 -#define SCSI_WRITE6 0x0A -#define SCSI_WRITE10 0x2A -#define SCSI_WRITE12 0xAA -#define SCSI_WRITE16 0x8A - -#define SCSI_VERIFY10 0x2F -#define SCSI_VERIFY12 0xAF -#define SCSI_VERIFY16 0x8F - -#define SCSI_SEND_DIAGNOSTIC 0x1D -#define SCSI_READ_FORMAT_CAPACITIES 0x23 - -#define NO_SENSE 0 -#define RECOVERED_ERROR 1 -#define NOT_READY 2 -#define MEDIUM_ERROR 3 -#define HARDWARE_ERROR 4 -#define ILLEGAL_REQUEST 5 -#define UNIT_ATTENTION 6 -#define DATA_PROTECT 7 -#define BLANK_CHECK 8 -#define VENDOR_SPECIFIC 9 -#define COPY_ABORTED 10 -#define ABORTED_COMMAND 11 -#define VOLUME_OVERFLOW 13 -#define MISCOMPARE 14 - - -#define INVALID_CDB 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 WRITE_PROTECTED 0x27 -#define UNRECOVERED_READ_ERROR 0x11 -#define WRITE_FAULT 0x03 - -#define READ_FORMAT_CAPACITY_DATA_LEN 0x0C -#define READ_CAPACITY10_DATA_LEN 0x08 -#define MODE_SENSE10_DATA_LEN 0x08 -#define MODE_SENSE6_DATA_LEN 0x04 -#define REQUEST_SENSE_DATA_LEN 0x12 -#define STANDARD_INQUIRY_DATA_LEN 0x24 -#define BLKVFY 0x04 - -extern uint8_t Page00_Inquiry_Data[]; -extern uint8_t Standard_Inquiry_Data[]; -extern uint8_t Standard_Inquiry_Data2[]; -extern uint8_t Mode_Sense6_data[]; -extern uint8_t Mode_Sense10_data[]; -extern uint8_t Scsi_Sense_Data[]; -extern uint8_t ReadCapacity10_Data[]; -extern uint8_t ReadFormatCapacity_Data []; -/** - * @} - */ - - -/** @defgroup USBD_SCSI_Exported_TypesDefinitions - * @{ - */ - -typedef struct _SENSE_ITEM { - char Skey; - union { - struct _ASCs { - char ASC; - char ASCQ; - }b; - unsigned int ASC; - char *pData; - } w; -} SCSI_Sense_TypeDef; -/** - * @} - */ - -/** @defgroup USBD_SCSI_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup USBD_SCSI_Exported_Variables - * @{ - */ -extern SCSI_Sense_TypeDef SCSI_Sense [SENSE_LIST_DEEPTH]; -extern uint8_t SCSI_Sense_Head; -extern uint8_t SCSI_Sense_Tail; - -/** - * @} - */ -/** @defgroup USBD_SCSI_Exported_FunctionsPrototype - * @{ - */ -int8_t SCSI_ProcessCmd(USB_OTG_CORE_HANDLE *pdev, - uint8_t lun, - uint8_t *cmd); - -void SCSI_SenseCode(uint8_t lun, - uint8_t sKey, - uint8_t ASC); - -/** - * @} - */ - -#endif /* __USBD_MSC_SCSI_H */ -/** - * @} - */ - -/** - * @} - */ - -/** -* @} -*/ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ - diff --git a/lib/main/STM32_USB_Device_Library/Class/msc/src/usbd_msc_bot.c b/lib/main/STM32_USB_Device_Library/Class/msc/src/usbd_msc_bot.c deleted file mode 100644 index 01c88ddda7..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/msc/src/usbd_msc_bot.c +++ /dev/null @@ -1,393 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_msc_bot.c - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief This file provides all the BOT protocol core functions. - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "usbd_msc_bot.h" -#include "usbd_msc_scsi.h" -#include "usbd_ioreq.h" -#include "usbd_msc_mem.h" -/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY - * @{ - */ - - -/** @defgroup MSC_BOT - * @brief BOT protocol module - * @{ - */ - -/** @defgroup MSC_BOT_Private_TypesDefinitions - * @{ - */ -/** - * @} - */ - - -/** @defgroup MSC_BOT_Private_Defines - * @{ - */ - -/** - * @} - */ - - -/** @defgroup MSC_BOT_Private_Macros - * @{ - */ -/** - * @} - */ - - -/** @defgroup MSC_BOT_Private_Variables - * @{ - */ -uint16_t MSC_BOT_DataLen; -uint8_t MSC_BOT_State; -uint8_t MSC_BOT_Status; - -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 - #endif -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ -__ALIGN_BEGIN uint8_t MSC_BOT_Data[MSC_MEDIA_PACKET] __ALIGN_END ; - -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 - #endif -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ -__ALIGN_BEGIN MSC_BOT_CBW_TypeDef MSC_BOT_cbw __ALIGN_END ; - -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 - #endif -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ -__ALIGN_BEGIN MSC_BOT_CSW_TypeDef MSC_BOT_csw __ALIGN_END ; -/** - * @} - */ - - -/** @defgroup MSC_BOT_Private_FunctionPrototypes - * @{ - */ -static void MSC_BOT_CBW_Decode (USB_OTG_CORE_HANDLE *pdev); - -static void MSC_BOT_SendData (USB_OTG_CORE_HANDLE *pdev, - uint8_t* pbuf, - uint16_t len); - -static void MSC_BOT_Abort(USB_OTG_CORE_HANDLE *pdev); -/** - * @} - */ - - -/** @defgroup MSC_BOT_Private_Functions - * @{ - */ - - - -/** -* @brief MSC_BOT_Init -* Initialize the BOT Process -* @param pdev: device instance -* @retval None -*/ -void MSC_BOT_Init (USB_OTG_CORE_HANDLE *pdev) -{ - MSC_BOT_State = BOT_IDLE; - MSC_BOT_Status = BOT_STATE_NORMAL; - USBD_STORAGE_fops->Init(0); - - DCD_EP_Flush(pdev, MSC_OUT_EP); - DCD_EP_Flush(pdev, MSC_IN_EP); - /* Prapare EP to Receive First BOT Cmd */ - DCD_EP_PrepareRx (pdev, - MSC_OUT_EP, - (uint8_t *)&MSC_BOT_cbw, - BOT_CBW_LENGTH); -} - -/** -* @brief MSC_BOT_Reset -* Reset the BOT Machine -* @param pdev: device instance -* @retval None -*/ -void MSC_BOT_Reset (USB_OTG_CORE_HANDLE *pdev) -{ - MSC_BOT_State = BOT_IDLE; - MSC_BOT_Status = BOT_STATE_RECOVERY; - /* Prapare EP to Receive First BOT Cmd */ - DCD_EP_PrepareRx (pdev, - MSC_OUT_EP, - (uint8_t *)&MSC_BOT_cbw, - BOT_CBW_LENGTH); -} - -/** -* @brief MSC_BOT_DeInit -* Uninitialize the BOT Machine -* @param pdev: device instance -* @retval None -*/ -void MSC_BOT_DeInit (USB_OTG_CORE_HANDLE *pdev) -{ - MSC_BOT_State = BOT_IDLE; -} - -/** -* @brief MSC_BOT_DataIn -* Handle BOT IN data stage -* @param pdev: device instance -* @param epnum: endpoint index -* @retval None -*/ -void MSC_BOT_DataIn (USB_OTG_CORE_HANDLE *pdev, - uint8_t epnum) -{ - - switch (MSC_BOT_State) - { - case BOT_DATA_IN: - if(SCSI_ProcessCmd(pdev, - MSC_BOT_cbw.bLUN, - &MSC_BOT_cbw.CB[0]) < 0) - { - MSC_BOT_SendCSW (pdev, CSW_CMD_FAILED); - } - break; - - case BOT_SEND_DATA: - case BOT_LAST_DATA_IN: - MSC_BOT_SendCSW (pdev, CSW_CMD_PASSED); - - break; - - default: - break; - } -} -/** -* @brief MSC_BOT_DataOut -* Proccess MSC OUT data -* @param pdev: device instance -* @param epnum: endpoint index -* @retval None -*/ -void MSC_BOT_DataOut (USB_OTG_CORE_HANDLE *pdev, - uint8_t epnum) -{ - switch (MSC_BOT_State) - { - case BOT_IDLE: - MSC_BOT_CBW_Decode(pdev); - break; - - case BOT_DATA_OUT: - - if(SCSI_ProcessCmd(pdev, - MSC_BOT_cbw.bLUN, - &MSC_BOT_cbw.CB[0]) < 0) - { - MSC_BOT_SendCSW (pdev, CSW_CMD_FAILED); - } - - break; - - default: - break; - } - -} - -/** -* @brief MSC_BOT_CBW_Decode -* Decode the CBW command and set the BOT state machine accordingtly -* @param pdev: device instance -* @retval None -*/ -static void MSC_BOT_CBW_Decode (USB_OTG_CORE_HANDLE *pdev) -{ - - MSC_BOT_csw.dTag = MSC_BOT_cbw.dTag; - MSC_BOT_csw.dDataResidue = MSC_BOT_cbw.dDataLength; - - if ((USBD_GetRxCount (pdev ,MSC_OUT_EP) != BOT_CBW_LENGTH) || - (MSC_BOT_cbw.dSignature != BOT_CBW_SIGNATURE)|| - (MSC_BOT_cbw.bLUN > 1) || - (MSC_BOT_cbw.bCBLength < 1) || - (MSC_BOT_cbw.bCBLength > 16)) - { - - SCSI_SenseCode(MSC_BOT_cbw.bLUN, - ILLEGAL_REQUEST, - INVALID_CDB); - MSC_BOT_Status = BOT_STATE_ERROR; - MSC_BOT_Abort(pdev); - - } - else - { - if(SCSI_ProcessCmd(pdev, - MSC_BOT_cbw.bLUN, - &MSC_BOT_cbw.CB[0]) < 0) - { - MSC_BOT_Abort(pdev); - } - /*Burst xfer handled internally*/ - else if ((MSC_BOT_State != BOT_DATA_IN) && - (MSC_BOT_State != BOT_DATA_OUT) && - (MSC_BOT_State != BOT_LAST_DATA_IN)) - { - if (MSC_BOT_DataLen > 0) - { - MSC_BOT_SendData(pdev, - MSC_BOT_Data, - MSC_BOT_DataLen); - } - else if (MSC_BOT_DataLen == 0) - { - MSC_BOT_SendCSW (pdev, - CSW_CMD_PASSED); - } - } - } -} - -/** -* @brief MSC_BOT_SendData -* Send the requested data -* @param pdev: device instance -* @param buf: pointer to data buffer -* @param len: Data Length -* @retval None -*/ -static void MSC_BOT_SendData(USB_OTG_CORE_HANDLE *pdev, - uint8_t* buf, - uint16_t len) -{ - - len = MIN (MSC_BOT_cbw.dDataLength, len); - MSC_BOT_csw.dDataResidue -= len; - MSC_BOT_csw.bStatus = CSW_CMD_PASSED; - MSC_BOT_State = BOT_SEND_DATA; - - DCD_EP_Tx (pdev, MSC_IN_EP, buf, len); -} - -/** -* @brief MSC_BOT_SendCSW -* Send the Command Status Wrapper -* @param pdev: device instance -* @param status : CSW status -* @retval None -*/ -void MSC_BOT_SendCSW (USB_OTG_CORE_HANDLE *pdev, - uint8_t CSW_Status) -{ - MSC_BOT_csw.dSignature = BOT_CSW_SIGNATURE; - MSC_BOT_csw.bStatus = CSW_Status; - MSC_BOT_State = BOT_IDLE; - - DCD_EP_Tx (pdev, - MSC_IN_EP, - (uint8_t *)&MSC_BOT_csw, - BOT_CSW_LENGTH); - - /* Prapare EP to Receive next Cmd */ - DCD_EP_PrepareRx (pdev, - MSC_OUT_EP, - (uint8_t *)&MSC_BOT_cbw, - BOT_CBW_LENGTH); - -} - -/** -* @brief MSC_BOT_Abort -* Abort the current transfer -* @param pdev: device instance -* @retval status -*/ - -static void MSC_BOT_Abort (USB_OTG_CORE_HANDLE *pdev) -{ - - if ((MSC_BOT_cbw.bmFlags == 0) && - (MSC_BOT_cbw.dDataLength != 0) && - (MSC_BOT_Status == BOT_STATE_NORMAL) ) - { - DCD_EP_Stall(pdev, MSC_OUT_EP ); - } - DCD_EP_Stall(pdev, MSC_IN_EP); - - if(MSC_BOT_Status == BOT_STATE_ERROR) - { - DCD_EP_PrepareRx (pdev, - MSC_OUT_EP, - (uint8_t *)&MSC_BOT_cbw, - BOT_CBW_LENGTH); - } -} - -/** -* @brief MSC_BOT_CplClrFeature -* Complete the clear feature request -* @param pdev: device instance -* @param epnum: endpoint index -* @retval None -*/ - -void MSC_BOT_CplClrFeature (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum) -{ - if(MSC_BOT_Status == BOT_STATE_ERROR )/* Bad CBW Signature */ - { - DCD_EP_Stall(pdev, MSC_IN_EP); - MSC_BOT_Status = BOT_STATE_NORMAL; - } - else if(((epnum & 0x80) == 0x80) && ( MSC_BOT_Status != BOT_STATE_RECOVERY)) - { - MSC_BOT_SendCSW (pdev, CSW_CMD_FAILED); - } - -} -/** - * @} - */ - - -/** - * @} - */ - - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/msc/src/usbd_msc_core.c b/lib/main/STM32_USB_Device_Library/Class/msc/src/usbd_msc_core.c deleted file mode 100644 index cf03ef4de6..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/msc/src/usbd_msc_core.c +++ /dev/null @@ -1,490 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_msc_core.c - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief This file provides all the MSC core functions. - * - * @verbatim - * - * =================================================================== - * MSC Class Description - * =================================================================== - * This module manages the MSC class V1.0 following the "Universal - * Serial Bus Mass Storage Class (MSC) Bulk-Only Transport (BOT) Version 1.0 - * Sep. 31, 1999". - * This driver implements the following aspects of the specification: - * - Bulk-Only Transport protocol - * - Subclass : SCSI transparent command set (ref. SCSI Primary Commands - 3 (SPC-3)) - * - * @endverbatim - * - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "usbd_msc_mem.h" -#include "usbd_msc_core.h" -#include "usbd_msc_bot.h" -#include "usbd_req.h" - - -/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY - * @{ - */ - - -/** @defgroup MSC_CORE - * @brief Mass storage core module - * @{ - */ - -/** @defgroup MSC_CORE_Private_TypesDefinitions - * @{ - */ -/** - * @} - */ - - -/** @defgroup MSC_CORE_Private_Defines - * @{ - */ - -/** - * @} - */ - - -/** @defgroup MSC_CORE_Private_Macros - * @{ - */ -/** - * @} - */ - - -/** @defgroup MSC_CORE_Private_FunctionPrototypes - * @{ - */ -uint8_t USBD_MSC_Init (void *pdev, - uint8_t cfgidx); - -uint8_t USBD_MSC_DeInit (void *pdev, - uint8_t cfgidx); - -uint8_t USBD_MSC_Setup (void *pdev, - USB_SETUP_REQ *req); - -uint8_t USBD_MSC_DataIn (void *pdev, - uint8_t epnum); - - -uint8_t USBD_MSC_DataOut (void *pdev, - uint8_t epnum); - -uint8_t *USBD_MSC_GetCfgDesc (uint8_t speed, - uint16_t *length); - -#ifdef USB_OTG_HS_CORE -uint8_t *USBD_MSC_GetOtherCfgDesc (uint8_t speed, - uint16_t *length); -#endif - - -uint8_t USBD_MSC_CfgDesc[USB_MSC_CONFIG_DESC_SIZ]; - - - - -/** - * @} - */ - - -/** @defgroup MSC_CORE_Private_Variables - * @{ - */ - - -USBD_Class_cb_TypeDef USBD_MSC_cb = -{ - USBD_MSC_Init, - USBD_MSC_DeInit, - USBD_MSC_Setup, - NULL, /*EP0_TxSent*/ - NULL, /*EP0_RxReady*/ - USBD_MSC_DataIn, - USBD_MSC_DataOut, - NULL, /*SOF */ - NULL, - NULL, - USBD_MSC_GetCfgDesc, -#ifdef USB_OTG_HS_CORE - USBD_MSC_GetOtherCfgDesc, -#endif -}; - -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 - #endif -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ -/* USB Mass storage device Configuration Descriptor */ -/* All Descriptors (Configuration, Interface, Endpoint, Class, Vendor */ -__ALIGN_BEGIN uint8_t USBD_MSC_CfgDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END = -{ - - 0x09, /* bLength: Configuation Descriptor size */ - USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */ - USB_MSC_CONFIG_DESC_SIZ, - - 0x00, - 0x01, /* bNumInterfaces: 1 interface */ - 0x01, /* bConfigurationValue: */ - 0x04, /* iConfiguration: */ - 0xC0, /* bmAttributes: */ - 0x32, /* MaxPower 100 mA */ - - /******************** Mass Storage interface ********************/ - 0x09, /* bLength: Interface Descriptor size */ - 0x04, /* bDescriptorType: */ - 0x00, /* bInterfaceNumber: Number of Interface */ - 0x00, /* bAlternateSetting: Alternate setting */ - 0x02, /* bNumEndpoints*/ - 0x08, /* bInterfaceClass: MSC Class */ - 0x06, /* bInterfaceSubClass : SCSI transparent*/ - 0x50, /* nInterfaceProtocol */ - 0x05, /* iInterface: */ - /******************** Mass Storage Endpoints ********************/ - 0x07, /*Endpoint descriptor length = 7*/ - 0x05, /*Endpoint descriptor type */ - MSC_IN_EP, /*Endpoint address (IN, address 1) */ - 0x02, /*Bulk endpoint type */ - LOBYTE(MSC_MAX_PACKET), - HIBYTE(MSC_MAX_PACKET), - 0x00, /*Polling interval in milliseconds */ - - 0x07, /*Endpoint descriptor length = 7 */ - 0x05, /*Endpoint descriptor type */ - MSC_OUT_EP, /*Endpoint address (OUT, address 1) */ - 0x02, /*Bulk endpoint type */ - LOBYTE(MSC_MAX_PACKET), - HIBYTE(MSC_MAX_PACKET), - 0x00 /*Polling interval in milliseconds*/ -}; -#ifdef USB_OTG_HS_CORE - #ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 - #endif - #endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ -__ALIGN_BEGIN uint8_t USBD_MSC_OtherCfgDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END = -{ - - 0x09, /* bLength: Configuation Descriptor size */ - USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION, - USB_MSC_CONFIG_DESC_SIZ, - - 0x00, - 0x01, /* bNumInterfaces: 1 interface */ - 0x01, /* bConfigurationValue: */ - 0x04, /* iConfiguration: */ - 0xC0, /* bmAttributes: */ - 0x32, /* MaxPower 100 mA */ - - /******************** Mass Storage interface ********************/ - 0x09, /* bLength: Interface Descriptor size */ - 0x04, /* bDescriptorType: */ - 0x00, /* bInterfaceNumber: Number of Interface */ - 0x00, /* bAlternateSetting: Alternate setting */ - 0x02, /* bNumEndpoints*/ - 0x08, /* bInterfaceClass: MSC Class */ - 0x06, /* bInterfaceSubClass : SCSI transparent command set*/ - 0x50, /* nInterfaceProtocol */ - 0x05, /* iInterface: */ - /******************** Mass Storage Endpoints ********************/ - 0x07, /*Endpoint descriptor length = 7*/ - 0x05, /*Endpoint descriptor type */ - MSC_IN_EP, /*Endpoint address (IN, address 1) */ - 0x02, /*Bulk endpoint type */ - 0x40, - 0x00, - 0x00, /*Polling interval in milliseconds */ - - 0x07, /*Endpoint descriptor length = 7 */ - 0x05, /*Endpoint descriptor type */ - MSC_OUT_EP, /*Endpoint address (OUT, address 1) */ - 0x02, /*Bulk endpoint type */ - 0x40, - 0x00, - 0x00 /*Polling interval in milliseconds*/ -}; -#endif - -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 - #endif -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ -__ALIGN_BEGIN static uint8_t USBD_MSC_MaxLun __ALIGN_END = 0; - -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 - #endif -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ -__ALIGN_BEGIN static uint8_t USBD_MSC_AltSet __ALIGN_END = 0; - -/** - * @} - */ - - -/** @defgroup MSC_CORE_Private_Functions - * @{ - */ - -/** -* @brief USBD_MSC_Init -* Initialize the mass storage configuration -* @param pdev: device instance -* @param cfgidx: configuration index -* @retval status -*/ -uint8_t USBD_MSC_Init (void *pdev, - uint8_t cfgidx) -{ - USBD_MSC_DeInit(pdev , cfgidx ); - - /* Open EP IN */ - DCD_EP_Open(pdev, - MSC_IN_EP, - MSC_EPIN_SIZE, - USB_OTG_EP_BULK); - - /* Open EP OUT */ - DCD_EP_Open(pdev, - MSC_OUT_EP, - MSC_EPOUT_SIZE, - USB_OTG_EP_BULK); - - /* Init the BOT layer */ - MSC_BOT_Init(pdev); - - return USBD_OK; -} - -/** -* @brief USBD_MSC_DeInit -* DeInitilaize the mass storage configuration -* @param pdev: device instance -* @param cfgidx: configuration index -* @retval status -*/ -uint8_t USBD_MSC_DeInit (void *pdev, - uint8_t cfgidx) -{ - /* Close MSC EPs */ - DCD_EP_Close (pdev , MSC_IN_EP); - DCD_EP_Close (pdev , MSC_OUT_EP); - - /* Un Init the BOT layer */ - MSC_BOT_DeInit(pdev); - return USBD_OK; -} -/** -* @brief USBD_MSC_Setup -* Handle the MSC specific requests -* @param pdev: device instance -* @param req: USB request -* @retval status -*/ -uint8_t USBD_MSC_Setup (void *pdev, USB_SETUP_REQ *req) -{ - - switch (req->bmRequest & USB_REQ_TYPE_MASK) - { - - /* Class request */ - case USB_REQ_TYPE_CLASS : - switch (req->bRequest) - { - case BOT_GET_MAX_LUN : - - if((req->wValue == 0) && - (req->wLength == 1) && - ((req->bmRequest & 0x80) == 0x80)) - { - USBD_MSC_MaxLun = USBD_STORAGE_fops->GetMaxLun(); - if(USBD_MSC_MaxLun > 0) - { - USBD_CtlSendData (pdev, - &USBD_MSC_MaxLun, - 1); - } - else - { - USBD_CtlError(pdev , req); - return USBD_FAIL; - - } - } - else - { - USBD_CtlError(pdev , req); - return USBD_FAIL; - } - break; - - case BOT_RESET : - if((req->wValue == 0) && - (req->wLength == 0) && - ((req->bmRequest & 0x80) != 0x80)) - { - MSC_BOT_Reset(pdev); - } - else - { - USBD_CtlError(pdev , req); - return USBD_FAIL; - } - break; - - default: - USBD_CtlError(pdev , req); - return USBD_FAIL; - } - break; - /* Interface & Endpoint request */ - case USB_REQ_TYPE_STANDARD: - switch (req->bRequest) - { - case USB_REQ_GET_INTERFACE : - USBD_CtlSendData (pdev, - &USBD_MSC_AltSet, - 1); - break; - - case USB_REQ_SET_INTERFACE : - USBD_MSC_AltSet = (uint8_t)(req->wValue); - break; - - case USB_REQ_CLEAR_FEATURE: - - /* Flush the FIFO and Clear the stall status */ - DCD_EP_Flush(pdev, (uint8_t)req->wIndex); - - /* Re-activate the EP */ - DCD_EP_Close (pdev , (uint8_t)req->wIndex); - if((((uint8_t)req->wIndex) & 0x80) == 0x80) - { - DCD_EP_Open(pdev, - ((uint8_t)req->wIndex), - MSC_EPIN_SIZE, - USB_OTG_EP_BULK); - } - else - { - DCD_EP_Open(pdev, - ((uint8_t)req->wIndex), - MSC_EPOUT_SIZE, - USB_OTG_EP_BULK); - } - - /* Handle BOT error */ - MSC_BOT_CplClrFeature(pdev, (uint8_t)req->wIndex); - break; - - } - break; - - default: - break; - } - return USBD_OK; -} - -/** -* @brief USBD_MSC_DataIn -* handle data IN Stage -* @param pdev: device instance -* @param epnum: endpoint index -* @retval status -*/ -uint8_t USBD_MSC_DataIn (void *pdev, - uint8_t epnum) -{ - MSC_BOT_DataIn(pdev , epnum); - return USBD_OK; -} - -/** -* @brief USBD_MSC_DataOut -* handle data OUT Stage -* @param pdev: device instance -* @param epnum: endpoint index -* @retval status -*/ -uint8_t USBD_MSC_DataOut (void *pdev, - uint8_t epnum) -{ - MSC_BOT_DataOut(pdev , epnum); - return USBD_OK; -} - -/** -* @brief USBD_MSC_GetCfgDesc -* return configuration descriptor -* @param speed : current device speed -* @param length : pointer data length -* @retval pointer to descriptor buffer -*/ -uint8_t *USBD_MSC_GetCfgDesc (uint8_t speed, uint16_t *length) -{ - *length = sizeof (USBD_MSC_CfgDesc); - return USBD_MSC_CfgDesc; -} - -/** -* @brief USBD_MSC_GetOtherCfgDesc -* return other speed configuration descriptor -* @param speed : current device speed -* @param length : pointer data length -* @retval pointer to descriptor buffer -*/ -#ifdef USB_OTG_HS_CORE -uint8_t *USBD_MSC_GetOtherCfgDesc (uint8_t speed, - uint16_t *length) -{ - *length = sizeof (USBD_MSC_OtherCfgDesc); - return USBD_MSC_OtherCfgDesc; -} -#endif -/** - * @} - */ - - -/** - * @} - */ - - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/msc/src/usbd_msc_data.c b/lib/main/STM32_USB_Device_Library/Class/msc/src/usbd_msc_data.c deleted file mode 100644 index b5b0f2db51..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/msc/src/usbd_msc_data.c +++ /dev/null @@ -1,128 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_msc_data.c - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief This file provides all the vital inquiry pages and sense data. - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "usbd_msc_data.h" - - -/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY - * @{ - */ - - -/** @defgroup MSC_DATA - * @brief Mass storage info/data module - * @{ - */ - -/** @defgroup MSC_DATA_Private_TypesDefinitions - * @{ - */ -/** - * @} - */ - - -/** @defgroup MSC_DATA_Private_Defines - * @{ - */ -/** - * @} - */ - - -/** @defgroup MSC_DATA_Private_Macros - * @{ - */ -/** - * @} - */ - - -/** @defgroup MSC_DATA_Private_Variables - * @{ - */ - - -/* USB Mass storage Page 0 Inquiry Data */ -const uint8_t MSC_Page00_Inquiry_Data[] = {//7 - 0x00, - 0x00, - 0x00, - (LENGTH_INQUIRY_PAGE00 - 4), - 0x00, - 0x80, - 0x83 -}; -/* USB Mass storage sense 6 Data */ -const uint8_t MSC_Mode_Sense6_data[] = { - 0x00, - 0x00, - 0x00, - 0x00, - 0x00, - 0x00, - 0x00, - 0x00 -}; -/* USB Mass storage sense 10 Data */ -const uint8_t MSC_Mode_Sense10_data[] = { - 0x00, - 0x06, - 0x00, - 0x00, - 0x00, - 0x00, - 0x00, - 0x00 -}; -/** - * @} - */ - - -/** @defgroup MSC_DATA_Private_FunctionPrototypes - * @{ - */ -/** - * @} - */ - - -/** @defgroup MSC_DATA_Private_Functions - * @{ - */ - -/** - * @} - */ - - -/** - * @} - */ - - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/msc/src/usbd_msc_scsi.c b/lib/main/STM32_USB_Device_Library/Class/msc/src/usbd_msc_scsi.c deleted file mode 100644 index 8cff583bd0..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/msc/src/usbd_msc_scsi.c +++ /dev/null @@ -1,722 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_msc_scsi.c - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief This file provides all the USBD SCSI layer functions. - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "usbd_msc_bot.h" -#include "usbd_msc_scsi.h" -#include "usbd_msc_mem.h" -#include "usbd_msc_data.h" - - - -/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY - * @{ - */ - - -/** @defgroup MSC_SCSI - * @brief Mass storage SCSI layer module - * @{ - */ - -/** @defgroup MSC_SCSI_Private_TypesDefinitions - * @{ - */ -/** - * @} - */ - - -/** @defgroup MSC_SCSI_Private_Defines - * @{ - */ - -/** - * @} - */ - - -/** @defgroup MSC_SCSI_Private_Macros - * @{ - */ -/** - * @} - */ - - -/** @defgroup MSC_SCSI_Private_Variables - * @{ - */ - -SCSI_Sense_TypeDef SCSI_Sense [SENSE_LIST_DEEPTH]; -uint8_t SCSI_Sense_Head; -uint8_t SCSI_Sense_Tail; - -uint32_t SCSI_blk_size; -uint32_t SCSI_blk_nbr; - -uint32_t SCSI_blk_addr; -uint32_t SCSI_blk_len; - -USB_OTG_CORE_HANDLE *cdev; -/** - * @} - */ - - -/** @defgroup MSC_SCSI_Private_FunctionPrototypes - * @{ - */ -static int8_t SCSI_TestUnitReady(uint8_t lun, uint8_t *params); -static int8_t SCSI_Inquiry(uint8_t lun, uint8_t *params); -static int8_t SCSI_ReadFormatCapacity(uint8_t lun, uint8_t *params); -static int8_t SCSI_ReadCapacity10(uint8_t lun, uint8_t *params); -static int8_t SCSI_RequestSense (uint8_t lun, uint8_t *params); -static int8_t SCSI_StartStopUnit(uint8_t lun, uint8_t *params); -static int8_t SCSI_ModeSense6 (uint8_t lun, uint8_t *params); -static int8_t SCSI_ModeSense10 (uint8_t lun, uint8_t *params); -static int8_t SCSI_Write10(uint8_t lun , uint8_t *params); -static int8_t SCSI_Read10(uint8_t lun , uint8_t *params); -static int8_t SCSI_Verify10(uint8_t lun, uint8_t *params); -static int8_t SCSI_CheckAddressRange (uint8_t lun , - uint32_t blk_offset , - uint16_t blk_nbr); -static int8_t SCSI_ProcessRead (uint8_t lun); - -static int8_t SCSI_ProcessWrite (uint8_t lun); -/** - * @} - */ - - -/** @defgroup MSC_SCSI_Private_Functions - * @{ - */ - - -/** -* @brief SCSI_ProcessCmd -* Process SCSI commands -* @param pdev: device instance -* @param lun: Logical unit number -* @param params: Command parameters -* @retval status -*/ -int8_t SCSI_ProcessCmd(USB_OTG_CORE_HANDLE *pdev, - uint8_t lun, - uint8_t *params) -{ - cdev = pdev; - - switch (params[0]) - { - case SCSI_TEST_UNIT_READY: - return SCSI_TestUnitReady(lun, params); - - case SCSI_REQUEST_SENSE: - return SCSI_RequestSense (lun, params); - case SCSI_INQUIRY: - return SCSI_Inquiry(lun, params); - - case SCSI_START_STOP_UNIT: - return SCSI_StartStopUnit(lun, params); - - case SCSI_ALLOW_MEDIUM_REMOVAL: - return SCSI_StartStopUnit(lun, params); - - case SCSI_MODE_SENSE6: - return SCSI_ModeSense6 (lun, params); - - case SCSI_MODE_SENSE10: - return SCSI_ModeSense10 (lun, params); - - case SCSI_READ_FORMAT_CAPACITIES: - return SCSI_ReadFormatCapacity(lun, params); - - case SCSI_READ_CAPACITY10: - return SCSI_ReadCapacity10(lun, params); - - case SCSI_READ10: - return SCSI_Read10(lun, params); - - case SCSI_WRITE10: - return SCSI_Write10(lun, params); - - case SCSI_VERIFY10: - return SCSI_Verify10(lun, params); - - default: - SCSI_SenseCode(lun, - ILLEGAL_REQUEST, - INVALID_CDB); - return -1; - } -} - - -/** -* @brief SCSI_TestUnitReady -* Process SCSI Test Unit Ready Command -* @param lun: Logical unit number -* @param params: Command parameters -* @retval status -*/ -static int8_t SCSI_TestUnitReady(uint8_t lun, uint8_t *params) -{ - - /* case 9 : Hi > D0 */ - if (MSC_BOT_cbw.dDataLength != 0) - { - SCSI_SenseCode(MSC_BOT_cbw.bLUN, - ILLEGAL_REQUEST, - INVALID_CDB); - return -1; - } - - if(USBD_STORAGE_fops->IsReady(lun) !=0 ) - { - SCSI_SenseCode(lun, - NOT_READY, - MEDIUM_NOT_PRESENT); - return -1; - } - MSC_BOT_DataLen = 0; - return 0; -} - -/** -* @brief SCSI_Inquiry -* Process Inquiry command -* @param lun: Logical unit number -* @param params: Command parameters -* @retval status -*/ -static int8_t SCSI_Inquiry(uint8_t lun, uint8_t *params) -{ - uint8_t* pPage; - uint16_t len; - - if (params[1] & 0x01)/*Evpd is set*/ - { - pPage = (uint8_t *)MSC_Page00_Inquiry_Data; - len = LENGTH_INQUIRY_PAGE00; - } - else - { - - pPage = (uint8_t *)&USBD_STORAGE_fops->pInquiry[lun * USBD_STD_INQUIRY_LENGTH]; - len = pPage[4] + 5; - - if (params[4] <= len) - { - len = params[4]; - } - } - MSC_BOT_DataLen = len; - - while (len) - { - len--; - MSC_BOT_Data[len] = pPage[len]; - } - return 0; -} - -/** -* @brief SCSI_ReadCapacity10 -* Process Read Capacity 10 command -* @param lun: Logical unit number -* @param params: Command parameters -* @retval status -*/ -static int8_t SCSI_ReadCapacity10(uint8_t lun, uint8_t *params) -{ - - if(USBD_STORAGE_fops->GetCapacity(lun, &SCSI_blk_nbr, &SCSI_blk_size) != 0) - { - SCSI_SenseCode(lun, - NOT_READY, - MEDIUM_NOT_PRESENT); - return -1; - } - else - { - - MSC_BOT_Data[0] = (uint8_t)(SCSI_blk_nbr - 1 >> 24); - MSC_BOT_Data[1] = (uint8_t)(SCSI_blk_nbr - 1 >> 16); - MSC_BOT_Data[2] = (uint8_t)(SCSI_blk_nbr - 1 >> 8); - MSC_BOT_Data[3] = (uint8_t)(SCSI_blk_nbr - 1); - - MSC_BOT_Data[4] = (uint8_t)(SCSI_blk_size >> 24); - MSC_BOT_Data[5] = (uint8_t)(SCSI_blk_size >> 16); - MSC_BOT_Data[6] = (uint8_t)(SCSI_blk_size >> 8); - MSC_BOT_Data[7] = (uint8_t)(SCSI_blk_size); - - MSC_BOT_DataLen = 8; - return 0; - } -} -/** -* @brief SCSI_ReadFormatCapacity -* Process Read Format Capacity command -* @param lun: Logical unit number -* @param params: Command parameters -* @retval status -*/ -static int8_t SCSI_ReadFormatCapacity(uint8_t lun, uint8_t *params) -{ - - uint32_t blk_size; - uint32_t blk_nbr; - uint16_t i; - - for(i=0 ; i < 12 ; i++) - { - MSC_BOT_Data[i] = 0; - } - - if(USBD_STORAGE_fops->GetCapacity(lun, &blk_nbr, &blk_size) != 0) - { - SCSI_SenseCode(lun, - NOT_READY, - MEDIUM_NOT_PRESENT); - return -1; - } - else - { - MSC_BOT_Data[3] = 0x08; - MSC_BOT_Data[4] = (uint8_t)(blk_nbr - 1 >> 24); - MSC_BOT_Data[5] = (uint8_t)(blk_nbr - 1 >> 16); - MSC_BOT_Data[6] = (uint8_t)(blk_nbr - 1 >> 8); - MSC_BOT_Data[7] = (uint8_t)(blk_nbr - 1); - - MSC_BOT_Data[8] = 0x02; - MSC_BOT_Data[9] = (uint8_t)(blk_size >> 16); - MSC_BOT_Data[10] = (uint8_t)(blk_size >> 8); - MSC_BOT_Data[11] = (uint8_t)(blk_size); - - MSC_BOT_DataLen = 12; - return 0; - } -} -/** -* @brief SCSI_ModeSense6 -* Process Mode Sense6 command -* @param lun: Logical unit number -* @param params: Command parameters -* @retval status -*/ -static int8_t SCSI_ModeSense6 (uint8_t lun, uint8_t *params) -{ - - uint16_t len = 8 ; - MSC_BOT_DataLen = len; - - while (len) - { - len--; - MSC_BOT_Data[len] = MSC_Mode_Sense6_data[len]; - } - return 0; -} - -/** -* @brief SCSI_ModeSense10 -* Process Mode Sense10 command -* @param lun: Logical unit number -* @param params: Command parameters -* @retval status -*/ -static int8_t SCSI_ModeSense10 (uint8_t lun, uint8_t *params) -{ - uint16_t len = 8; - - MSC_BOT_DataLen = len; - - while (len) - { - len--; - MSC_BOT_Data[len] = MSC_Mode_Sense10_data[len]; - } - return 0; -} - -/** -* @brief SCSI_RequestSense -* Process Request Sense command -* @param lun: Logical unit number -* @param params: Command parameters -* @retval status -*/ - -static int8_t SCSI_RequestSense (uint8_t lun, uint8_t *params) -{ - uint8_t i; - - for(i=0 ; i < REQUEST_SENSE_DATA_LEN ; i++) - { - MSC_BOT_Data[i] = 0; - } - - MSC_BOT_Data[0] = 0x70; - MSC_BOT_Data[7] = REQUEST_SENSE_DATA_LEN - 6; - - if((SCSI_Sense_Head != SCSI_Sense_Tail)) { - - MSC_BOT_Data[2] = SCSI_Sense[SCSI_Sense_Head].Skey; - MSC_BOT_Data[12] = SCSI_Sense[SCSI_Sense_Head].w.b.ASCQ; - MSC_BOT_Data[13] = SCSI_Sense[SCSI_Sense_Head].w.b.ASC; - SCSI_Sense_Head++; - - if (SCSI_Sense_Head == SENSE_LIST_DEEPTH) - { - SCSI_Sense_Head = 0; - } - } - MSC_BOT_DataLen = REQUEST_SENSE_DATA_LEN; - - if (params[4] <= REQUEST_SENSE_DATA_LEN) - { - MSC_BOT_DataLen = params[4]; - } - return 0; -} - -/** -* @brief SCSI_SenseCode -* Load the last error code in the error list -* @param lun: Logical unit number -* @param sKey: Sense Key -* @param ASC: Additional Sense Key -* @retval none - -*/ -void SCSI_SenseCode(uint8_t lun, uint8_t sKey, uint8_t ASC) -{ - SCSI_Sense[SCSI_Sense_Tail].Skey = sKey; - SCSI_Sense[SCSI_Sense_Tail].w.ASC = ASC << 8; - SCSI_Sense_Tail++; - if (SCSI_Sense_Tail == SENSE_LIST_DEEPTH) - { - SCSI_Sense_Tail = 0; - } -} -/** -* @brief SCSI_StartStopUnit -* Process Start Stop Unit command -* @param lun: Logical unit number -* @param params: Command parameters -* @retval status -*/ -static int8_t SCSI_StartStopUnit(uint8_t lun, uint8_t *params) -{ - MSC_BOT_DataLen = 0; - return 0; -} - -/** -* @brief SCSI_Read10 -* Process Read10 command -* @param lun: Logical unit number -* @param params: Command parameters -* @retval status -*/ -static int8_t SCSI_Read10(uint8_t lun , uint8_t *params) -{ - if(MSC_BOT_State == BOT_IDLE) /* Idle */ - { - - /* case 10 : Ho <> Di */ - - if ((MSC_BOT_cbw.bmFlags & 0x80) != 0x80) - { - SCSI_SenseCode(MSC_BOT_cbw.bLUN, - ILLEGAL_REQUEST, - INVALID_CDB); - return -1; - } - - if(USBD_STORAGE_fops->IsReady(lun) !=0 ) - { - SCSI_SenseCode(lun, - NOT_READY, - MEDIUM_NOT_PRESENT); - return -1; - } - - SCSI_blk_addr = (params[2] << 24) | \ - (params[3] << 16) | \ - (params[4] << 8) | \ - params[5]; - - SCSI_blk_len = (params[7] << 8) | \ - params[8]; - - - - if( SCSI_CheckAddressRange(lun, SCSI_blk_addr, SCSI_blk_len) < 0) - { - return -1; /* error */ - } - - MSC_BOT_State = BOT_DATA_IN; - SCSI_blk_addr *= SCSI_blk_size; - SCSI_blk_len *= SCSI_blk_size; - - /* cases 4,5 : Hi <> Dn */ - if (MSC_BOT_cbw.dDataLength != SCSI_blk_len) - { - SCSI_SenseCode(MSC_BOT_cbw.bLUN, - ILLEGAL_REQUEST, - INVALID_CDB); - return -1; - } - } - MSC_BOT_DataLen = MSC_MEDIA_PACKET; - - return SCSI_ProcessRead(lun); -} - -/** -* @brief SCSI_Write10 -* Process Write10 command -* @param lun: Logical unit number -* @param params: Command parameters -* @retval status -*/ - -static int8_t SCSI_Write10 (uint8_t lun , uint8_t *params) -{ - if (MSC_BOT_State == BOT_IDLE) /* Idle */ - { - - /* case 8 : Hi <> Do */ - - if ((MSC_BOT_cbw.bmFlags & 0x80) == 0x80) - { - SCSI_SenseCode(MSC_BOT_cbw.bLUN, - ILLEGAL_REQUEST, - INVALID_CDB); - return -1; - } - - /* Check whether Media is ready */ - if(USBD_STORAGE_fops->IsReady(lun) !=0 ) - { - SCSI_SenseCode(lun, - NOT_READY, - MEDIUM_NOT_PRESENT); - return -1; - } - - /* Check If media is write-protected */ - if(USBD_STORAGE_fops->IsWriteProtected(lun) !=0 ) - { - SCSI_SenseCode(lun, - NOT_READY, - WRITE_PROTECTED); - return -1; - } - - - SCSI_blk_addr = (params[2] << 24) | \ - (params[3] << 16) | \ - (params[4] << 8) | \ - params[5]; - SCSI_blk_len = (params[7] << 8) | \ - params[8]; - - /* check if LBA address is in the right range */ - if(SCSI_CheckAddressRange(lun, SCSI_blk_addr, SCSI_blk_len) < 0) - { - return -1; /* error */ - } - - SCSI_blk_addr *= SCSI_blk_size; - SCSI_blk_len *= SCSI_blk_size; - - /* cases 3,11,13 : Hn,Ho <> D0 */ - if (MSC_BOT_cbw.dDataLength != SCSI_blk_len) - { - SCSI_SenseCode(MSC_BOT_cbw.bLUN, - ILLEGAL_REQUEST, - INVALID_CDB); - return -1; - } - - /* Prepare EP to receive first data packet */ - MSC_BOT_State = BOT_DATA_OUT; - DCD_EP_PrepareRx (cdev, - MSC_OUT_EP, - MSC_BOT_Data, - MIN (SCSI_blk_len, MSC_MEDIA_PACKET)); - } - else /* Write Process ongoing */ - { - return SCSI_ProcessWrite(lun); - } - return 0; -} - - -/** -* @brief SCSI_Verify10 -* Process Verify10 command -* @param lun: Logical unit number -* @param params: Command parameters -* @retval status -*/ - -static int8_t SCSI_Verify10(uint8_t lun , uint8_t *params){ - if ((params[1]& 0x02) == 0x02) - { - SCSI_SenseCode (lun, ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND); - return -1; /* Error, Verify Mode Not supported*/ - } - - if(SCSI_CheckAddressRange(lun, SCSI_blk_addr, SCSI_blk_len) < 0) - { - return -1; /* error */ - } - MSC_BOT_DataLen = 0; - return 0; -} - -/** -* @brief SCSI_CheckAddressRange -* Check address range -* @param lun: Logical unit number -* @param blk_offset: first block address -* @param blk_nbr: number of block to be processed -* @retval status -*/ -static int8_t SCSI_CheckAddressRange (uint8_t lun , uint32_t blk_offset , uint16_t blk_nbr) -{ - - if ((blk_offset + blk_nbr) > SCSI_blk_nbr ) - { - SCSI_SenseCode(lun, ILLEGAL_REQUEST, ADDRESS_OUT_OF_RANGE); - return -1; - } - return 0; -} - -/** -* @brief SCSI_ProcessRead -* Handle Read Process -* @param lun: Logical unit number -* @retval status -*/ -static int8_t SCSI_ProcessRead (uint8_t lun) -{ - uint32_t len; - - len = MIN(SCSI_blk_len , MSC_MEDIA_PACKET); - - if( USBD_STORAGE_fops->Read(lun , - MSC_BOT_Data, - SCSI_blk_addr / SCSI_blk_size, - len / SCSI_blk_size) < 0) - { - - SCSI_SenseCode(lun, HARDWARE_ERROR, UNRECOVERED_READ_ERROR); - return -1; - } - - - DCD_EP_Tx (cdev, - MSC_IN_EP, - MSC_BOT_Data, - len); - - - SCSI_blk_addr += len; - SCSI_blk_len -= len; - - /* case 6 : Hi = Di */ - MSC_BOT_csw.dDataResidue -= len; - - if (SCSI_blk_len == 0) - { - MSC_BOT_State = BOT_LAST_DATA_IN; - } - return 0; -} - -/** -* @brief SCSI_ProcessWrite -* Handle Write Process -* @param lun: Logical unit number -* @retval status -*/ - -static int8_t SCSI_ProcessWrite (uint8_t lun) -{ - uint32_t len; - - len = MIN(SCSI_blk_len , MSC_MEDIA_PACKET); - - if(USBD_STORAGE_fops->Write(lun , - MSC_BOT_Data, - SCSI_blk_addr / SCSI_blk_size, - len / SCSI_blk_size) < 0) - { - SCSI_SenseCode(lun, HARDWARE_ERROR, WRITE_FAULT); - return -1; - } - - - SCSI_blk_addr += len; - SCSI_blk_len -= len; - - /* case 12 : Ho = Do */ - MSC_BOT_csw.dDataResidue -= len; - - if (SCSI_blk_len == 0) - { - MSC_BOT_SendCSW (cdev, CSW_CMD_PASSED); - } - else - { - /* Prapare EP to Receive next packet */ - DCD_EP_PrepareRx (cdev, - MSC_OUT_EP, - MSC_BOT_Data, - MIN (SCSI_blk_len, MSC_MEDIA_PACKET)); - } - - return 0; -} -/** - * @} - */ - - -/** - * @} - */ - - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Class/msc/src/usbd_storage_template.c b/lib/main/STM32_USB_Device_Library/Class/msc/src/usbd_storage_template.c deleted file mode 100644 index 927e9dd45a..0000000000 --- a/lib/main/STM32_USB_Device_Library/Class/msc/src/usbd_storage_template.c +++ /dev/null @@ -1,179 +0,0 @@ -/** - ****************************************************************************** - * @file usbd_storage_template.c - * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 - * @brief Memory management layer - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - - -/* Includes ------------------------------------------------------------------*/ -#include "usbd_msc_mem.h" - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Extern function prototypes ------------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -#define STORAGE_LUN_NBR 1 - -int8_t STORAGE_Init (uint8_t lun); - -int8_t STORAGE_GetCapacity (uint8_t lun, - uint32_t *block_num, - uint16_t *block_size); - -int8_t STORAGE_IsReady (uint8_t lun); - -int8_t STORAGE_IsWriteProtected (uint8_t lun); - -int8_t STORAGE_Read (uint8_t lun, - uint8_t *buf, - uint32_t blk_addr, - uint16_t blk_len); - -int8_t STORAGE_Write (uint8_t lun, - uint8_t *buf, - uint32_t blk_addr, - uint16_t blk_len); - -int8_t STORAGE_GetMaxLun (void); - -/* USB Mass storage Standard Inquiry Data */ -const int8_t STORAGE_Inquirydata[] = {//36 - - /* LUN 0 */ - 0x00, - 0x80, - 0x02, - 0x02, - (USBD_STD_INQUIRY_LENGTH - 5), - 0x00, - 0x00, - 0x00, - 'S', 'T', 'M', ' ', ' ', ' ', ' ', ' ', /* Manufacturer : 8 bytes */ - 'P', 'r', 'o', 'd', 'u', 't', ' ', ' ', /* Product : 16 Bytes */ - ' ', ' ', ' ', ' ', ' ', ' ', ' ', ' ', - '0', '.', '0' ,'1', /* Version : 4 Bytes */ -}; - -USBD_STORAGE_cb_TypeDef USBD_MICRO_SDIO_fops = -{ - STORAGE_Init, - STORAGE_GetCapacity, - STORAGE_IsReady, - STORAGE_IsWriteProtected, - STORAGE_Read, - STORAGE_Write, - STORAGE_GetMaxLun, - STORAGE_Inquirydata, - -}; - -USBD_STORAGE_cb_TypeDef *USBD_STORAGE_fops = &USBD_MICRO_SDIO_fops; -/******************************************************************************* -* Function Name : Read_Memory -* Description : Handle the Read operation from the microSD card. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -int8_t STORAGE_Init (uint8_t lun) -{ - return (0); -} - -/******************************************************************************* -* Function Name : Read_Memory -* Description : Handle the Read operation from the STORAGE card. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -int8_t STORAGE_GetCapacity (uint8_t lun, uint32_t *block_num, uint16_t *block_size) -{ - return (0); -} - -/******************************************************************************* -* Function Name : Read_Memory -* Description : Handle the Read operation from the STORAGE card. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -int8_t STORAGE_IsReady (uint8_t lun) -{ - return (0); -} - -/******************************************************************************* -* Function Name : Read_Memory -* Description : Handle the Read operation from the STORAGE card. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -int8_t STORAGE_IsWriteProtected (uint8_t lun) -{ - return 0; -} - -/******************************************************************************* -* Function Name : Read_Memory -* Description : Handle the Read operation from the STORAGE card. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -int8_t STORAGE_Read (uint8_t lun, - uint8_t *buf, - uint32_t blk_addr, - uint16_t blk_len) -{ - return 0; -} -/******************************************************************************* -* Function Name : Write_Memory -* Description : Handle the Write operation to the STORAGE card. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -int8_t STORAGE_Write (uint8_t lun, - uint8_t *buf, - uint32_t blk_addr, - uint16_t blk_len) -{ - return (0); -} -/******************************************************************************* -* Function Name : Write_Memory -* Description : Handle the Write operation to the STORAGE card. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -int8_t STORAGE_GetMaxLun (void) -{ - return (STORAGE_LUN_NBR - 1); -} - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ - diff --git a/lib/main/STM32_USB_Device_Library/Core/inc/usbd_conf_template.h b/lib/main/STM32_USB_Device_Library/Core/inc/usbd_conf_template.h index 34cd39d11f..4d35c19284 100644 --- a/lib/main/STM32_USB_Device_Library/Core/inc/usbd_conf_template.h +++ b/lib/main/STM32_USB_Device_Library/Core/inc/usbd_conf_template.h @@ -2,20 +2,26 @@ ****************************************************************************** * @file usbd_conf_template.h * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 + * @version V1.2.0 + * @date 30-June-2015 * @brief usb device configuration template file ****************************************************************************** * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -24,9 +30,7 @@ #define __USBD_CONF__H__ /* Includes ------------------------------------------------------------------*/ -#include "stm32f2xx.h" - - +#include "usb_conf.h" /** @defgroup USB_CONF_Exported_Defines * @{ @@ -74,5 +78,5 @@ #endif //__USBD_CONF__H__ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Core/inc/usbd_core.h b/lib/main/STM32_USB_Device_Library/Core/inc/usbd_core.h index fb20acf63b..f11b1ffd6d 100644 --- a/lib/main/STM32_USB_Device_Library/Core/inc/usbd_core.h +++ b/lib/main/STM32_USB_Device_Library/Core/inc/usbd_core.h @@ -2,20 +2,26 @@ ****************************************************************************** * @file usbd_core.h * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 + * @version V1.2.0 + * @date 09-November-2015 * @brief Header file for usbd_core.c ****************************************************************************** - * @attention + * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -108,7 +114,7 @@ USBD_Status USBD_SetCfg(USB_OTG_CORE_HANDLE *pdev, uint8_t cfgidx); * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Core/inc/usbd_def.h b/lib/main/STM32_USB_Device_Library/Core/inc/usbd_def.h index a8c86710d7..965989cf2b 100644 --- a/lib/main/STM32_USB_Device_Library/Core/inc/usbd_def.h +++ b/lib/main/STM32_USB_Device_Library/Core/inc/usbd_def.h @@ -2,20 +2,26 @@ ****************************************************************************** * @file usbd_def.h * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 + * @version V1.2.0 + * @date 09-November-2015 * @brief general defines for the usb device library ****************************************************************************** - * @attention + * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -23,6 +29,7 @@ #ifndef __USBD_DEF_H #define __USBD_DEF_H + /* Includes ------------------------------------------------------------------*/ #include "usbd_conf.h" @@ -86,7 +93,7 @@ #define USB_DESC_TYPE_ENDPOINT 5 #define USB_DESC_TYPE_DEVICE_QUALIFIER 6 #define USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION 7 - +#define USB_DESC_TYPE_BOS 0x0F #define USB_CONFIG_REMOTE_WAKEUP 2 #define USB_CONFIG_SELF_POWERED 1 @@ -115,8 +122,8 @@ #define SWAPBYTE(addr) (((uint16_t)(*((uint8_t *)(addr)))) + \ (((uint16_t)(*(((uint8_t *)(addr)) + 1))) << 8)) -#define LOBYTE(x) ((uint8_t)(x & 0x00FF)) -#define HIBYTE(x) ((uint8_t)((x & 0xFF00) >>8)) +#define LOBYTE(x) ((uint8_t)((x) & 0x00FF)) +#define HIBYTE(x) ((uint8_t)(((x) & 0xFF00) >>8)) /** * @} */ @@ -146,4 +153,4 @@ /** * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Core/inc/usbd_ioreq.h b/lib/main/STM32_USB_Device_Library/Core/inc/usbd_ioreq.h index ca755f2bb6..835ae7428f 100644 --- a/lib/main/STM32_USB_Device_Library/Core/inc/usbd_ioreq.h +++ b/lib/main/STM32_USB_Device_Library/Core/inc/usbd_ioreq.h @@ -2,20 +2,26 @@ ****************************************************************************** * @file usbd_ioreq.h * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 + * @version V1.2.0 + * @date 09-November-2015 * @brief header file for the usbd_ioreq.c file ****************************************************************************** * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -112,4 +118,4 @@ uint16_t USBD_GetRxCount (USB_OTG_CORE_HANDLE *pdev , /** * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Core/inc/usbd_req.h b/lib/main/STM32_USB_Device_Library/Core/inc/usbd_req.h index 9aa9e44a32..8b8582b3ac 100644 --- a/lib/main/STM32_USB_Device_Library/Core/inc/usbd_req.h +++ b/lib/main/STM32_USB_Device_Library/Core/inc/usbd_req.h @@ -2,20 +2,26 @@ ****************************************************************************** * @file usbd_req.h * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 + * @version V1.2.0 + * @date 09-November-2015 * @brief header file for the usbd_req.c file ****************************************************************************** - * @attention + * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -99,4 +105,4 @@ void USBD_GetString(uint8_t *desc, uint8_t *unicode, uint16_t *len); */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Core/inc/usbd_usr.h b/lib/main/STM32_USB_Device_Library/Core/inc/usbd_usr.h index 44e7b1dd2d..8db10f6213 100644 --- a/lib/main/STM32_USB_Device_Library/Core/inc/usbd_usr.h +++ b/lib/main/STM32_USB_Device_Library/Core/inc/usbd_usr.h @@ -2,20 +2,26 @@ ****************************************************************************** * @file usbd_usr.h * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 + * @version V1.2.0 + * @date 09-November-2015 * @brief Header file for usbd_usr.c ****************************************************************************** * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -24,9 +30,7 @@ #define __USBD_USR_H__ /* Includes ------------------------------------------------------------------*/ -#include "usbd_core.h" - - +#include "usbd_ioreq.h" /** @addtogroup USBD_USER * @{ */ @@ -128,8 +132,4 @@ void USBD_USR_HS_DeviceDisconnected(void); * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ - - - - +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Core/src/usbd_core.c b/lib/main/STM32_USB_Device_Library/Core/src/usbd_core.c index 2316cc31e0..0613f5018a 100644 --- a/lib/main/STM32_USB_Device_Library/Core/src/usbd_core.c +++ b/lib/main/STM32_USB_Device_Library/Core/src/usbd_core.c @@ -2,20 +2,26 @@ ****************************************************************************** * @file usbd_core.c * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 + * @version V1.2.0 + * @date 09-November-2015 * @brief This file provides all the USBD core functions. ****************************************************************************** * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -79,6 +85,7 @@ static uint8_t USBD_DevDisconnected(USB_OTG_CORE_HANDLE *pdev); #endif static uint8_t USBD_IsoINIncomplete(USB_OTG_CORE_HANDLE *pdev); static uint8_t USBD_IsoOUTIncomplete(USB_OTG_CORE_HANDLE *pdev); +static uint8_t USBD_RunTestMode (USB_OTG_CORE_HANDLE *pdev) ; /** * @} */ @@ -87,23 +94,26 @@ static uint8_t USBD_IsoOUTIncomplete(USB_OTG_CORE_HANDLE *pdev); * @{ */ - +__IO USB_OTG_DCTL_TypeDef SET_TEST_MODE; USBD_DCD_INT_cb_TypeDef USBD_DCD_INT_cb = { - USBD_DataOutStage, - USBD_DataInStage, - USBD_SetupStage, - USBD_SOF, - USBD_Reset, - USBD_Suspend, - USBD_Resume, - USBD_IsoINIncomplete, - USBD_IsoOUTIncomplete, + USBD_DataOutStage, + USBD_DataInStage, + USBD_SetupStage, + USBD_SOF, + USBD_Reset, + USBD_Suspend, + USBD_Resume, + USBD_IsoINIncomplete, + USBD_IsoOUTIncomplete, #ifdef VBUS_SENSING_ENABLED -USBD_DevConnected, -USBD_DevDisconnected, -#endif + USBD_DevConnected, + USBD_DevDisconnected, +#else + NULL, + NULL, +#endif }; USBD_DCD_INT_cb_TypeDef *USBD_DCD_INT_fops = &USBD_DCD_INT_cb; @@ -117,7 +127,7 @@ USBD_DCD_INT_cb_TypeDef *USBD_DCD_INT_fops = &USBD_DCD_INT_cb; /** * @brief USBD_Init -* Initailizes the device stack and load the class driver +* Initializes the device stack and load the class driver * @param pdev: device instance * @param core_address: USB OTG core ID * @param class_cb: Class callback structure address @@ -152,7 +162,7 @@ void USBD_Init(USB_OTG_CORE_HANDLE *pdev, /** * @brief USBD_DeInit -* Re-Initialize th deviuce library +* Re-Initialize the device library * @param pdev: device instance * @retval status: status */ @@ -160,6 +170,7 @@ USBD_Status USBD_DeInit(USB_OTG_CORE_HANDLE *pdev) { /* Software Init */ (void)pdev; + return USBD_OK; } @@ -240,7 +251,12 @@ static uint8_t USBD_DataOutStage(USB_OTG_CORE_HANDLE *pdev , uint8_t epnum) (pdev->dev.device_status == USB_OTG_CONFIGURED)) { pdev->dev.class_cb->DataOut(pdev, epnum); - } + } + + else + { + /* Do Nothing */ + } return USBD_OK; } @@ -271,6 +287,12 @@ static uint8_t USBD_DataInStage(USB_OTG_CORE_HANDLE *pdev , uint8_t epnum) USBD_CtlContinueSendData (pdev, ep->xfer_buff, ep->rem_data_len); + + /* Start the transfer */ + DCD_EP_PrepareRx (pdev, + 0, + NULL, + 0); } else { /* last packet is MPS multiple, so send ZLP packet */ @@ -281,6 +303,12 @@ static uint8_t USBD_DataInStage(USB_OTG_CORE_HANDLE *pdev , uint8_t epnum) USBD_CtlContinueSendData(pdev , NULL, 0); ep->ctl_data_len = 0; + + /* Start the transfer */ + DCD_EP_PrepareRx (pdev, + 0, + NULL, + 0); } else { @@ -293,15 +321,40 @@ static uint8_t USBD_DataInStage(USB_OTG_CORE_HANDLE *pdev , uint8_t epnum) } } } + if (pdev->dev.test_mode == 1) + { + USBD_RunTestMode(pdev); + pdev->dev.test_mode = 0; + } } else if((pdev->dev.class_cb->DataIn != NULL)&& (pdev->dev.device_status == USB_OTG_CONFIGURED)) { pdev->dev.class_cb->DataIn(pdev, epnum); - } + } + + else + { + /* Do Nothing */ + } return USBD_OK; } + + + +/** +* @brief USBD_RunTestMode +* Launch test mode process +* @param pdev: device instance +* @retval status +*/ +static uint8_t USBD_RunTestMode (USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_WRITE_REG32(&pdev->regs.DREGS->DCTL, SET_TEST_MODE.d32); + return USBD_OK; +} + /** * @brief USBD_Reset * Handle Reset event @@ -341,6 +394,7 @@ static uint8_t USBD_Resume(USB_OTG_CORE_HANDLE *pdev) { /* Upon Resume call usr call back */ pdev->dev.usr_cb->DeviceResumed(); + pdev->dev.device_status = pdev->dev.device_old_status; pdev->dev.device_status = USB_OTG_CONFIGURED; return USBD_OK; } @@ -355,7 +409,7 @@ static uint8_t USBD_Resume(USB_OTG_CORE_HANDLE *pdev) static uint8_t USBD_Suspend(USB_OTG_CORE_HANDLE *pdev) { - + pdev->dev.device_old_status = pdev->dev.device_status; pdev->dev.device_status = USB_OTG_SUSPENDED; /* Upon Resume call usr call back */ pdev->dev.usr_cb->DeviceSuspended(); @@ -442,6 +496,7 @@ static uint8_t USBD_IsoOUTIncomplete(USB_OTG_CORE_HANDLE *pdev) static uint8_t USBD_DevConnected(USB_OTG_CORE_HANDLE *pdev) { pdev->dev.usr_cb->DeviceConnected(); + pdev->dev.connection_status = 1; return USBD_OK; } @@ -455,6 +510,7 @@ static uint8_t USBD_DevDisconnected(USB_OTG_CORE_HANDLE *pdev) { pdev->dev.usr_cb->DeviceDisconnected(); pdev->dev.class_cb->DeInit(pdev, 0); + pdev->dev.connection_status = 0; return USBD_OK; } #endif @@ -472,5 +528,5 @@ static uint8_t USBD_DevDisconnected(USB_OTG_CORE_HANDLE *pdev) * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Core/src/usbd_ioreq.c b/lib/main/STM32_USB_Device_Library/Core/src/usbd_ioreq.c index 6964766bd1..fd5493dcd9 100644 --- a/lib/main/STM32_USB_Device_Library/Core/src/usbd_ioreq.c +++ b/lib/main/STM32_USB_Device_Library/Core/src/usbd_ioreq.c @@ -2,25 +2,32 @@ ****************************************************************************** * @file usbd_ioreq.c * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 + * @version V1.2.0 + * @date 09-November-2015 * @brief This file provides the IO requests APIs for control endpoints. ****************************************************************************** * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ /* Includes ------------------------------------------------------------------*/ #include "usbd_ioreq.h" + /** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY * @{ */ @@ -169,7 +176,7 @@ USBD_Status USBD_CtlContinueRx (USB_OTG_CORE_HANDLE *pdev, } /** * @brief USBD_CtlSendStatus -* send zero lzngth packet on the ctl pipe +* send zero length packet on the ctl pipe * @param pdev: USB OTG device instance * @retval status */ @@ -189,7 +196,7 @@ USBD_Status USBD_CtlSendStatus (USB_OTG_CORE_HANDLE *pdev) /** * @brief USBD_CtlReceiveStatus -* receive zero lzngth packet on the ctl pipe +* receive zero length packet on the ctl pipe * @param pdev: USB OTG device instance * @retval status */ @@ -234,4 +241,4 @@ uint16_t USBD_GetRxCount (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum) * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_Device_Library/Core/src/usbd_req.c b/lib/main/STM32_USB_Device_Library/Core/src/usbd_req.c index f08d26c6c5..b74e82e3a1 100644 --- a/lib/main/STM32_USB_Device_Library/Core/src/usbd_req.c +++ b/lib/main/STM32_USB_Device_Library/Core/src/usbd_req.c @@ -2,20 +2,26 @@ ****************************************************************************** * @file usbd_req.c * @author MCD Application Team - * @version V1.0.0 - * @date 22-July-2011 + * @version V1.2.0 + * @date 09-November-2015 * @brief This file provides the standard USB requests following chapter 9. ****************************************************************************** * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -63,6 +69,7 @@ /** @defgroup USBD_REQ_Private_Variables * @{ */ +extern __IO USB_OTG_DCTL_TypeDef SET_TEST_MODE; #ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED #if defined ( __ICCARM__ ) /*!< IAR Compiler */ @@ -85,11 +92,6 @@ __ALIGN_BEGIN uint32_t USBD_default_cfg __ALIGN_END = 0; #endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ __ALIGN_BEGIN uint32_t USBD_cfg_status __ALIGN_END = 0; -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 - #endif -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ __ALIGN_BEGIN uint8_t USBD_StrDesc[USB_MAX_STR_DESC_SIZ] __ALIGN_END ; /** * @} @@ -233,10 +235,16 @@ USBD_Status USBD_StdEPReq (USB_OTG_CORE_HANDLE *pdev, USB_SETUP_REQ *req) USBD_Status ret = USBD_OK; ep_addr = LOBYTE(req->wIndex); - - switch (req->bRequest) + + /* Check the class specific requests before going to standard request */ + if ((req->bmRequest & USB_REQ_TYPE_MASK) == USB_REQ_TYPE_CLASS) { - + pdev->dev.class_cb->Setup (pdev, req); + return ret; + } + + switch (req->bRequest) + { case USB_REQ_SET_FEATURE : switch (pdev->dev.device_status) @@ -333,6 +341,12 @@ USBD_Status USBD_StdEPReq (USB_OTG_CORE_HANDLE *pdev, USB_SETUP_REQ *req) USBD_ep_status = 0x0000; } } + + else + { + /* Do Nothing */ + } + USBD_CtlSendData (pdev, (uint8_t *)&USBD_ep_status, 2); @@ -361,15 +375,17 @@ static void USBD_GetDescriptor(USB_OTG_CORE_HANDLE *pdev, { uint16_t len; uint8_t *pbuf; - + len = req->wLength ; + switch (req->wValue >> 8) { +#if (USBD_LPM_ENABLED == 1) + case USB_DESC_TYPE_BOS: + pbuf = pdev->pDesc->GetBOSDescriptor(pdev->dev_speed, &len); + break; +#endif case USB_DESC_TYPE_DEVICE: pbuf = pdev->dev.usr_device->GetDeviceDescriptor(pdev->cfg.speed, &len); - if ((req->wLength == 64) ||( pdev->dev.device_status == USB_OTG_DEFAULT)) - { - len = 8; - } break; case USB_DESC_TYPE_CONFIGURATION: @@ -419,7 +435,7 @@ static void USBD_GetDescriptor(USB_OTG_CORE_HANDLE *pdev, #else USBD_CtlError(pdev , req); return; -#endif /* USBD_CtlError(pdev , req); */ +#endif /* USBD_CtlError(pdev , req)*/ } break; case USB_DESC_TYPE_DEVICE_QUALIFIER: @@ -449,7 +465,7 @@ static void USBD_GetDescriptor(USB_OTG_CORE_HANDLE *pdev, case USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION: #ifdef USB_OTG_HS_CORE - + if(pdev->cfg.speed == USB_OTG_SPEED_HIGH ) { pbuf = (uint8_t *)pdev->dev.class_cb->GetOtherConfigDescriptor(pdev->cfg.speed, &len); @@ -465,8 +481,6 @@ static void USBD_GetDescriptor(USB_OTG_CORE_HANDLE *pdev, USBD_CtlError(pdev , req); return; #endif - - default: USBD_CtlError(pdev , req); return; @@ -646,23 +660,26 @@ static void USBD_GetStatus(USB_OTG_CORE_HANDLE *pdev, USB_SETUP_REQ *req) { + switch (pdev->dev.device_status) { case USB_OTG_ADDRESSED: case USB_OTG_CONFIGURED: +#ifdef USBD_SELF_POWERED + USBD_cfg_status = USB_CONFIG_SELF_POWERED; +#else + USBD_cfg_status = 0x00; +#endif + if (pdev->dev.DevRemoteWakeup) { - USBD_cfg_status = USB_CONFIG_SELF_POWERED | USB_CONFIG_REMOTE_WAKEUP; - } - else - { - USBD_cfg_status = USB_CONFIG_SELF_POWERED; + USBD_cfg_status |= USB_CONFIG_REMOTE_WAKEUP; } USBD_CtlSendData (pdev, (uint8_t *)&USBD_cfg_status, - 1); + 2); break; default : @@ -701,30 +718,38 @@ static void USBD_SetFeature(USB_OTG_CORE_HANDLE *pdev, test_mode = req->wIndex >> 8; switch (test_mode) { - case 1: // TEST_J + case 1: /* TEST_J */ dctl.b.tstctl = 1; break; - case 2: // TEST_K + case 2: /* TEST_K */ dctl.b.tstctl = 2; break; - case 3: // TEST_SE0_NAK + case 3: /* TEST_SE0_NAK */ dctl.b.tstctl = 3; break; - case 4: // TEST_PACKET + case 4: /* TEST_PACKET */ dctl.b.tstctl = 4; break; - case 5: // TEST_FORCE_ENABLE + case 5: /* TEST_FORCE_ENABLE */ dctl.b.tstctl = 5; break; + + default : + dctl.b.tstctl = 1; + break; } - USB_OTG_WRITE_REG32(&pdev->regs.DREGS->DCTL, dctl.d32); + SET_TEST_MODE = dctl; + pdev->dev.test_mode = 1; USBD_CtlSendStatus(pdev); } - + else + { + /* Do Nothing */ + } } @@ -788,21 +813,9 @@ void USBD_ParseSetupRequest( USB_OTG_CORE_HANDLE *pdev, void USBD_CtlError( USB_OTG_CORE_HANDLE *pdev, USB_SETUP_REQ *req) { - if((req->bmRequest & 0x80) == 0x80) - { - DCD_EP_Stall(pdev , 0x80); - } - else - { - if(req->wLength == 0) - { - DCD_EP_Stall(pdev , 0x80); - } - else - { - DCD_EP_Stall(pdev , 0); - } - } + (void)req; + DCD_EP_Stall(pdev , 0x80); + DCD_EP_Stall(pdev , 0); USB_OTG_EP0_OutStart(pdev); } @@ -865,4 +878,4 @@ static uint8_t USBD_GetLen(uint8_t *buf) * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_OTG_Driver/Release_Notes.html b/lib/main/STM32_USB_OTG_Driver/Release_Notes.html index 17d2a0832f..4aa1e5aa9f 100644 --- a/lib/main/STM32_USB_OTG_Driver/Release_Notes.html +++ b/lib/main/STM32_USB_OTG_Driver/Release_Notes.html @@ -1,941 +1,952 @@ - - - - - - - -Release Notes for STM32F105/7xx and STM32F2xx USB OTG Driver - - - - - -
- -

 

- -
- - - - - -
- - - - - - - -
-

Back to Release page

-
-

Release Notes for STM32F105/7xx and STM32F2xx USB OTG Driver

-

Copyright - 2011 STMicroelectronics

-

-
-

 

- - - - -
-

Contents

-
    -
  1. STM32F105/7xx and STM32F2xx USB OTG Driver update History
  2. -
  3. License
  4. -
-

STM32F105/7xx and STM32F2xx USB OTG Driver  update History

V2.0.0 / 22-July-2011

Main -Changes

-
  • Second official version supporting STM32F105/7 and STM32F2xx devices
  • Rename the Library from "STM32_USB_HOST_Driver" to "STM32_USB_OTG_Driver"
  • Add support for STM32F2xx devices
  • Add support for Device and OTG modes
  • Change HCD layer to support High speed core
  • Change the Low level driver to support multi core support for Host mode
  • Add Stop mechanism for Host and Device modes
  • Change VBUS enabling method, to use the external or the internal VBUS when using the ULPI

V1.0.0 - 11/29/2010

-
  • Created 

License

-

The use of this STM32 software is governed by the terms and conditions of the License Agreement "MCD-ST Liberty SW License Agreement 20Jul2011 v0.1.pdf" available in the root of this package. 

-
-
-
-

For - complete documentation on STM32(CORTEX M3) 32-Bit - Microcontrollers visit www.st.com/STM32

-
-

-
- -
- -

 

- -
- + + + + +Release Notes for STM32F105/7xx, STM32F2xx and STM32F4xx USB OTG Driver + + + + + + + + +
+ +

 

+ +
+ + + + + +
+ + + + + + + +
+

Back to Release page

+
+

Release Notes for STM32F105/7xx, STM32F2xx and STM32F4xx USB OTG Driver

+

Copyright + 2015 STMicroelectronics

+

+
+

 

+ + + + +
+

Update History

V2.2.0 / 09-November-2015

Main +Changes

+ +
    +
  • Add support of  STM32F469/479xx and  STM32F446 devices
  • +
  • usb_dcd_int.c
    • Bug +Fix: Masking the TxFIFOempty interrupt of the endpoint after +finishing writing data packet to TxFIFO in DCD_WriteEmptyTxFifo function
    • Bug Fix: The USB TRD (Turnaround) is configured depending on AHB frequency used by application.
    • Bug Fix: Handle multi-packet for OUT transfer with DMA in HS mode
    • Remove CLEAR_IN_EP_INTR(epnum, emptyintr) in USBD_OTG_EP1IN_ISR_Handler and DCD_HandleInEP_ISR
    • Correct PCFCCTL register access
  • usb_core.c
    • USB_OTG_HC_Halt function: Modify Channel halt function to disable the channel at the end
    • Correct PCFCCTL register access
    • Bug Fix: Handle multi-packet for OUT transfer with DMA in HS mode
    • Bug Fix: Keep the disconnect interrupt maskedIn function  USB_OTG_EnableHostInt for correct handling of connection/disconnection
    • In function USB_OTG_ResetPort change reset time to 100ms instead of 10ms for better stability during enumeration
  • usb_hcd.c
    •  Add function HCD_IsPortEnabled to check portenabled for correct handling of connection/disconnection
  • usb_hcd_int.c 
    • Remove USB_OTG_ResetPort(pdev) calling 
    • Update USB_OTG_USBH_handle_port_ISR for correct handling of connection/disconnection
    • Disconnect interrupt is unmasked after a connection
    • Creation of PortEnabled event (need to wait for this event before starting enumerating device)
    • Halt channel and restart transfer is removed When using DMA (HS) In case of NAK or NYET in USB_OTG_USBH_handle_hc_n_Out_ISR and USB_OTG_USBH_handle_hc_n_In_ISR
    • Clearing the NAK interrupt flag before re-enabling the channel for a new transfer in USB_OTG_USBH_handle_hc_n_In_ISR function

V2.1.0 / 19-March-2012

+

Main +Changes

+ +
  • Official support of STM32F4xx devices
  • All source files: license disclaimer text update and add link to the License file on ST Internet
  • Unmask Session request interrupt to handle the connect event during the core start-up
  • Remove any reference to the USB HS external I2C PHY
  • Update optimization pragma for AR Compiler
  • Handle Correctly the Low Speed device connection in HS mode
  • Add a wrapper to isolate the library from the low level driver: connection done through ISR structure
  • Miscellaneous bug fix

V2.0.0 / 22-July-2011

Main +Changes

+
  • Second official version supporting STM32F105/7 and STM32F2xx devices
  • Rename the Library from "STM32_USB_HOST_Driver" to "STM32_USB_OTG_Driver"
  • Add support for STM32F2xx devices
  • Add support for Device and OTG modes
  • Change HCD layer to support High speed core
  • Change the Low level driver to support multi core support for Host mode
  • Add Stop mechanism for Host and Device modes
  • Change VBUS enabling method, to use the external or the internal VBUS when using the ULPI

V1.0.0 - 11/29/2010

+
  • Created 

License

+

Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); You may not use this package except in compliance with the License. You may obtain a copy of the License at:


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.
+
+
+
+

For + complete documentation on STM32 + Microcontrollers visit www.st.com/STM32

+
+

+
+ +
+ +

 

+ +
+ \ No newline at end of file diff --git a/lib/main/STM32_USB_OTG_Driver/inc/usb_bsp.h b/lib/main/STM32_USB_OTG_Driver/inc/usb_bsp.h index 37a1344dcb..158ee7efd3 100644 --- a/lib/main/STM32_USB_OTG_Driver/inc/usb_bsp.h +++ b/lib/main/STM32_USB_OTG_Driver/inc/usb_bsp.h @@ -2,20 +2,26 @@ ****************************************************************************** * @file usb_bsp.h * @author MCD Application Team - * @version V2.0.0 - * @date 22-July-2011 + * @version V2.2.0 + * @date 09-November-2015 * @brief Specific api's relative to the used hardware platform ****************************************************************************** * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -75,15 +81,19 @@ void USB_OTG_BSP_Init (USB_OTG_CORE_HANDLE *pdev); void USB_OTG_BSP_uDelay (const uint32_t usec); void USB_OTG_BSP_mDelay (const uint32_t msec); void USB_OTG_BSP_EnableInterrupt (USB_OTG_CORE_HANDLE *pdev); +void USB_OTG_BSP_TimerIRQ (void); #ifdef USE_HOST_MODE void USB_OTG_BSP_ConfigVBUS(USB_OTG_CORE_HANDLE *pdev); void USB_OTG_BSP_DriveVBUS(USB_OTG_CORE_HANDLE *pdev,uint8_t state); -#endif +void USB_OTG_BSP_Resume(USB_OTG_CORE_HANDLE *pdev) ; +void USB_OTG_BSP_Suspend(USB_OTG_CORE_HANDLE *pdev); + +#endif /* USE_HOST_MODE */ /** * @} */ -#endif //__USB_BSP__H__ +#endif /* __USB_BSP__H__ */ /** * @} @@ -92,5 +102,5 @@ void USB_OTG_BSP_DriveVBUS(USB_OTG_CORE_HANDLE *pdev,uint8_t state); /** * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_OTG_Driver/inc/usb_conf_template.h b/lib/main/STM32_USB_OTG_Driver/inc/usb_conf_template.h index f3695478d0..53c9edb1ef 100644 --- a/lib/main/STM32_USB_OTG_Driver/inc/usb_conf_template.h +++ b/lib/main/STM32_USB_OTG_Driver/inc/usb_conf_template.h @@ -2,20 +2,26 @@ ****************************************************************************** * @file usb_conf.h * @author MCD Application Team - * @version V2.0.0 - * @date 22-July-2011 - * @brief general low level driver configuration + * @version V2.2.0 + * @date 09-November-2015 + * @brief General low level driver configuration ****************************************************************************** * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -24,8 +30,7 @@ #define __USB_CONF__H__ /* Includes ------------------------------------------------------------------*/ -#include "stm32f2xx.h" - +#include "usb_conf.h" /** @addtogroup USB_OTG_DRIVER * @{ @@ -45,10 +50,37 @@ configuration, you can declare the needed define in your toolchain compiler preprocessor. */ +/****************** USB OTG FS PHY CONFIGURATION ******************************* +* The USB OTG FS Core supports one on-chip Full Speed PHY. +* +* The USE_EMBEDDED_PHY symbol is defined in the project compiler preprocessor +* when FS core is used. +*******************************************************************************/ #ifndef USE_USB_OTG_FS //#define USE_USB_OTG_FS #endif /* USE_USB_OTG_FS */ +#ifdef USE_USB_OTG_FS + #define USB_OTG_FS_CORE +#endif + +/****************** USB OTG HS PHY CONFIGURATION ******************************* +* The USB OTG HS Core supports two PHY interfaces: +* (i) An ULPI interface for the external High Speed PHY: the USB HS Core will +* operate in High speed mode +* (ii) An on-chip Full Speed PHY: the USB HS Core will operate in Full speed mode +* +* You can select the PHY to be used using one of these two defines: +* (i) USE_ULPI_PHY: if the USB OTG HS Core is to be used in High speed mode +* (ii) USE_EMBEDDED_PHY: if the USB OTG HS Core is to be used in Full speed mode +* +* Notes: +* - The USE_ULPI_PHY symbol is defined in the project compiler preprocessor as +* default PHY when HS core is used. +* - On STM322xG-EVAL and STM324xG-EVAL boards, only configuration(i) is available. +* Configuration (ii) need a different hardware, for more details refer to your +* STM32 device datasheet. +*******************************************************************************/ #ifndef USE_USB_OTG_HS //#define USE_USB_OTG_HS #endif /* USE_USB_OTG_HS */ @@ -61,15 +93,6 @@ //#define USE_EMBEDDED_PHY #endif /* USE_EMBEDDED_PHY */ -#ifndef USE_I2C_PHY - //#define USE_I2C_PHY -#endif /* USE_I2C_PHY */ - - -#ifdef USE_USB_OTG_FS - #define USB_OTG_FS_CORE -#endif - #ifdef USE_USB_OTG_HS #define USB_OTG_HS_CORE #endif @@ -139,10 +162,10 @@ #define TXH_NP_HS_FIFOSIZ 96 #define TXH_P_HS_FIFOSIZ 96 - //#define USB_OTG_HS_LOW_PWR_MGMT_SUPPORT - //#define USB_OTG_HS_SOF_OUTPUT_ENABLED +// #define USB_OTG_HS_LOW_PWR_MGMT_SUPPORT +// #define USB_OTG_HS_SOF_OUTPUT_ENABLED - //#define USB_OTG_INTERNAL_VBUS_ENABLED +// #define USB_OTG_INTERNAL_VBUS_ENABLED #define USB_OTG_EXTERNAL_VBUS_ENABLED #ifdef USE_ULPI_PHY @@ -151,9 +174,6 @@ #ifdef USE_EMBEDDED_PHY #define USB_OTG_EMBEDDED_PHY_ENABLED #endif - #ifdef USE_I2C_PHY - #define USB_OTG_I2C_PHY_ENABLED - #endif #define USB_OTG_HS_INTERNAL_DMA_ENABLED #define USB_OTG_HS_DEDICATED_EP1_ENABLED #endif @@ -168,23 +188,24 @@ #define TXH_NP_HS_FIFOSIZ 96 #define TXH_P_HS_FIFOSIZ 96 - //#define USB_OTG_FS_LOW_PWR_MGMT_SUPPORT - //#define USB_OTG_FS_SOF_OUTPUT_ENABLED +// #define USB_OTG_FS_LOW_PWR_MGMT_SUPPORT +// #define USB_OTG_FS_SOF_OUTPUT_ENABLED #endif +/****************** USB OTG MISC CONFIGURATION ********************************/ +//#define VBUS_SENSING_ENABLED + /****************** USB OTG MODE CONFIGURATION ********************************/ //#define USE_HOST_MODE #define USE_DEVICE_MODE //#define USE_OTG_MODE - #ifndef USB_OTG_FS_CORE #ifndef USB_OTG_HS_CORE #error "USB_OTG_HS_CORE or USB_OTG_FS_CORE should be defined" #endif #endif - #ifndef USE_DEVICE_MODE #ifndef USE_HOST_MODE #error "USE_DEVICE_MODE or USE_HOST_MODE should be defined" @@ -198,9 +219,7 @@ #else //USE_USB_OTG_HS #ifndef USE_ULPI_PHY #ifndef USE_EMBEDDED_PHY - #ifndef USE_I2C_PHY - #error "USE_ULPI_PHY or USE_EMBEDDED_PHY or USE_I2C_PHY should be defined" - #endif + #error "USE_ULPI_PHY or USE_EMBEDDED_PHY should be defined" #endif #endif #endif @@ -228,7 +247,6 @@ #endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ /* __packed keyword used to decrease the data type alignment to 1-byte */ - #if defined (__CC_ARM) /* ARM Compiler */ #define __packed __packed #elif defined (__ICCARM__) /* IAR Compiler */ @@ -284,5 +302,5 @@ /** * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_OTG_Driver/inc/usb_core.h b/lib/main/STM32_USB_OTG_Driver/inc/usb_core.h index 82a09e15c3..eaf1b5de50 100644 --- a/lib/main/STM32_USB_OTG_Driver/inc/usb_core.h +++ b/lib/main/STM32_USB_OTG_Driver/inc/usb_core.h @@ -2,20 +2,26 @@ ****************************************************************************** * @file usb_core.h * @author MCD Application Team - * @version V2.0.0 - * @date 22-July-2011 + * @version V2.2.0 + * @date 09-November-2015 * @brief Header of the Core Layer ****************************************************************************** * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -63,7 +69,7 @@ /** * @} */ -#define MAX_DATA_LENGTH 0xFF +#define MAX_DATA_LENGTH 0x200 /** @defgroup USB_CORE_Exported_Types * @{ @@ -188,18 +194,12 @@ typedef struct _Device_TypeDef uint8_t *(*GetProductStrDescriptor)( uint8_t speed , uint16_t *length); uint8_t *(*GetSerialStrDescriptor)( uint8_t speed , uint16_t *length); uint8_t *(*GetConfigurationStrDescriptor)( uint8_t speed , uint16_t *length); - uint8_t *(*GetInterfaceStrDescriptor)( uint8_t speed , uint16_t *length); -} USBD_DEVICE, *pUSBD_DEVICE; + uint8_t *(*GetInterfaceStrDescriptor)( uint8_t speed , uint16_t *length); -typedef struct USB_OTG_hPort -{ - void (*Disconnect) (void *phost); - void (*Connect) (void *phost); - uint8_t ConnStatus; - uint8_t DisconnStatus; - uint8_t ConnHandled; - uint8_t DisconnHandled; -} USB_OTG_hPort_TypeDef; +#if (USBD_LPM_ENABLED == 1) + uint8_t *(*GetBOSDescriptor)( uint8_t speed , uint16_t *length); +#endif +} USBD_DEVICE, *pUSBD_DEVICE; typedef struct _Device_cb { @@ -248,7 +248,10 @@ typedef struct _DCD uint8_t device_config; uint8_t device_state; uint8_t device_status; + uint8_t device_old_status; uint8_t device_address; + uint8_t connection_status; + uint8_t test_mode; uint32_t DevRemoteWakeup; USB_OTG_EP in_ep [USB_OTG_MAX_TX_FIFOS]; USB_OTG_EP out_ep [USB_OTG_MAX_TX_FIFOS]; @@ -265,13 +268,13 @@ typedef struct _HCD { uint8_t Rx_Buffer [MAX_DATA_LENGTH]; __IO uint32_t ConnSts; + __IO uint32_t PortEnabled; __IO uint32_t ErrCnt[USB_OTG_MAX_TX_FIFOS]; __IO uint32_t XferCnt[USB_OTG_MAX_TX_FIFOS]; __IO HC_STATUS HC_Status[USB_OTG_MAX_TX_FIFOS]; __IO URB_STATE URB_State[USB_OTG_MAX_TX_FIFOS]; USB_OTG_HC hc [USB_OTG_MAX_TX_FIFOS]; uint16_t channel [USB_OTG_MAX_TX_FIFOS]; - USB_OTG_hPort_TypeDef *port_cb; } HCD_DEV , *USB_OTG_USBH_PDEV; @@ -404,5 +407,5 @@ uint32_t USB_OTG_GetEPStatus(USB_OTG_CORE_HANDLE *pdev ,USB_OTG_EP *ep); /** * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_OTG_Driver/inc/usb_dcd.h b/lib/main/STM32_USB_OTG_Driver/inc/usb_dcd.h index 6bfd89939c..123126cb67 100644 --- a/lib/main/STM32_USB_OTG_Driver/inc/usb_dcd.h +++ b/lib/main/STM32_USB_OTG_Driver/inc/usb_dcd.h @@ -2,20 +2,26 @@ ****************************************************************************** * @file usb_dcd.h * @author MCD Application Team - * @version V2.0.0 - * @date 22-July-2011 + * @version V2.2.0 + * @date 09-November-2015 * @brief Peripheral Driver Header file ****************************************************************************** - * @attention + * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -144,7 +150,7 @@ void DCD_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , */ -#endif //__DCD_H__ +#endif /* __DCD_H__ */ /** @@ -154,5 +160,5 @@ void DCD_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , /** * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_OTG_Driver/inc/usb_dcd_int.h b/lib/main/STM32_USB_OTG_Driver/inc/usb_dcd_int.h index 2edd876922..cd942e2b21 100644 --- a/lib/main/STM32_USB_OTG_Driver/inc/usb_dcd_int.h +++ b/lib/main/STM32_USB_OTG_Driver/inc/usb_dcd_int.h @@ -2,20 +2,26 @@ ****************************************************************************** * @file usb_dcd_int.h * @author MCD Application Team - * @version V2.0.0 - * @date 22-July-2011 + * @version V2.2.0 + * @date 09-November-2015 * @brief Peripheral Device Interface Layer ****************************************************************************** - * @attention + * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -53,12 +59,11 @@ typedef struct _USBD_DCD_INT uint8_t (* Resume) (USB_OTG_CORE_HANDLE *pdev); uint8_t (* IsoINIncomplete) (USB_OTG_CORE_HANDLE *pdev); uint8_t (* IsoOUTIncomplete) (USB_OTG_CORE_HANDLE *pdev); -#ifdef VBUS_SENSING_ENABLED - uint8_t (* DevConnected) (USB_OTG_CORE_HANDLE *pdev); - uint8_t (* DevDisconnected) (USB_OTG_CORE_HANDLE *pdev); -#endif -}USBD_DCD_INT_cb_TypeDef; + uint8_t (* DevConnected) (USB_OTG_CORE_HANDLE *pdev); + uint8_t (* DevDisconnected) (USB_OTG_CORE_HANDLE *pdev); + +} USBD_DCD_INT_cb_TypeDef; extern USBD_DCD_INT_cb_TypeDef *USBD_DCD_INT_fops; /** @@ -85,7 +90,7 @@ extern USBD_DCD_INT_cb_TypeDef *USBD_DCD_INT_fops; #define CLEAR_OUT_EP_INTR(epnum,intr) \ doepint.d32=0; \ doepint.b.intr = 1; \ - USB_OTG_WRITE_REG32(&pdev->regs.OUTEP_REGS[epnum]->DOEPINT,doepint.d32); + USB_OTG_WRITE_REG32(&pdev->regs.OUTEP_REGS[(epnum)]->DOEPINT,doepint.d32); /** * @} @@ -103,13 +108,14 @@ extern USBD_DCD_INT_cb_TypeDef *USBD_DCD_INT_fops; */ uint32_t USBD_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev); - +uint32_t USBD_OTG_EP1OUT_ISR_Handler (USB_OTG_CORE_HANDLE *pdev); +uint32_t USBD_OTG_EP1IN_ISR_Handler (USB_OTG_CORE_HANDLE *pdev); /** * @} */ -#endif // USB_DCD_INT_H__ +#endif /* USB_DCD_INT_H__ */ /** * @} @@ -118,5 +124,5 @@ uint32_t USBD_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev); /** * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_OTG_Driver/inc/usb_defines.h b/lib/main/STM32_USB_OTG_Driver/inc/usb_defines.h index b119c2586e..34cc8520ca 100644 --- a/lib/main/STM32_USB_OTG_Driver/inc/usb_defines.h +++ b/lib/main/STM32_USB_OTG_Driver/inc/usb_defines.h @@ -2,20 +2,26 @@ ****************************************************************************** * @file usb_defines.h * @author MCD Application Team - * @version V2.0.0 - * @date 22-July-2011 + * @version V2.2.0 + * @date 09-November-2015 * @brief Header of the Core Layer ****************************************************************************** * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -57,7 +63,6 @@ #define USB_OTG_ULPI_PHY 1 #define USB_OTG_EMBEDDED_PHY 2 -#define USB_OTG_I2C_PHY 3 /** * @} @@ -215,10 +220,10 @@ typedef enum /** @defgroup Internal_Macro's * @{ */ -#define USB_OTG_READ_REG32(reg) (*(__IO uint32_t *)reg) -#define USB_OTG_WRITE_REG32(reg,value) (*(__IO uint32_t *)reg = value) +#define USB_OTG_READ_REG32(reg) (*(__IO uint32_t *)(reg)) +#define USB_OTG_WRITE_REG32(reg,value) (*(__IO uint32_t *)(reg) = (value)) #define USB_OTG_MODIFY_REG32(reg,clear_mask,set_mask) \ - USB_OTG_WRITE_REG32(reg, (((USB_OTG_READ_REG32(reg)) & ~clear_mask) | set_mask ) ) + USB_OTG_WRITE_REG32((reg), (((USB_OTG_READ_REG32(reg)) & ~(clear_mask)) | (set_mask)) ) /******************************************************************************** ENUMERATION TYPE @@ -230,7 +235,7 @@ enum USB_OTG_SPEED { USB_SPEED_HIGH }; -#endif //__USB_DEFINES__H__ +#endif /* __USB_DEFINES__H__ */ /** @@ -240,5 +245,5 @@ enum USB_OTG_SPEED { /** * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_OTG_Driver/inc/usb_hcd.h b/lib/main/STM32_USB_OTG_Driver/inc/usb_hcd.h index 15e8ab161e..9462d284ed 100644 --- a/lib/main/STM32_USB_OTG_Driver/inc/usb_hcd.h +++ b/lib/main/STM32_USB_OTG_Driver/inc/usb_hcd.h @@ -2,20 +2,26 @@ ****************************************************************************** * @file usb_hcd.h * @author MCD Application Team - * @version V2.0.0 - * @date 22-July-2011 + * @version V2.2.0 + * @date 09-November-2015 * @brief Host layer Header file ****************************************************************************** * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -80,6 +86,8 @@ uint32_t HCD_SubmitRequest (USB_OTG_CORE_HANDLE *pdev , uint32_t HCD_GetCurrentSpeed (USB_OTG_CORE_HANDLE *pdev); uint32_t HCD_ResetPort (USB_OTG_CORE_HANDLE *pdev); uint32_t HCD_IsDeviceConnected (USB_OTG_CORE_HANDLE *pdev); +uint32_t HCD_IsPortEnabled (USB_OTG_CORE_HANDLE *pdev); + uint32_t HCD_GetCurrentFrame (USB_OTG_CORE_HANDLE *pdev) ; URB_STATE HCD_GetURB_State (USB_OTG_CORE_HANDLE *pdev, uint8_t ch_num); uint32_t HCD_GetXferCnt (USB_OTG_CORE_HANDLE *pdev, uint8_t ch_num); @@ -98,5 +106,5 @@ HC_STATUS HCD_GetHCState (USB_OTG_CORE_HANDLE *pdev, uint8_t ch_num) /** * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_OTG_Driver/inc/usb_hcd_int.h b/lib/main/STM32_USB_OTG_Driver/inc/usb_hcd_int.h index c95c59f825..58e01c00a3 100644 --- a/lib/main/STM32_USB_OTG_Driver/inc/usb_hcd_int.h +++ b/lib/main/STM32_USB_OTG_Driver/inc/usb_hcd_int.h @@ -2,20 +2,26 @@ ****************************************************************************** * @file usb_hcd_int.h * @author MCD Application Team - * @version V2.0.0 - * @date 22-July-2011 + * @version V2.2.0 + * @date 09-November-2015 * @brief Peripheral Device Interface Layer ****************************************************************************** - * @attention + * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -23,7 +29,6 @@ #ifndef __HCD_INT_H__ #define __HCD_INT_H__ - /* Includes ------------------------------------------------------------------*/ #include "usb_hcd.h" @@ -49,6 +54,18 @@ /** @defgroup USB_HCD_INT_Exported_Types * @{ */ + +typedef struct _USBH_HCD_INT +{ + uint8_t (* SOF) (USB_OTG_CORE_HANDLE *pdev); + uint8_t (* DevConnected) (USB_OTG_CORE_HANDLE *pdev); + uint8_t (* DevDisconnected) (USB_OTG_CORE_HANDLE *pdev); + uint8_t (* DevPortEnabled) (USB_OTG_CORE_HANDLE *pdev); + uint8_t (* DevPortDisabled) (USB_OTG_CORE_HANDLE *pdev); + +}USBH_HCD_INT_cb_TypeDef; + +extern USBH_HCD_INT_cb_TypeDef *USBH_HCD_INT_fops; /** * @} */ @@ -66,25 +83,25 @@ USB_OTG_WRITE_REG32(&((HC_REGS)->HCINT), hcint_clear.d32);\ }\ -#define MASK_HOST_INT_CHH(hc_num) { USB_OTG_HCGINTMSK_TypeDef GINTMSK; \ - GINTMSK.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCGINTMSK); \ - GINTMSK.b.chhltd = 0; \ - USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCGINTMSK, GINTMSK.d32);} +#define MASK_HOST_INT_CHH(hc_num) { USB_OTG_HCINTMSK_TypeDef INTMSK; \ + INTMSK.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK); \ + INTMSK.b.chhltd = 0; \ + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK, INTMSK.d32);} -#define UNMASK_HOST_INT_CHH(hc_num) { USB_OTG_HCGINTMSK_TypeDef GINTMSK; \ - GINTMSK.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCGINTMSK); \ - GINTMSK.b.chhltd = 1; \ - USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCGINTMSK, GINTMSK.d32);} +#define UNMASK_HOST_INT_CHH(hc_num) { USB_OTG_HCINTMSK_TypeDef INTMSK; \ + INTMSK.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK); \ + INTMSK.b.chhltd = 1; \ + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK, INTMSK.d32);} -#define MASK_HOST_INT_ACK(hc_num) { USB_OTG_HCGINTMSK_TypeDef GINTMSK; \ - GINTMSK.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCGINTMSK); \ - GINTMSK.b.ack = 0; \ - USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCGINTMSK, GINTMSK.d32);} +#define MASK_HOST_INT_ACK(hc_num) { USB_OTG_HCINTMSK_TypeDef INTMSK; \ + INTMSK.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK); \ + INTMSK.b.ack = 0; \ + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK, GINTMSK.d32);} -#define UNMASK_HOST_INT_ACK(hc_num) { USB_OTG_HCGINTMSK_TypeDef GINTMSK; \ - GINTMSK.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCGINTMSK); \ - GINTMSK.b.ack = 1; \ - USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCGINTMSK, GINTMSK.d32);} +#define UNMASK_HOST_INT_ACK(hc_num) { USB_OTG_HCGINTMSK_TypeDef INTMSK; \ + INTMSK.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK); \ + INTMSK.b.ack = 1; \ + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK, INTMSK.d32);} /** * @} @@ -122,5 +139,5 @@ uint32_t USBH_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev); /** * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_OTG_Driver/inc/usb_otg.h b/lib/main/STM32_USB_OTG_Driver/inc/usb_otg.h index 54d61b827d..44be2cf36d 100644 --- a/lib/main/STM32_USB_OTG_Driver/inc/usb_otg.h +++ b/lib/main/STM32_USB_OTG_Driver/inc/usb_otg.h @@ -2,20 +2,26 @@ ****************************************************************************** * @file usb_otg.h * @author MCD Application Team - * @version V2.0.0 - * @date 22-July-2011 + * @version V2.2.0 + * @date 09-November-2015 * @brief OTG Core Header ****************************************************************************** * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -41,10 +47,9 @@ void USB_OTG_InitiateSRP(void); void USB_OTG_InitiateHNP(uint8_t state , uint8_t mode); -void USB_OTG_Switchback (USB_OTG_CORE_HANDLE *pdev); -uint32_t USB_OTG_GetCurrentState (USB_OTG_CORE_HANDLE *pdev); +void USB_OTG_Switchback (USB_OTG_CORE_DEVICE *pdev); +uint32_t USB_OTG_GetCurrentState (USB_OTG_CORE_DEVICE *pdev); -uint32_t STM32_USBO_OTG_ISR_Handler(USB_OTG_CORE_HANDLE *pdev); /** * @} */ @@ -90,5 +95,5 @@ uint32_t STM32_USBO_OTG_ISR_Handler(USB_OTG_CORE_HANDLE *pdev); /** * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_OTG_Driver/inc/usb_regs.h b/lib/main/STM32_USB_OTG_Driver/inc/usb_regs.h index cd71ddfaf4..8a22d3a5fb 100644 --- a/lib/main/STM32_USB_OTG_Driver/inc/usb_regs.h +++ b/lib/main/STM32_USB_OTG_Driver/inc/usb_regs.h @@ -2,20 +2,26 @@ ****************************************************************************** * @file usb_regs.h * @author MCD Application Team - * @version V2.0.0 - * @date 22-July-2011 + * @version V2.2.0 + * @date 09-November-2015 * @brief hardware registers ****************************************************************************** * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -74,7 +80,7 @@ /** @defgroup __USB_OTG_Core_register * @{ */ -typedef struct _USB_OTG_GREGS //000h +typedef struct _USB_OTG_GREGS /* 000h */ { __IO uint32_t GOTGCTL; /* USB_OTG Control and Status Register 000h*/ __IO uint32_t GOTGINT; /* USB_OTG Interrupt Register 004h*/ @@ -88,8 +94,7 @@ typedef struct _USB_OTG_GREGS //000h __IO uint32_t GRXFSIZ; /* Receive FIFO Size Register 024h*/ __IO uint32_t DIEPTXF0_HNPTXFSIZ; /* EP0 / Non Periodic Tx FIFO Size Register 028h*/ __IO uint32_t HNPTXSTS; /* Non Periodic Tx FIFO/Queue Sts reg 02Ch*/ - __IO uint32_t GI2CCTL; /* I2C Access Register 030h*/ - uint32_t Reserved34; /* PHY Vendor Control Register 034h*/ + uint32_t Reserved30[2]; /* Reserved 030h*/ __IO uint32_t GCCFG; /* General Purpose IO Register 038h*/ __IO uint32_t CID; /* User ID Register 03Ch*/ uint32_t Reserved40[48]; /* Reserved 040h-0FFh*/ @@ -105,7 +110,7 @@ USB_OTG_GREGS; /** @defgroup __device_Registers * @{ */ -typedef struct _USB_OTG_DREGS // 800h +typedef struct _USB_OTG_DREGS /* 800h */ { __IO uint32_t DCFG; /* dev Configuration Register 800h*/ __IO uint32_t DCTL; /* dev Control Register 804h*/ @@ -160,12 +165,12 @@ USB_OTG_INEPREGS; typedef struct _USB_OTG_OUTEPREGS { __IO uint32_t DOEPCTL; /* dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h*/ - __IO uint32_t DOUTEPFRM; /* dev OUT Endpoint Frame number B00h + (ep_num * 20h) + 04h*/ - __IO uint32_t DOEPINT; /* dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h*/ - uint32_t Reserved0C; /* Reserved B00h + (ep_num * 20h) + 0Ch*/ - __IO uint32_t DOEPTSIZ; /* dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h*/ - __IO uint32_t DOEPDMA; /* dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h*/ - uint32_t Reserved18[2]; /* Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch*/ + uint32_t Reserved04; /* Reserved B00h + (ep_num * 20h) + 04h*/ + __IO uint32_t DOEPINT; /* dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h*/ + uint32_t Reserved0C; /* Reserved B00h + (ep_num * 20h) + 0Ch*/ + __IO uint32_t DOEPTSIZ; /* dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h*/ + __IO uint32_t DOEPDMA; /* dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h*/ + uint32_t Reserved18[2]; /* Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch*/ } USB_OTG_OUTEPREGS; /** @@ -200,7 +205,7 @@ typedef struct _USB_OTG_HC_REGS __IO uint32_t HCCHAR; __IO uint32_t HCSPLT; __IO uint32_t HCINT; - __IO uint32_t HCGINTMSK; + __IO uint32_t HCINTMSK; __IO uint32_t HCTSIZ; __IO uint32_t HCDMA; uint32_t Reserved[2]; @@ -214,7 +219,7 @@ USB_OTG_HC_REGS; /** @defgroup __otg_Core_registers * @{ */ -typedef struct USB_OTG_core_regs //000h +typedef struct USB_OTG_core_regs /* 000h */ { USB_OTG_GREGS *GREGS; USB_OTG_DREGS *DREGS; @@ -227,7 +232,7 @@ typedef struct USB_OTG_core_regs //000h __IO uint32_t *PCGCCTL; } USB_OTG_CORE_REGS , *PUSB_OTG_CORE_REGS; -typedef union _USB_OTG_OTGCTL_TypeDef +typedef union _USB_OTG_GOTGCTL_TypeDef { uint32_t d32; struct @@ -250,19 +255,18 @@ uint32_t Reserved12_15 : 4; uint32_t conidsts : 1; -uint32_t Reserved17 : +uint32_t dbct : 1; uint32_t asesvld : 1; uint32_t bsesvld : 1; -uint32_t currmod : - 1; -uint32_t Reserved21_31 : - 11; +uint32_t Reserved20_31 : + 12; } b; -} USB_OTG_OTGCTL_TypeDef ; +} USB_OTG_GOTGCTL_TypeDef ; + typedef union _USB_OTG_GOTGINT_TypeDef { uint32_t d32; @@ -320,15 +324,11 @@ typedef union _USB_OTG_GUSBCFG_TypeDef { uint32_t toutcal : 3; -uint32_t phyif : - 1; -uint32_t ulpi_utmi_sel : - 1; -uint32_t fsintf : - 1; +uint32_t Reserved3_5 : + 3; uint32_t physel : 1; -uint32_t ddrsel : +uint32_t Reserved7 : 1; uint32_t srpcap : 1; @@ -336,11 +336,11 @@ uint32_t hnpcap : 1; uint32_t usbtrdtim : 4; -uint32_t nptxfrwnden : +uint32_t Reserved14 : 1; uint32_t phylpwrclksel : 1; -uint32_t otgutmifssel : +uint32_t Reserved16 : 1; uint32_t ulpi_fsls : 1; @@ -350,12 +350,18 @@ uint32_t ulpi_clk_sus_m : 1; uint32_t ulpi_ext_vbus_drv : 1; -uint32_t ulpi_int_vbus_indicator : +uint32_t ulpi_int_vbus_ind : 1; uint32_t term_sel_dl_pulse : 1; -uint32_t Reserved : - 6; +uint32_t ulpi_ind_cpl : + 1; +uint32_t ulpi_passthrough : + 1; +uint32_t ulpi_protect_disable : + 1; +uint32_t Reserved26_28 : + 3; uint32_t force_host : 1; uint32_t force_dev : @@ -376,7 +382,7 @@ uint32_t hsftrst : 1; uint32_t hstfrm : 1; -uint32_t intknqflsh : +uint32_t Reserved3 : 1; uint32_t rxfflsh : 1; @@ -414,10 +420,8 @@ uint32_t ginnakeff : 1; uint32_t goutnakeff : 1; -uint32_t Reserved8 : - 1; -uint32_t i2cintr : - 1; +uint32_t Reserved8_9 : + 2; uint32_t erlysuspend : 1; uint32_t usbsuspend : @@ -484,10 +488,8 @@ uint32_t ginnakeff : 1; uint32_t goutnakeff : 1; -uint32_t Reserved8 : - 1; -uint32_t i2cintr : - 1; +uint32_t Reserved8_9 : + 2; uint32_t erlysuspend : 1; uint32_t usbsuspend : @@ -500,10 +502,8 @@ uint32_t isooutdrop : 1; uint32_t eopframe : 1; -uint32_t intimerrx : - 1; -uint32_t epmismatch : - 1; +uint32_t Reserved16_17 : + 2; uint32_t inepint: 1; uint32_t outepintr : @@ -588,20 +588,21 @@ typedef union _USB_OTG_HNPTXSTS_TypeDef uint32_t d32; struct { -uint32_t nptxfspcavail : - 16; -uint32_t nptxqspcavail : - 8; -uint32_t nptxqtop_terminate : - 1; -uint32_t nptxqtop_timer : - 2; -uint32_t nptxqtop : - 2; -uint32_t chnum : - 2; -uint32_t Reserved : - 1; + uint32_t nptxfspcavail : + 16; + uint32_t nptxqspcavail : + 8; + struct + { + uint32_t terminate : + 1; + uint32_t token : + 2; + uint32_t chnum : + 4; + } nptxqtop; + uint32_t Reserved : + 1; } b; } USB_OTG_HNPTXSTS_TypeDef ; @@ -617,36 +618,7 @@ uint32_t Reserved : } b; } USB_OTG_DTXFSTSn_TypeDef ; -typedef union _USB_OTG_GI2CCTL_TypeDef -{ - uint32_t d32; - struct - { -uint32_t rwdata : - 8; -uint32_t regaddr : - 8; -uint32_t addr : - 7; -uint32_t i2cen : - 1; -uint32_t ack : - 1; -uint32_t i2csuspctl : - 1; -uint32_t i2cdevaddr : - 2; -uint32_t dat_se0: - 1; -uint32_t Reserved : - 1; -uint32_t rw : - 1; -uint32_t bsydne : - 1; - } - b; -} USB_OTG_GI2CCTL_TypeDef ; + typedef union _USB_OTG_GCCFG_TypeDef { uint32_t d32; @@ -656,7 +628,7 @@ uint32_t Reserved_in : 16; uint32_t pwdn : 1; -uint32_t i2cifen : +uint32_t Reserved_17 : 1; uint32_t vbussensingA : 1; @@ -687,10 +659,8 @@ uint32_t devaddr : 7; uint32_t perfrint : 2; -uint32_t Reserved13_17 : - 5; -uint32_t epmscnt : - 4; +uint32_t Reserved12_31 : + 19; } b; } USB_OTG_DCFG_TypeDef ; @@ -717,8 +687,10 @@ uint32_t sgoutnak : 1; uint32_t cgoutnak : 1; +uint32_t poprg_done : + 1; uint32_t Reserved : - 21; + 20; } b; } USB_OTG_DCTL_TypeDef ; @@ -751,13 +723,13 @@ uint32_t xfercompl : 1; uint32_t epdisabled : 1; -uint32_t ahberr : +uint32_t Reserved2 : 1; uint32_t timeout : 1; uint32_t intktxfemp : 1; -uint32_t intknepmis : +uint32_t Reserved5 : 1; uint32_t inepnakeff : 1; @@ -765,7 +737,7 @@ uint32_t emptyintr : 1; uint32_t txfifoundrn : 1; -uint32_t Reserved08_31 : +uint32_t Reserved14_31 : 23; } b; @@ -780,7 +752,7 @@ uint32_t xfercompl : 1; uint32_t epdisabled : 1; -uint32_t ahberr : +uint32_t Reserved2 : 1; uint32_t setup : 1; @@ -821,8 +793,12 @@ uint32_t rx_thr_en : 1; uint32_t rx_thr_len : 9; -uint32_t Reserved26_31 : - 6; +uint32_t Reserved26 : + 1; +uint32_t arp_en : + 1; +uint32_t Reserved28_31 : + 4; } b; } USB_OTG_DTHRCTL_TypeDef ; @@ -890,12 +866,13 @@ uint32_t xfersize : uint32_t Reserved7_18 : 12; uint32_t pktcnt : - 2; + 1; uint32_t Reserved20_28 : 9; uint32_t supcnt : 2; - uint32_t Reserved31; +uint32_t Reserved31 : + 1; } b; } USB_OTG_DEP0XFRSIZ_TypeDef ; @@ -945,16 +922,17 @@ uint32_t ptxfspcavail : 16; uint32_t ptxqspcavail : 8; -uint32_t ptxqtop_terminate : - 1; -uint32_t ptxqtop_timer : - 2; -uint32_t ptxqtop : - 2; -uint32_t chnum : - 2; -uint32_t ptxqtop_odd : - 1; + struct + { + uint32_t terminate : + 1; + uint32_t token : + 2; + uint32_t chnum : + 4; + uint32_t odd_even : + 1; + } ptxqtop; } b; } USB_OTG_HPTXSTS_TypeDef ; @@ -1118,7 +1096,7 @@ uint32_t dopng : } b; } USB_OTG_HCTSIZn_TypeDef ; -typedef union _USB_OTG_HCGINTMSK_TypeDef +typedef union _USB_OTG_HCINTMSK_TypeDef { uint32_t d32; struct @@ -1149,7 +1127,8 @@ uint32_t Reserved : 21; } b; -} USB_OTG_HCGINTMSK_TypeDef ; +} USB_OTG_HCINTMSK_TypeDef ; + typedef union _USB_OTG_PCGCCTL_TypeDef { uint32_t d32; @@ -1159,8 +1138,12 @@ uint32_t stoppclk : 1; uint32_t gatehclk : 1; -uint32_t Reserved : - 30; +uint32_t Reserved2_3 : + 2; +uint32_t phy_susp : + 1; +uint32_t Reserved5_31 : + 27; } b; } USB_OTG_PCGCCTL_TypeDef ; @@ -1192,7 +1175,7 @@ uint32_t Reserved : */ -#endif //__USB_OTG_REGS_H__ +#endif /* __USB_OTG_REGS_H__ */ /** @@ -1202,5 +1185,5 @@ uint32_t Reserved : /** * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_OTG_Driver/src/usb_bsp_template.c b/lib/main/STM32_USB_OTG_Driver/src/usb_bsp_template.c index c868aded87..5bba0e071c 100644 --- a/lib/main/STM32_USB_OTG_Driver/src/usb_bsp_template.c +++ b/lib/main/STM32_USB_OTG_Driver/src/usb_bsp_template.c @@ -2,21 +2,27 @@ ****************************************************************************** * @file usb_bsp.c * @author MCD Application Team - * @version V2.0.0 - * @date 22-July-2011 + * @version V2.2.0 + * @date 09-November-2015 * @brief This file is responsible to offer board support package and is * configurable by user. ****************************************************************************** * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -80,7 +86,7 @@ /** * @brief USB_OTG_BSP_Init - * Initilizes BSP configurations + * Initializes BSP configurations * @param None * @retval None */ @@ -91,7 +97,7 @@ void USB_OTG_BSP_Init(void) } /** * @brief USB_OTG_BSP_EnableInterrupt - * Enabele USB Global interrupt + * Enable USB Global interrupt * @param None * @retval None */ @@ -125,6 +131,7 @@ void USB_OTG_BSP_DriveVBUS(uint32_t speed, uint8_t state) void USB_OTG_BSP_ConfigVBUS(uint32_t speed) { (void)speed; + } /** @@ -199,4 +206,4 @@ void USB_OTG_BSP_TimerIRQ (void) * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_OTG_Driver/src/usb_core.c b/lib/main/STM32_USB_OTG_Driver/src/usb_core.c index 1b6cb84b49..15213d28cd 100644 --- a/lib/main/STM32_USB_OTG_Driver/src/usb_core.c +++ b/lib/main/STM32_USB_OTG_Driver/src/usb_core.c @@ -2,20 +2,26 @@ ****************************************************************************** * @file usb_core.c * @author MCD Application Team - * @version V2.0.0 - * @date 22-July-2011 + * @version V2.2.0 + * @date 09-November-2015 * @brief USB-OTG Core Layer ****************************************************************************** - * @attention + * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -96,7 +102,7 @@ static void USB_OTG_EnableCommonInt(USB_OTG_CORE_HANDLE *pdev) USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GOTGINT, 0xFFFFFFFF); #endif /* Clear any pending interrupts */ - USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTSTS, 0xFFFFFFFF); + USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTSTS, 0xBFFFFFFF); /* Enable the interrupts in the INTMSK */ int_mask.b.wkupintr = 1; int_mask.b.usbsuspend = 1; @@ -172,9 +178,10 @@ USB_OTG_STS USB_OTG_WritePacket(USB_OTG_CORE_HANDLE *pdev, count32b = (len + 3) / 4; fifo = pdev->regs.DFIFO[ch_ep_num]; - for (i = 0; i < count32b; i++, src+=4) + for (i = 0; i < count32b; i++) { USB_OTG_WRITE_REG32( fifo, *((__packed uint32_t *)src) ); + src+=4; } } return status; @@ -197,10 +204,10 @@ void *USB_OTG_ReadPacket(USB_OTG_CORE_HANDLE *pdev, __IO uint32_t *fifo = pdev->regs.DFIFO[0]; - for ( i = 0; i < count32b; i++, dest += 4 ) + for( i = 0; i < count32b; i++) { *(__packed uint32_t *)dest = USB_OTG_READ_REG32(fifo); - + dest += 4 ; } return ((void *)dest); } @@ -223,7 +230,7 @@ USB_OTG_STS USB_OTG_SelectCore(USB_OTG_CORE_HANDLE *pdev, /* at startup the core is in FS mode */ pdev->cfg.speed = USB_OTG_SPEED_FULL; pdev->cfg.mps = USB_OTG_FS_MAX_PACKET_SIZE ; - + /* initialize device cfg following its address */ if (coreID == USB_OTG_FS_CORE_ID) { @@ -253,13 +260,9 @@ USB_OTG_STS USB_OTG_SelectCore(USB_OTG_CORE_HANDLE *pdev, #ifdef USB_OTG_ULPI_PHY_ENABLED pdev->cfg.phy_itface = USB_OTG_ULPI_PHY; #else - #ifdef USB_OTG_EMBEDDED_PHY_ENABLED +#ifdef USB_OTG_EMBEDDED_PHY_ENABLED pdev->cfg.phy_itface = USB_OTG_EMBEDDED_PHY; - #else - #ifdef USB_OTG_I2C_PHY_ENABLED - pdev->cfg.phy_itface = USB_OTG_I2C_PHY; - #endif - #endif +#endif #endif #ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED @@ -276,6 +279,11 @@ USB_OTG_STS USB_OTG_SelectCore(USB_OTG_CORE_HANDLE *pdev, } + else + { + /* Do Nothing */ + } + pdev->regs.GREGS = (USB_OTG_GREGS *)(baseAddress + \ USB_OTG_CORE_GLOBAL_REGS_OFFSET); pdev->regs.DREGS = (USB_OTG_DREGS *) (baseAddress + \ @@ -323,15 +331,14 @@ USB_OTG_STS USB_OTG_CoreInit(USB_OTG_CORE_HANDLE *pdev) USB_OTG_STS status = USB_OTG_OK; USB_OTG_GUSBCFG_TypeDef usbcfg; USB_OTG_GCCFG_TypeDef gccfg; - USB_OTG_GI2CCTL_TypeDef i2cctl; USB_OTG_GAHBCFG_TypeDef ahbcfg; - +#if defined (STM32F446xx) || defined (STM32F469_479xx) + USB_OTG_DCTL_TypeDef dctl; +#endif usbcfg.d32 = 0; gccfg.d32 = 0; ahbcfg.d32 = 0; - - if (pdev->cfg.phy_itface == USB_OTG_ULPI_PHY) { gccfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GCCFG); @@ -351,15 +358,11 @@ USB_OTG_STS USB_OTG_CoreInit(USB_OTG_CORE_HANDLE *pdev) #ifdef USB_OTG_INTERNAL_VBUS_ENABLED usbcfg.b.ulpi_ext_vbus_drv = 0; /* Use internal VBUS */ #else - #ifdef USB_OTG_EXTERNAL_VBUS_ENABLED +#ifdef USB_OTG_EXTERNAL_VBUS_ENABLED usbcfg.b.ulpi_ext_vbus_drv = 1; /* Use external VBUS */ - #endif +#endif #endif usbcfg.b.term_sel_dl_pulse = 0; /* Data line pulsing using utmi_txvalid */ - usbcfg.b.ulpi_utmi_sel = 1; /* ULPI seleInterfacect */ - - usbcfg.b.phyif = 0; /* 8 bits */ - usbcfg.b.ddrsel = 0; /* single data rate */ usbcfg.b.ulpi_fsls = 0; usbcfg.b.ulpi_clk_sus_m = 0; @@ -377,7 +380,7 @@ USB_OTG_STS USB_OTG_CoreInit(USB_OTG_CORE_HANDLE *pdev) } } - else /* FS interface (embedded Phy or I2C Phy) */ + else /* FS interface (embedded Phy) */ { usbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GUSBCFG);; @@ -385,16 +388,12 @@ USB_OTG_STS USB_OTG_CoreInit(USB_OTG_CORE_HANDLE *pdev) USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GUSBCFG, usbcfg.d32); /* Reset after a PHY select and set Host mode */ USB_OTG_CoreReset(pdev); - /* Enable the I2C interface and deactivate the power down*/ + /* Deactivate the power down*/ gccfg.d32 = 0; gccfg.b.pwdn = 1; - - if(pdev->cfg.phy_itface == USB_OTG_I2C_PHY) - { - gccfg.b.i2cifen = 1; - } gccfg.b.vbussensingA = 1 ; - gccfg.b.vbussensingB = 1 ; + gccfg.b.vbussensingB = 1 ; + #ifndef VBUS_SENSING_ENABLED gccfg.b.disablevbussensing = 1; #endif @@ -406,32 +405,6 @@ USB_OTG_STS USB_OTG_CoreInit(USB_OTG_CORE_HANDLE *pdev) USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GCCFG, gccfg.d32); USB_OTG_BSP_mDelay(20); - /* Program GUSBCFG.OtgUtmifsSel to I2C*/ - usbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GUSBCFG); - - if(pdev->cfg.phy_itface == USB_OTG_I2C_PHY) - { - usbcfg.b.otgutmifssel = 1; - } - - USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GUSBCFG, usbcfg.d32); - - if(pdev->cfg.phy_itface == USB_OTG_I2C_PHY) - { - /*Program GI2CCTL.I2CEn*/ - i2cctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GI2CCTL); - i2cctl.b.i2cdevaddr = 1; - i2cctl.b.i2cen = 0; - i2cctl.b.dat_se0 = 1; - i2cctl.b.addr = 0x2D; - USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GI2CCTL, i2cctl.d32); - - USB_OTG_BSP_mDelay(200); - - i2cctl.b.i2cen = 1; - USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GI2CCTL, i2cctl.d32); - USB_OTG_BSP_mDelay(200); - } } /* case the HS core is working in FS mode */ if(pdev->cfg.dma_enable == 1) @@ -451,6 +424,20 @@ USB_OTG_STS USB_OTG_CoreInit(USB_OTG_CORE_HANDLE *pdev) USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GUSBCFG, usbcfg.d32); USB_OTG_EnableCommonInt(pdev); #endif + +#if defined (STM32F446xx) || defined (STM32F469_479xx) + usbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GUSBCFG); + usbcfg.b.srpcap = 1; + /*clear sdis bit in dctl */ + dctl.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DCTL); + /* Connect device */ + dctl.b.sftdiscon = 0; + USB_OTG_WRITE_REG32(&pdev->regs.DREGS->DCTL, dctl.d32); + dctl.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DCTL); + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GUSBCFG, usbcfg.d32); + USB_OTG_EnableCommonInt(pdev); +#endif + return status; } /** @@ -573,6 +560,11 @@ USB_OTG_STS USB_OTG_SetCurrentMode(USB_OTG_CORE_HANDLE *pdev , uint8_t mode) usbcfg.b.force_dev = 1; } + else + { + /* Do Nothing */ + } + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GUSBCFG, usbcfg.d32); USB_OTG_BSP_mDelay(50); return status; @@ -670,7 +662,15 @@ USB_OTG_STS USB_OTG_CoreInitHost(USB_OTG_CORE_HANDLE *pdev) USB_OTG_WRITE_REG32(pdev->regs.PCGCCTL, 0); /* Initialize Host Configuration Register */ - USB_OTG_InitFSLSPClkSel(pdev , HCFG_48_MHZ); /* in init phase */ + if (pdev->cfg.phy_itface == USB_OTG_ULPI_PHY) + { + USB_OTG_InitFSLSPClkSel(pdev , HCFG_30_60_MHZ); + } + else + { + USB_OTG_InitFSLSPClkSel(pdev , HCFG_48_MHZ); + } + USB_OTG_ResetPort(pdev); hcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HCFG); hcfg.b.fslssupp = 0; @@ -693,9 +693,9 @@ USB_OTG_STS USB_OTG_CoreInitHost(USB_OTG_CORE_HANDLE *pdev) } #endif #ifdef USB_OTG_HS_CORE - if (pdev->cfg.coreID == USB_OTG_HS_CORE_ID) + if (pdev->cfg.coreID == USB_OTG_HS_CORE_ID) { - /* set Rx FIFO size */ + /* set Rx FIFO size */ USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GRXFSIZ, RX_FIFO_HS_SIZE); nptxfifosize.b.startaddr = RX_FIFO_HS_SIZE; nptxfifosize.b.depth = TXH_NP_HS_FIFOSIZ; @@ -722,7 +722,7 @@ USB_OTG_STS USB_OTG_CoreInitHost(USB_OTG_CORE_HANDLE *pdev) for (i = 0; i < pdev->cfg.host_channels; i++) { USB_OTG_WRITE_REG32( &pdev->regs.HC_REGS[i]->HCINT, 0xFFFFFFFF ); - USB_OTG_WRITE_REG32( &pdev->regs.HC_REGS[i]->HCGINTMSK, 0 ); + USB_OTG_WRITE_REG32( &pdev->regs.HC_REGS[i]->HCINTMSK, 0 ); } #ifndef USE_OTG_MODE USB_OTG_DriveVbus(pdev, 1); @@ -796,12 +796,19 @@ USB_OTG_STS USB_OTG_EnableHostInt(USB_OTG_CORE_HANDLE *pdev) { intmsk.b.rxstsqlvl = 1; } - intmsk.b.portintr = 1; - intmsk.b.hcintr = 1; - intmsk.b.disconnect = 1; - intmsk.b.sofintr = 1; - intmsk.b.incomplisoout = 1; + + + intmsk.b.incomplisoout = 1; + intmsk.b.hcintr = 1; +intmsk.b.portintr = 1; USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GINTMSK, intmsk.d32, intmsk.d32); + + intmsk.d32 = 0; + + intmsk.b.disconnect = 1; + + intmsk.b.sofintr = 1; + USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GINTMSK, intmsk.d32, 0); return status; } @@ -865,7 +872,7 @@ uint32_t USB_OTG_ResetPort(USB_OTG_CORE_HANDLE *pdev) hprt0.d32 = USB_OTG_ReadHPRT0(pdev); hprt0.b.prtrst = 1; USB_OTG_WRITE_REG32(pdev->regs.HPRT0, hprt0.d32); - USB_OTG_BSP_mDelay (10); /* See Note #1 */ + USB_OTG_BSP_mDelay (100); /* See Note #1 */ hprt0.b.prtrst = 0; USB_OTG_WRITE_REG32(pdev->regs.HPRT0, hprt0.d32); USB_OTG_BSP_mDelay (20); @@ -883,7 +890,7 @@ USB_OTG_STS USB_OTG_HC_Init(USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num) { USB_OTG_STS status = USB_OTG_OK; uint32_t intr_enable = 0; - USB_OTG_HCGINTMSK_TypeDef hcintmsk; + USB_OTG_HCINTMSK_TypeDef hcintmsk; USB_OTG_GINTMSK_TypeDef gintmsk; USB_OTG_HCCHAR_TypeDef hcchar; USB_OTG_HCINTn_TypeDef hcint; @@ -955,7 +962,7 @@ USB_OTG_STS USB_OTG_HC_Init(USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num) } - USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCGINTMSK, hcintmsk.d32); + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK, hcintmsk.d32); /* Enable the top level host channel interrupt. */ @@ -1048,11 +1055,11 @@ USB_OTG_STS USB_OTG_HC_StartXfer(USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num) hcchar.b.chen = 1; hcchar.b.chdis = 0; USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR, hcchar.d32); - + if (pdev->cfg.dma_enable == 0) /* Slave mode */ { if((pdev->host.hc[hc_num].ep_is_in == 0) && - (pdev->host.hc[hc_num].xfer_len > 0)) + (pdev->host.hc[hc_num].xfer_len > 0)) { switch(pdev->host.hc[hc_num].ep_type) { @@ -1116,7 +1123,7 @@ USB_OTG_STS USB_OTG_HC_Halt(USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num) nptxsts.d32 = 0; hptxsts.d32 = 0; hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR); - hcchar.b.chen = 1; + hcchar.b.chdis = 1; /* Check for space in the request queue to issue the halt. */ @@ -1126,6 +1133,7 @@ USB_OTG_STS USB_OTG_HC_Halt(USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num) if (nptxsts.b.nptxqspcavail == 0) { hcchar.b.chen = 0; + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR, hcchar.d32); } } else @@ -1134,8 +1142,10 @@ USB_OTG_STS USB_OTG_HC_Halt(USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num) if (hptxsts.b.ptxqspcavail == 0) { hcchar.b.chen = 0; + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR, hcchar.d32); } } + hcchar.b.chen = 1; USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR, hcchar.d32); return status; } @@ -1150,7 +1160,7 @@ USB_OTG_STS USB_OTG_HC_DoPing(USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num) USB_OTG_STS status = USB_OTG_OK; USB_OTG_HCCHAR_TypeDef hcchar; USB_OTG_HCTSIZn_TypeDef hctsiz; - + hctsiz.d32 = 0; hctsiz.b.dopng = 1; hctsiz.b.pktcnt = 1; @@ -1282,7 +1292,7 @@ USB_OTG_STS USB_OTG_CoreInitDev (USB_OTG_CORE_HANDLE *pdev) if(pdev->cfg.phy_itface == USB_OTG_ULPI_PHY) { - USB_OTG_InitDevSpeed (pdev , USB_OTG_SPEED_PARAM_HIGH); + USB_OTG_InitDevSpeed (pdev , USB_OTG_SPEED_PARAM_HIGH); } else /* set High speed phy in Full speed mode */ { @@ -1405,7 +1415,7 @@ USB_OTG_STS USB_OTG_EnableDevInt(USB_OTG_CORE_HANDLE *pdev) /* Disable all interrupts. */ USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTMSK, 0); /* Clear any pending interrupts */ - USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTSTS, 0xFFFFFFFF); + USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTSTS, 0xBFFFFFFF); /* Enable the common interrupts */ USB_OTG_EnableCommonInt(pdev); @@ -1421,7 +1431,7 @@ USB_OTG_STS USB_OTG_EnableDevInt(USB_OTG_CORE_HANDLE *pdev) intmsk.b.inepintr = 1; intmsk.b.outepintr = 1; intmsk.b.sofintr = 1; - + intmsk.b.incomplisoin = 1; intmsk.b.incomplisoout = 1; #ifdef VBUS_SENSING_ENABLED @@ -1460,10 +1470,14 @@ enum USB_OTG_SPEED USB_OTG_GetDeviceSpeed (USB_OTG_CORE_HANDLE *pdev) case DSTS_ENUMSPD_LS_PHY_6MHZ: speed = USB_SPEED_LOW; break; + default: + speed = USB_SPEED_FULL; + break; } return speed; } + /** * @brief enables EP0 OUT to receive SETUP packets and configures EP0 * for transmitting packets @@ -1492,6 +1506,9 @@ USB_OTG_STS USB_OTG_EP0Activate(USB_OTG_CORE_HANDLE *pdev) case DSTS_ENUMSPD_LS_PHY_6MHZ: diepctl.b.mps = DEP0CTL_MPS_8; break; + default: + diepctl.b.mps = DEP0CTL_MPS_64; + break; } USB_OTG_WRITE_REG32(&pdev->regs.INEP_REGS[0]->DIEPCTL, diepctl.d32); dctl.b.cgnpinnak = 1; @@ -1628,7 +1645,7 @@ USB_OTG_STS USB_OTG_EPStartXfer(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep) */ deptsiz.b.xfersize = ep->xfer_len; deptsiz.b.pktcnt = (ep->xfer_len - 1 + ep->maxpacket) / ep->maxpacket; - + if (ep->type == EP_TYPE_ISOC) { deptsiz.b.mc = 1; @@ -1672,7 +1689,7 @@ USB_OTG_STS USB_OTG_EPStartXfer(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep) depctl.b.cnak = 1; depctl.b.epena = 1; USB_OTG_WRITE_REG32(&pdev->regs.INEP_REGS[ep->num]->DIEPCTL, depctl.d32); - + if (ep->type == EP_TYPE_ISOC) { USB_OTG_WritePacket(pdev, ep->xfer_buff, ep->num, ep->xfer_len); @@ -1696,6 +1713,7 @@ USB_OTG_STS USB_OTG_EPStartXfer(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep) { deptsiz.b.pktcnt = (ep->xfer_len + (ep->maxpacket - 1)) / ep->maxpacket; deptsiz.b.xfersize = deptsiz.b.pktcnt * ep->maxpacket; + ep->xfer_len = deptsiz.b.xfersize ; } USB_OTG_WRITE_REG32(&pdev->regs.OUTEP_REGS[ep->num]->DOEPTSIZ, deptsiz.d32); @@ -2039,13 +2057,13 @@ void USB_OTG_StopDevice(USB_OTG_CORE_HANDLE *pdev) uint32_t i; pdev->dev.device_status = 1; - + for (i = 0; i < pdev->cfg.dev_endpoints ; i++) { USB_OTG_WRITE_REG32( &pdev->regs.INEP_REGS[i]->DIEPINT, 0xFF); USB_OTG_WRITE_REG32( &pdev->regs.OUTEP_REGS[i]->DOEPINT, 0xFF); } - + USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DIEPMSK, 0 ); USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DOEPMSK, 0 ); USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DAINTMSK, 0 ); @@ -2075,24 +2093,35 @@ uint32_t USB_OTG_GetEPStatus(USB_OTG_CORE_HANDLE *pdev ,USB_OTG_EP *ep) depctl_addr = &(pdev->regs.INEP_REGS[ep->num]->DIEPCTL); depctl.d32 = USB_OTG_READ_REG32(depctl_addr); - if (depctl.b.stall == 1) + if (depctl.b.stall == 1) + { Status = USB_OTG_EP_TX_STALL; + } else if (depctl.b.naksts == 1) + { Status = USB_OTG_EP_TX_NAK; + } else + { Status = USB_OTG_EP_TX_VALID; - + } } else { depctl_addr = &(pdev->regs.OUTEP_REGS[ep->num]->DOEPCTL); depctl.d32 = USB_OTG_READ_REG32(depctl_addr); - if (depctl.b.stall == 1) + if (depctl.b.stall == 1) + { Status = USB_OTG_EP_RX_STALL; + } else if (depctl.b.naksts == 1) + { Status = USB_OTG_EP_RX_NAK; + } else + { Status = USB_OTG_EP_RX_VALID; + } } /* Return the current status */ @@ -2112,7 +2141,7 @@ void USB_OTG_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep , uint32_t __IO uint32_t *depctl_addr; depctl.d32 = 0; - + /* Process for IN endpoint */ if (ep->is_in == 1) { @@ -2124,7 +2153,9 @@ void USB_OTG_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep , uint32_t USB_OTG_EPSetStall(pdev, ep); return; } else if (Status == USB_OTG_EP_TX_NAK) + { depctl.b.snak = 1; + } else if (Status == USB_OTG_EP_TX_VALID) { if (depctl.b.stall == 1) @@ -2138,7 +2169,14 @@ void USB_OTG_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep , uint32_t depctl.b.epena = 1; } else if (Status == USB_OTG_EP_TX_DIS) + { depctl.b.usbactep = 0; + } + + else + { + /* Do Nothing */ + } } else /* Process for OUT endpoint */ { @@ -2149,7 +2187,9 @@ void USB_OTG_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep , uint32_t depctl.b.stall = 1; } else if (Status == USB_OTG_EP_RX_NAK) + { depctl.b.snak = 1; + } else if (Status == USB_OTG_EP_RX_VALID) { if (depctl.b.stall == 1) @@ -2166,8 +2206,13 @@ void USB_OTG_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep , uint32_t { depctl.b.usbactep = 0; } + + else + { + /* Do Nothing */ + } } - + USB_OTG_WRITE_REG32(depctl_addr, depctl.d32); } @@ -2184,4 +2229,4 @@ void USB_OTG_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep , uint32_t * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_OTG_Driver/src/usb_dcd.c b/lib/main/STM32_USB_OTG_Driver/src/usb_dcd.c index c3336cb845..6940076c30 100644 --- a/lib/main/STM32_USB_OTG_Driver/src/usb_dcd.c +++ b/lib/main/STM32_USB_OTG_Driver/src/usb_dcd.c @@ -2,20 +2,26 @@ ****************************************************************************** * @file usb_dcd.c * @author MCD Application Team - * @version V2.0.0 - * @date 22-July-2011 + * @version V2.2.0 + * @date 09-November-2015 * @brief Peripheral Device Interface Layer ****************************************************************************** - * @attention + * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -101,7 +107,7 @@ void DCD_Init(USB_OTG_CORE_HANDLE *pdev , ep->is_in = 1; ep->num = i; ep->tx_fifo_num = i; - /* Control until ep is actvated */ + /* Control until ep is activated */ ep->type = EP_TYPE_CTRL; ep->maxpacket = USB_OTG_MAX_EP0_SIZE; ep->xfer_buff = 0; @@ -123,18 +129,28 @@ void DCD_Init(USB_OTG_CORE_HANDLE *pdev , } USB_OTG_DisableGlobalInt(pdev); + +#if defined (STM32F446xx) || defined (STM32F469_479xx) + + /* Force Device Mode*/ + USB_OTG_SetCurrentMode(pdev, DEVICE_MODE); /*Init the Core (common init.) */ USB_OTG_CoreInit(pdev); +#else + + /*Init the Core (common init.) */ + USB_OTG_CoreInit(pdev); /* Force Device Mode*/ USB_OTG_SetCurrentMode(pdev, DEVICE_MODE); + +#endif /* Init Device */ USB_OTG_CoreInitDev(pdev); - /* Enable USB Global interrupt */ USB_OTG_EnableGlobalInt(pdev); } @@ -469,4 +485,4 @@ void DCD_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum , uint32_t Statu * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_OTG_Driver/src/usb_dcd_int.c b/lib/main/STM32_USB_OTG_Driver/src/usb_dcd_int.c index e3a02b1312..fe05306b02 100644 --- a/lib/main/STM32_USB_OTG_Driver/src/usb_dcd_int.c +++ b/lib/main/STM32_USB_OTG_Driver/src/usb_dcd_int.c @@ -2,20 +2,26 @@ ****************************************************************************** * @file usb_dcd_int.c * @author MCD Application Team - * @version V2.0.0 - * @date 22-July-2011 + * @version V2.2.0 + * @date 09-November-2015 * @brief Peripheral Device interrupt subroutines ****************************************************************************** - * @attention + * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -124,8 +130,7 @@ uint32_t USBD_OTG_EP1OUT_ISR_Handler (USB_OTG_CORE_HANDLE *pdev) if (pdev->cfg.dma_enable == 1) { deptsiz.d32 = USB_OTG_READ_REG32(&(pdev->regs.OUTEP_REGS[1]->DOEPTSIZ)); - /*ToDo : handle more than one single MPS size packet */ - pdev->dev.out_ep[1].xfer_count = pdev->dev.out_ep[1].maxpacket - \ + pdev->dev.out_ep[1].xfer_count = pdev->dev.out_ep[1].xfer_len- \ deptsiz.b.xfersize; } /* Inform upper layer: data ready */ @@ -140,11 +145,7 @@ uint32_t USBD_OTG_EP1OUT_ISR_Handler (USB_OTG_CORE_HANDLE *pdev) /* Clear the bit in DOEPINTn for this interrupt */ CLEAR_OUT_EP_INTR(1, epdisabled); } - /* AHB Error */ - if ( doepint.b.ahberr ) - { - CLEAR_OUT_EP_INTR(1, ahberr); - } + return 1; } @@ -173,10 +174,6 @@ uint32_t USBD_OTG_EP1IN_ISR_Handler (USB_OTG_CORE_HANDLE *pdev) /* TX COMPLETE */ USBD_DCD_INT_fops->DataInStage(pdev , 1); } - if ( diepint.b.ahberr ) - { - CLEAR_IN_EP_INTR(1, ahberr); - } if ( diepint.b.epdisabled ) { CLEAR_IN_EP_INTR(1, epdisabled); @@ -189,10 +186,6 @@ uint32_t USBD_OTG_EP1IN_ISR_Handler (USB_OTG_CORE_HANDLE *pdev) { CLEAR_IN_EP_INTR(1, intktxfemp); } - if (diepint.b.intknepmis) - { - CLEAR_IN_EP_INTR(1, intknepmis); - } if (diepint.b.inepnakeff) { CLEAR_IN_EP_INTR(1, inepnakeff); @@ -200,7 +193,6 @@ uint32_t USBD_OTG_EP1IN_ISR_Handler (USB_OTG_CORE_HANDLE *pdev) if (diepint.b.emptyintr) { DCD_WriteEmptyTxFifo(pdev , 1); - CLEAR_IN_EP_INTR(1, emptyintr); } return 1; } @@ -390,7 +382,9 @@ static uint32_t DCD_HandleUSBSuspend_ISR(USB_OTG_CORE_HANDLE *pdev) USB_OTG_GINTSTS_TypeDef gintsts; USB_OTG_PCGCCTL_TypeDef power; USB_OTG_DSTS_TypeDef dsts; + __IO uint8_t prev_status = 0; + prev_status = pdev->dev.device_status; USBD_DCD_INT_fops->Suspend (pdev); dsts.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DSTS); @@ -400,7 +394,9 @@ static uint32_t DCD_HandleUSBSuspend_ISR(USB_OTG_CORE_HANDLE *pdev) gintsts.b.usbsuspend = 1; USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32); - if((pdev->cfg.low_power) && (dsts.b.suspsts == 1)) + if((pdev->cfg.low_power) && (dsts.b.suspsts == 1) && + (pdev->dev.connection_status == 1) && + (prev_status == USB_OTG_CONFIGURED)) { /* switch-off the clocks */ power.d32 = 0; @@ -434,7 +430,7 @@ static uint32_t DCD_HandleInEP_ISR(USB_OTG_CORE_HANDLE *pdev) while ( ep_intr ) { - if (ep_intr&0x1) /* In ITR */ + if ((ep_intr & 0x1) == 0x01) /* In ITR */ { diepint.d32 = DCD_ReadDevInEP(pdev , epnum); /* Get In ITR status */ if ( diepint.b.xfercompl ) @@ -454,10 +450,6 @@ static uint32_t DCD_HandleInEP_ISR(USB_OTG_CORE_HANDLE *pdev) } } } - if ( diepint.b.ahberr ) - { - CLEAR_IN_EP_INTR(epnum, ahberr); - } if ( diepint.b.timeout ) { CLEAR_IN_EP_INTR(epnum, timeout); @@ -466,10 +458,6 @@ static uint32_t DCD_HandleInEP_ISR(USB_OTG_CORE_HANDLE *pdev) { CLEAR_IN_EP_INTR(epnum, intktxfemp); } - if (diepint.b.intknepmis) - { - CLEAR_IN_EP_INTR(epnum, intknepmis); - } if (diepint.b.inepnakeff) { CLEAR_IN_EP_INTR(epnum, inepnakeff); @@ -480,10 +468,7 @@ static uint32_t DCD_HandleInEP_ISR(USB_OTG_CORE_HANDLE *pdev) } if (diepint.b.emptyintr) { - DCD_WriteEmptyTxFifo(pdev , epnum); - - CLEAR_IN_EP_INTR(epnum, emptyintr); } } epnum++; @@ -549,11 +534,6 @@ static uint32_t DCD_HandleOutEP_ISR(USB_OTG_CORE_HANDLE *pdev) /* Clear the bit in DOEPINTn for this interrupt */ CLEAR_OUT_EP_INTR(epnum, epdisabled); } - /* AHB Error */ - if ( doepint.b.ahberr ) - { - CLEAR_OUT_EP_INTR(epnum, ahberr); - } /* Setup Phase Done (control EPs) */ if ( doepint.b.setup ) { @@ -657,6 +637,7 @@ static uint32_t DCD_WriteEmptyTxFifo(USB_OTG_CORE_HANDLE *pdev, uint32_t epnum) uint32_t len = 0; uint32_t len32b; txstatus.d32 = 0; + uint32_t fifoemptymsk; ep = &pdev->dev.in_ep[epnum]; @@ -670,8 +651,6 @@ static uint32_t DCD_WriteEmptyTxFifo(USB_OTG_CORE_HANDLE *pdev, uint32_t epnum) len32b = (len + 3) / 4; txstatus.d32 = USB_OTG_READ_REG32( &pdev->regs.INEP_REGS[epnum]->DTXFSTS); - - while (txstatus.b.txfspcavail > len32b && ep->xfer_count < ep->xfer_len && ep->xfer_len != 0) @@ -691,6 +670,14 @@ static uint32_t DCD_WriteEmptyTxFifo(USB_OTG_CORE_HANDLE *pdev, uint32_t epnum) ep->xfer_count += len; txstatus.d32 = USB_OTG_READ_REG32(&pdev->regs.INEP_REGS[epnum]->DTXFSTS); + + /* Mask the TxFIFOEmpty interrupt */ + if (ep->xfer_len == ep->xfer_count) + { + fifoemptymsk = 0x1 << ep->num; + USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DIEPEMPMSK, + fifoemptymsk, 0); + } } return 1; @@ -739,7 +726,6 @@ static uint32_t DCD_HandleUsbReset_ISR(USB_OTG_CORE_HANDLE *pdev) doepmsk.b.setup = 1; doepmsk.b.xfercompl = 1; - doepmsk.b.ahberr = 1; doepmsk.b.epdisabled = 1; USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DOEPMSK, doepmsk.d32 ); #ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED @@ -748,8 +734,7 @@ static uint32_t DCD_HandleUsbReset_ISR(USB_OTG_CORE_HANDLE *pdev) diepmsk.b.xfercompl = 1; diepmsk.b.timeout = 1; diepmsk.b.epdisabled = 1; - diepmsk.b.ahberr = 1; - diepmsk.b.intknepmis = 1; + USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DIEPMSK, diepmsk.d32 ); #ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DINEP1MSK, diepmsk.d32 ); @@ -781,28 +766,102 @@ static uint32_t DCD_HandleUsbReset_ISR(USB_OTG_CORE_HANDLE *pdev) */ static uint32_t DCD_HandleEnumDone_ISR(USB_OTG_CORE_HANDLE *pdev) { + uint32_t hclk = 168000000; + USB_OTG_GINTSTS_TypeDef gintsts; USB_OTG_GUSBCFG_TypeDef gusbcfg; - + RCC_ClocksTypeDef RCC_Clocks; USB_OTG_EP0Activate(pdev); - /* Set USB turn-around time based on device speed and PHY interface. */ + /* Get HCLK frequency */ + RCC_GetClocksFreq(&RCC_Clocks); + hclk = RCC_Clocks.HCLK_Frequency; + + /* Clear default TRDT value and Set USB turn-around time based on device speed and PHY interface. */ gusbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GUSBCFG); + gusbcfg.b.usbtrdtim = 0; + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GUSBCFG, gusbcfg.d32); /* Full or High speed */ if ( USB_OTG_GetDeviceSpeed(pdev) == USB_SPEED_HIGH) { pdev->cfg.speed = USB_OTG_SPEED_HIGH; pdev->cfg.mps = USB_OTG_HS_MAX_PACKET_SIZE ; + + /*USBTRD min For HS device*/ gusbcfg.b.usbtrdtim = 9; } else { pdev->cfg.speed = USB_OTG_SPEED_FULL; - pdev->cfg.mps = USB_OTG_FS_MAX_PACKET_SIZE ; - gusbcfg.b.usbtrdtim = 5; + pdev->cfg.mps = USB_OTG_FS_MAX_PACKET_SIZE ; + + /* The USBTRD is configured according to the tables below, depending on AHB frequency + used by application. In the low AHB frequency range it is used to stretch enough the USB response + time to IN tokens, the USB turnaround time, so to compensate for the longer AHB read access + latency to the Data FIFO */ + + if((hclk >= 15000000)&&(hclk < 16000000)) + { + /* hclk Clock Range between 15-16 MHz */ + gusbcfg.b.usbtrdtim = 0xE; + } + + else if((hclk >= 16000000)&&(hclk < 17100000)) + { + /* hclk Clock Range between 16-17.1 MHz */ + gusbcfg.b.usbtrdtim = 0xD; + } + + else if((hclk >= 17100000)&&(hclk < 18400000)) + { + /* hclk Clock Range between 17-18.4 MHz */ + gusbcfg.b.usbtrdtim = 0xC; + } + + else if((hclk >= 18400000)&&(hclk < 20000000)) + { + /* hclk Clock Range between 18.4-20 MHz */ + gusbcfg.b.usbtrdtim = 0xB; + } + + else if((hclk >= 20000000)&&(hclk < 21800000)) + { + /* hclk Clock Range between 20-21.8 MHz */ + gusbcfg.b.usbtrdtim = 0xA; + } + + else if((hclk >= 21800000)&&(hclk < 24000000)) + { + /* hclk Clock Range between 21.8-24 MHz */ + gusbcfg.b.usbtrdtim = 0x9; + } + + else if((hclk >= 24000000)&&(hclk < 26600000)) + { + /* hclk Clock Range between 24-26.6 MHz */ + gusbcfg.b.usbtrdtim = 0x8; + } + + else if((hclk >= 26600000)&&(hclk < 30000000)) + { + /* hclk Clock Range between 26.6-30 MHz */ + gusbcfg.b.usbtrdtim = 0x7; + } + + else if((hclk >= 30000000)&&(hclk < 34300000)) + { + /* hclk Clock Range between 30-34.3 MHz */ + gusbcfg.b.usbtrdtim= 0x6; + } + + else /* if(hclk >= 34300000) */ + { + /* hclk Clock Range between 34.3-168 MHz */ + gusbcfg.b.usbtrdtim = 0x5; + } } - + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GUSBCFG, gusbcfg.d32); /* Clear interrupt */ @@ -869,8 +928,6 @@ static uint32_t DCD_ReadDevInEP (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum) return v; } - - /** * @} */ @@ -883,4 +940,4 @@ static uint32_t DCD_ReadDevInEP (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum) * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_OTG_Driver/src/usb_hcd.c b/lib/main/STM32_USB_OTG_Driver/src/usb_hcd.c index 689d061aeb..d24027c1e6 100644 --- a/lib/main/STM32_USB_OTG_Driver/src/usb_hcd.c +++ b/lib/main/STM32_USB_OTG_Driver/src/usb_hcd.c @@ -2,20 +2,26 @@ ****************************************************************************** * @file usb_hcd.c * @author MCD Application Team - * @version V2.0.0 - * @date 22-July-2011 + * @version V2.2.0 + * @date 09-November-2015 * @brief Host Interface Layer ****************************************************************************** * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -142,8 +148,8 @@ uint32_t HCD_ResetPort(USB_OTG_CORE_HANDLE *pdev) { /* Before starting to drive a USB reset, the application waits for the OTG - interrupt triggered by the debounce done bit (DBCDNE bit in OTG_FS_GOTGINT), - which indicates that the bus is stable again after the electrical debounce + interrupt triggered by the denounce done bit (DBCDNE bit in OTG_FS_GOTGINT), + which indicates that the bus is stable again after the electrical denounce caused by the attachment of a pull-up resistor on DP (FS) or DM (LS). */ @@ -163,6 +169,19 @@ uint32_t HCD_IsDeviceConnected(USB_OTG_CORE_HANDLE *pdev) return (pdev->host.ConnSts); } + +/** + * @brief HCD_IsPortEnabled + * This function checks if port is enabled + * @param pdev : Selected device + * @retval Frame number + * + */ +uint32_t HCD_IsPortEnabled(USB_OTG_CORE_HANDLE *pdev) +{ + return (pdev->host.PortEnabled); +} + /** * @brief HCD_GetCurrentFrame * This function returns the frame number for sof packet @@ -253,4 +272,4 @@ uint32_t HCD_SubmitRequest (USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num) * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_OTG_Driver/src/usb_hcd_int.c b/lib/main/STM32_USB_OTG_Driver/src/usb_hcd_int.c index bd4081fb3d..7366d155f0 100644 --- a/lib/main/STM32_USB_OTG_Driver/src/usb_hcd_int.c +++ b/lib/main/STM32_USB_OTG_Driver/src/usb_hcd_int.c @@ -2,20 +2,26 @@ ****************************************************************************** * @file usb_hcd_int.c * @author MCD Application Team - * @version V2.0.0 - * @date 22-July-2011 + * @version V2.2.0 + * @date 09-November-2015 * @brief Host driver interrupt subroutines ****************************************************************************** * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -25,62 +31,60 @@ #include "usb_hcd_int.h" #if defined (__CC_ARM) /*!< ARM Compiler */ - #pragma O0 -#elif defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma O0 +#pragma O0 #elif defined (__GNUC__) /*!< GNU Compiler */ - #pragma GCC optimize ("O0") +#pragma GCC optimize ("O0") #elif defined (__TASKING__) /*!< TASKING Compiler */ - #pragma optimize=0 +#pragma optimize=0 #endif /* __CC_ARM */ /** @addtogroup USB_OTG_DRIVER - * @{ - */ - +* @{ +*/ + /** @defgroup USB_HCD_INT - * @brief This file contains the interrupt subroutines for the Host mode. - * @{ - */ +* @brief This file contains the interrupt subroutines for the Host mode. +* @{ +*/ /** @defgroup USB_HCD_INT_Private_Defines - * @{ - */ +* @{ +*/ /** - * @} - */ - +* @} +*/ + /** @defgroup USB_HCD_INT_Private_TypesDefinitions - * @{ - */ +* @{ +*/ /** - * @} - */ +* @} +*/ /** @defgroup USB_HCD_INT_Private_Macros - * @{ - */ +* @{ +*/ /** - * @} - */ +* @} +*/ /** @defgroup USB_HCD_INT_Private_Variables - * @{ - */ +* @{ +*/ /** - * @} - */ +* @} +*/ /** @defgroup USB_HCD_INT_Private_FunctionPrototypes - * @{ - */ +* @{ +*/ static uint32_t USB_OTG_USBH_handle_sof_ISR(USB_OTG_CORE_HANDLE *pdev); static uint32_t USB_OTG_USBH_handle_port_ISR(USB_OTG_CORE_HANDLE *pdev); @@ -96,20 +100,20 @@ static uint32_t USB_OTG_USBH_handle_Disconnect_ISR (USB_OTG_CORE_HANDLE *pdev); static uint32_t USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR (USB_OTG_CORE_HANDLE *pdev); /** - * @} - */ +* @} +*/ /** @defgroup USB_HCD_INT_Private_Functions - * @{ - */ +* @{ +*/ /** - * @brief HOST_Handle_ISR - * This function handles all USB Host Interrupts - * @param pdev: Selected device - * @retval status - */ +* @brief HOST_Handle_ISR +* This function handles all USB Host Interrupts +* @param pdev: Selected device +* @retval status +*/ uint32_t USBH_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev) { @@ -163,22 +167,22 @@ uint32_t USBH_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev) } - if (gintsts.b.incomplisoout) - { - retval |= USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR (pdev); - } - + if (gintsts.b.incomplisoout) + { + retval |= USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR (pdev); + } + } return retval; } /** - * @brief USB_OTG_USBH_handle_hc_ISR - * This function indicates that one or more host channels has a pending - * @param pdev: Selected device - * @retval status - */ +* @brief USB_OTG_USBH_handle_hc_ISR +* This function indicates that one or more host channels has a pending +* @param pdev: Selected device +* @retval status +*/ static uint32_t USB_OTG_USBH_handle_hc_ISR (USB_OTG_CORE_HANDLE *pdev) { USB_OTG_HAINT_TypeDef haint; @@ -212,17 +216,18 @@ static uint32_t USB_OTG_USBH_handle_hc_ISR (USB_OTG_CORE_HANDLE *pdev) } /** - * @brief USB_OTG_otg_hcd_handle_sof_intr - * Handles the start-of-frame interrupt in host mode. - * @param pdev: Selected device - * @retval status - */ +* @brief USB_OTG_otg_hcd_handle_sof_intr +* Handles the start-of-frame interrupt in host mode. +* @param pdev: Selected device +* @retval status +*/ static uint32_t USB_OTG_USBH_handle_sof_ISR (USB_OTG_CORE_HANDLE *pdev) { USB_OTG_GINTSTS_TypeDef gintsts; - - gintsts.d32 = 0; + + USBH_HCD_INT_fops->SOF(pdev); + /* Clear interrupt */ gintsts.b.sofintr = 1; USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32); @@ -231,19 +236,18 @@ static uint32_t USB_OTG_USBH_handle_sof_ISR (USB_OTG_CORE_HANDLE *pdev) } /** - * @brief USB_OTG_USBH_handle_Disconnect_ISR - * Handles disconnect event. - * @param pdev: Selected device - * @retval status - */ +* @brief USB_OTG_USBH_handle_Disconnect_ISR +* Handles disconnect event. +* @param pdev: Selected device +* @retval status +*/ static uint32_t USB_OTG_USBH_handle_Disconnect_ISR (USB_OTG_CORE_HANDLE *pdev) { USB_OTG_GINTSTS_TypeDef gintsts; - pdev->host.ConnSts = 0; gintsts.d32 = 0; - pdev->host.port_cb->Disconnect(pdev); + USBH_HCD_INT_fops->DevDisconnected(pdev); /* Clear interrupt */ gintsts.b.disconnect = 1; @@ -251,13 +255,15 @@ static uint32_t USB_OTG_USBH_handle_Disconnect_ISR (USB_OTG_CORE_HANDLE *pdev) return 1; } - +#if defined ( __ICCARM__ ) /*!< IAR Compiler */ +#pragma optimize = none +#endif /* __CC_ARM */ /** - * @brief USB_OTG_USBH_handle_nptxfempty_ISR - * Handles non periodic tx fifo empty. - * @param pdev: Selected device - * @retval status - */ +* @brief USB_OTG_USBH_handle_nptxfempty_ISR +* Handles non periodic tx fifo empty. +* @param pdev: Selected device +* @retval status +*/ static uint32_t USB_OTG_USBH_handle_nptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev) { USB_OTG_GINTMSK_TypeDef intmsk; @@ -266,44 +272,46 @@ static uint32_t USB_OTG_USBH_handle_nptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev) hnptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->HNPTXSTS); - len_words = (pdev->host.hc[hnptxsts.b.chnum].xfer_len + 3) / 4; + len_words = (pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_len + 3) / 4; while ((hnptxsts.b.nptxfspcavail > len_words)&& - (pdev->host.hc[hnptxsts.b.chnum].xfer_len != 0)) + (pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_len != 0)) { len = hnptxsts.b.nptxfspcavail * 4; - if (len > pdev->host.hc[hnptxsts.b.chnum].xfer_len) + if (len > pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_len) { /* Last packet */ - len = pdev->host.hc[hnptxsts.b.chnum].xfer_len; + len = pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_len; intmsk.d32 = 0; intmsk.b.nptxfempty = 1; USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, intmsk.d32, 0); } - len_words = (pdev->host.hc[hnptxsts.b.chnum].xfer_len + 3) / 4; + len_words = (pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_len + 3) / 4; - USB_OTG_WritePacket (pdev , pdev->host.hc[hnptxsts.b.chnum].xfer_buff, hnptxsts.b.chnum, len); + USB_OTG_WritePacket (pdev , pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_buff, hnptxsts.b.nptxqtop.chnum, len); + + pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_buff += len; + pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_len -= len; + pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_count += len; - pdev->host.hc[hnptxsts.b.chnum].xfer_buff += len; - pdev->host.hc[hnptxsts.b.chnum].xfer_len -= len; - pdev->host.hc[hnptxsts.b.chnum].xfer_count += len; - hnptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->HNPTXSTS); } - + return 1; } - +#if defined ( __ICCARM__ ) /*!< IAR Compiler */ +#pragma optimize = none +#endif /* __CC_ARM */ /** - * @brief USB_OTG_USBH_handle_ptxfempty_ISR - * Handles periodic tx fifo empty - * @param pdev: Selected device - * @retval status - */ +* @brief USB_OTG_USBH_handle_ptxfempty_ISR +* Handles periodic tx fifo empty +* @param pdev: Selected device +* @retval status +*/ static uint32_t USB_OTG_USBH_handle_ptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev) { USB_OTG_GINTMSK_TypeDef intmsk; @@ -312,31 +320,31 @@ static uint32_t USB_OTG_USBH_handle_ptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev) hptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HPTXSTS); - len_words = (pdev->host.hc[hptxsts.b.chnum].xfer_len + 3) / 4; + len_words = (pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_len + 3) / 4; while ((hptxsts.b.ptxfspcavail > len_words)&& - (pdev->host.hc[hptxsts.b.chnum].xfer_len != 0)) + (pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_len != 0)) { len = hptxsts.b.ptxfspcavail * 4; - if (len > pdev->host.hc[hptxsts.b.chnum].xfer_len) + if (len > pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_len) { - len = pdev->host.hc[hptxsts.b.chnum].xfer_len; + len = pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_len; /* Last packet */ intmsk.d32 = 0; intmsk.b.ptxfempty = 1; USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, intmsk.d32, 0); } - len_words = (pdev->host.hc[hptxsts.b.chnum].xfer_len + 3) / 4; + len_words = (pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_len + 3) / 4; - USB_OTG_WritePacket (pdev , pdev->host.hc[hptxsts.b.chnum].xfer_buff, hptxsts.b.chnum, len); + USB_OTG_WritePacket (pdev , pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_buff, hptxsts.b.ptxqtop.chnum, len); + + pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_buff += len; + pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_len -= len; + pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_count += len; - pdev->host.hc[hptxsts.b.chnum].xfer_buff += len; - pdev->host.hc[hptxsts.b.chnum].xfer_len -= len; - pdev->host.hc[hptxsts.b.chnum].xfer_count += len; - hptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HPTXSTS); } @@ -344,19 +352,23 @@ static uint32_t USB_OTG_USBH_handle_ptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev) } /** - * @brief USB_OTG_USBH_handle_port_ISR - * This function determines which interrupt conditions have occurred - * @param pdev: Selected device - * @retval status - */ +* @brief USB_OTG_USBH_handle_port_ISR +* This function determines which interrupt conditions have occurred +* @param pdev: Selected device +* @retval status +*/ +#if defined ( __ICCARM__ ) /*!< IAR Compiler */ +#pragma optimize = none +#endif /* __CC_ARM */ static uint32_t USB_OTG_USBH_handle_port_ISR (USB_OTG_CORE_HANDLE *pdev) { USB_OTG_HPRT0_TypeDef hprt0; USB_OTG_HPRT0_TypeDef hprt0_dup; USB_OTG_HCFG_TypeDef hcfg; - uint32_t do_reset = 0; uint32_t retval = 0; + USB_OTG_GINTMSK_TypeDef intmsk; + intmsk.d32 = 0; hcfg.d32 = 0; hprt0.d32 = 0; hprt0_dup.d32 = 0; @@ -374,24 +386,21 @@ static uint32_t USB_OTG_USBH_handle_port_ISR (USB_OTG_CORE_HANDLE *pdev) /* Port Connect Detected */ if (hprt0.b.prtconndet) { - pdev->host.port_cb->Connect(pdev); hprt0_dup.b.prtconndet = 1; - do_reset = 1; - retval |= 1; + USBH_HCD_INT_fops->DevConnected(pdev); + retval |= 1; } /* Port Enable Changed */ if (hprt0.b.prtenchng) { hprt0_dup.b.prtenchng = 1; + if (hprt0.b.prtena == 1) { - pdev->host.ConnSts = 1; - if ((hprt0.b.prtspd == HPRT0_PRTSPD_LOW_SPEED) || (hprt0.b.prtspd == HPRT0_PRTSPD_FULL_SPEED)) - { - + { hcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HCFG); if (hprt0.b.prtspd == HPRT0_PRTSPD_LOW_SPEED) @@ -399,65 +408,70 @@ static uint32_t USB_OTG_USBH_handle_port_ISR (USB_OTG_CORE_HANDLE *pdev) USB_OTG_WRITE_REG32(&pdev->regs.HREGS->HFIR, 6000 ); if (hcfg.b.fslspclksel != HCFG_6_MHZ) { - if(pdev->cfg.coreID == USB_OTG_FS_CORE_ID) - { - USB_OTG_InitFSLSPClkSel(pdev ,HCFG_6_MHZ ); - } - do_reset = 1; - } - } - else - { - - USB_OTG_WRITE_REG32(&pdev->regs.HREGS->HFIR, 48000 ); - if (hcfg.b.fslspclksel != HCFG_48_MHZ) - { - USB_OTG_InitFSLSPClkSel(pdev ,HCFG_48_MHZ ); - do_reset = 1; + if(pdev->cfg.phy_itface == USB_OTG_EMBEDDED_PHY) + { + USB_OTG_InitFSLSPClkSel(pdev , HCFG_6_MHZ); + } + + else + { + USB_OTG_WRITE_REG32(&pdev->regs.HREGS->HFIR, 48000 ); + if (hcfg.b.fslspclksel != HCFG_48_MHZ) + { + USB_OTG_InitFSLSPClkSel(pdev ,HCFG_48_MHZ ); + } + } } } } - else - { - do_reset = 1; - } + + USBH_HCD_INT_fops->DevPortEnabled(pdev); + + /*unmask disconnect interrupt */ + intmsk.d32 = 0; + intmsk.b.disconnect = 1; + USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GINTMSK, intmsk.d32, intmsk.d32); + } + else + { + USBH_HCD_INT_fops->DevPortDisabled(pdev); + } } + /* Overcurrent Change Interrupt */ if (hprt0.b.prtovrcurrchng) { hprt0_dup.b.prtovrcurrchng = 1; retval |= 1; } - if (do_reset) - { - USB_OTG_ResetPort(pdev); - - } + /* Clear Port Interrupts */ USB_OTG_WRITE_REG32(pdev->regs.HPRT0, hprt0_dup.d32); return retval; } - +#if defined ( __ICCARM__ ) /*!< IAR Compiler */ +#pragma optimize = none +#endif /* __CC_ARM */ /** - * @brief USB_OTG_USBH_handle_hc_n_Out_ISR - * Handles interrupt for a specific Host Channel - * @param pdev: Selected device - * @param hc_num: Channel number - * @retval status - */ +* @brief USB_OTG_USBH_handle_hc_n_Out_ISR +* Handles interrupt for a specific Host Channel +* @param pdev: Selected device +* @param hc_num: Channel number +* @retval status +*/ uint32_t USB_OTG_USBH_handle_hc_n_Out_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t num) { USB_OTG_HCINTn_TypeDef hcint; - USB_OTG_HCGINTMSK_TypeDef hcintmsk; + USB_OTG_HCINTMSK_TypeDef hcintmsk; USB_OTG_HC_REGS *hcreg; USB_OTG_HCCHAR_TypeDef hcchar; hcreg = pdev->regs.HC_REGS[num]; hcint.d32 = USB_OTG_READ_REG32(&hcreg->HCINT); - hcintmsk.d32 = USB_OTG_READ_REG32(&hcreg->HCGINTMSK); + hcintmsk.d32 = USB_OTG_READ_REG32(&hcreg->HCINTMSK); hcint.d32 = hcint.d32 & hcintmsk.d32; hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[num]->HCCHAR); @@ -471,7 +485,12 @@ uint32_t USB_OTG_USBH_handle_hc_n_Out_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t { CLEAR_HC_INT(hcreg , ack); } - + else if (hcint.b.frmovrun) + { + UNMASK_HOST_INT_CHH (num); + USB_OTG_HC_Halt(pdev, num); + CLEAR_HC_INT(hcreg ,frmovrun); + } else if (hcint.b.xfercompl) { pdev->host.ErrCnt[num] = 0; @@ -493,7 +512,10 @@ uint32_t USB_OTG_USBH_handle_hc_n_Out_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t { pdev->host.ErrCnt[num] = 0; UNMASK_HOST_INT_CHH (num); - USB_OTG_HC_Halt(pdev, num); + if (pdev->cfg.dma_enable == 0) + { + USB_OTG_HC_Halt(pdev, num); + } CLEAR_HC_INT(hcreg , nak); pdev->host.HC_Status[num] = HC_NAK; } @@ -502,7 +524,6 @@ uint32_t USB_OTG_USBH_handle_hc_n_Out_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t { UNMASK_HOST_INT_CHH (num); USB_OTG_HC_Halt(pdev, num); - pdev->host.ErrCnt[num] ++; pdev->host.HC_Status[num] = HC_XACTERR; CLEAR_HC_INT(hcreg , xacterr); } @@ -510,13 +531,15 @@ uint32_t USB_OTG_USBH_handle_hc_n_Out_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t { pdev->host.ErrCnt[num] = 0; UNMASK_HOST_INT_CHH (num); - USB_OTG_HC_Halt(pdev, num); + if (pdev->cfg.dma_enable == 0) + { + USB_OTG_HC_Halt(pdev, num); + } CLEAR_HC_INT(hcreg , nyet); pdev->host.HC_Status[num] = HC_NYET; } else if (hcint.b.datatglerr) { - UNMASK_HOST_INT_CHH (num); USB_OTG_HC_Halt(pdev, num); CLEAR_HC_INT(hcreg , nak); @@ -555,43 +578,41 @@ uint32_t USB_OTG_USBH_handle_hc_n_Out_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t } else if(pdev->host.HC_Status[num] == HC_XACTERR) { - if (pdev->host.ErrCnt[num] == 3) { pdev->host.URB_State[num] = URB_ERROR; - pdev->host.ErrCnt[num] = 0; } } CLEAR_HC_INT(hcreg , chhltd); } - + return 1; } - +#if defined ( __ICCARM__ ) /*!< IAR Compiler */ +#pragma optimize = none +#endif /* __CC_ARM */ /** - * @brief USB_OTG_USBH_handle_hc_n_In_ISR - * Handles interrupt for a specific Host Channel - * @param pdev: Selected device - * @param hc_num: Channel number - * @retval status - */ +* @brief USB_OTG_USBH_handle_hc_n_In_ISR +* Handles interrupt for a specific Host Channel +* @param pdev: Selected device +* @param hc_num: Channel number +* @retval status +*/ uint32_t USB_OTG_USBH_handle_hc_n_In_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t num) { USB_OTG_HCINTn_TypeDef hcint; - USB_OTG_HCGINTMSK_TypeDef hcintmsk; + USB_OTG_HCINTMSK_TypeDef hcintmsk; USB_OTG_HCCHAR_TypeDef hcchar; USB_OTG_HCTSIZn_TypeDef hctsiz; USB_OTG_HC_REGS *hcreg; - hcreg = pdev->regs.HC_REGS[num]; hcint.d32 = USB_OTG_READ_REG32(&hcreg->HCINT); - hcintmsk.d32 = USB_OTG_READ_REG32(&hcreg->HCGINTMSK); + hcintmsk.d32 = USB_OTG_READ_REG32(&hcreg->HCINTMSK); hcint.d32 = hcint.d32 & hcintmsk.d32; hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[num]->HCCHAR); hcintmsk.d32 = 0; - if (hcint.b.ahberr) { CLEAR_HC_INT(hcreg ,ahberr); @@ -610,16 +631,15 @@ uint32_t USB_OTG_USBH_handle_hc_n_In_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t n CLEAR_HC_INT(hcreg , stall); /* Clear the STALL Condition */ hcint.b.nak = 0; /* NOTE: When there is a 'stall', reset also nak, else, the pdev->host.HC_Status = HC_STALL - will be overwritten by 'nak' in code below */ + will be overwritten by 'nak' in code below */ USB_OTG_HC_Halt(pdev, num); } else if (hcint.b.datatglerr) { - - UNMASK_HOST_INT_CHH (num); - USB_OTG_HC_Halt(pdev, num); - CLEAR_HC_INT(hcreg , nak); - pdev->host.HC_Status[num] = HC_DATATGLERR; + UNMASK_HOST_INT_CHH (num); + USB_OTG_HC_Halt(pdev, num); + CLEAR_HC_INT(hcreg , nak); + pdev->host.HC_Status[num] = HC_DATATGLERR; CLEAR_HC_INT(hcreg , datatglerr); } @@ -632,13 +652,12 @@ uint32_t USB_OTG_USBH_handle_hc_n_In_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t n else if (hcint.b.xfercompl) { - if (pdev->cfg.dma_enable == 1) { hctsiz.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[num]->HCTSIZ); pdev->host.XferCnt[num] = pdev->host.hc[num].xfer_len - hctsiz.b.xfersize; } - + pdev->host.HC_Status[num] = HC_XFRC; pdev->host.ErrCnt [num]= 0; CLEAR_HC_INT(hcreg , xfercompl); @@ -650,15 +669,14 @@ uint32_t USB_OTG_USBH_handle_hc_n_In_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t n USB_OTG_HC_Halt(pdev, num); CLEAR_HC_INT(hcreg , nak); pdev->host.hc[num].toggle_in ^= 1; - + } else if(hcchar.b.eptype == EP_TYPE_INTR) { hcchar.b.oddfrm = 1; USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[num]->HCCHAR, hcchar.d32); pdev->host.URB_State[num] = URB_DONE; - } - + } } else if (hcint.b.chhltd) { @@ -671,15 +689,15 @@ uint32_t USB_OTG_USBH_handle_hc_n_In_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t n else if (pdev->host.HC_Status[num] == HC_STALL) { - pdev->host.URB_State[num] = URB_STALL; + pdev->host.URB_State[num] = URB_STALL; } else if((pdev->host.HC_Status[num] == HC_XACTERR) || (pdev->host.HC_Status[num] == HC_DATATGLERR)) { - pdev->host.ErrCnt[num] = 0; - pdev->host.URB_State[num] = URB_ERROR; - + pdev->host.ErrCnt[num] = 0; + pdev->host.URB_State[num] = URB_ERROR; + } else if(hcchar.b.eptype == EP_TYPE_INTR) { @@ -692,43 +710,48 @@ uint32_t USB_OTG_USBH_handle_hc_n_In_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t n else if (hcint.b.xacterr) { UNMASK_HOST_INT_CHH (num); - pdev->host.ErrCnt[num] ++; pdev->host.HC_Status[num] = HC_XACTERR; USB_OTG_HC_Halt(pdev, num); CLEAR_HC_INT(hcreg , xacterr); - } else if (hcint.b.nak) { if(hcchar.b.eptype == EP_TYPE_INTR) { UNMASK_HOST_INT_CHH (num); - USB_OTG_HC_Halt(pdev, num); - CLEAR_HC_INT(hcreg , nak); + if (pdev->cfg.dma_enable == 0) + { + USB_OTG_HC_Halt(pdev, num); + } } - else if ((hcchar.b.eptype == EP_TYPE_CTRL)|| - (hcchar.b.eptype == EP_TYPE_BULK)) + + pdev->host.HC_Status[num] = HC_NAK; + CLEAR_HC_INT(hcreg , nak); + + if ((hcchar.b.eptype == EP_TYPE_CTRL)|| + (hcchar.b.eptype == EP_TYPE_BULK)) { /* re-activate the channel */ hcchar.b.chen = 1; hcchar.b.chdis = 0; USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[num]->HCCHAR, hcchar.d32); } - pdev->host.HC_Status[num] = HC_NAK; } - + return 1; } /** - * @brief USB_OTG_USBH_handle_rx_qlvl_ISR - * Handles the Rx Status Queue Level Interrupt - * @param pdev: Selected device - * @retval status - */ - +* @brief USB_OTG_USBH_handle_rx_qlvl_ISR +* Handles the Rx Status Queue Level Interrupt +* @param pdev: Selected device +* @retval status +*/ +#if defined ( __ICCARM__ ) /*!< IAR Compiler */ +#pragma optimize = none +#endif /* __CC_ARM */ static uint32_t USB_OTG_USBH_handle_rx_qlvl_ISR (USB_OTG_CORE_HANDLE *pdev) { USB_OTG_GRXFSTS_TypeDef grxsts; @@ -759,7 +782,7 @@ static uint32_t USB_OTG_USBH_handle_rx_qlvl_ISR (USB_OTG_CORE_HANDLE *pdev) pdev->host.hc[grxsts.b.chnum].xfer_buff += grxsts.b.bcnt; pdev->host.hc[grxsts.b.chnum].xfer_count += grxsts.b.bcnt; - + count = pdev->host.hc[channelnum].xfer_count; pdev->host.XferCnt[channelnum] = count; @@ -774,9 +797,9 @@ static uint32_t USB_OTG_USBH_handle_rx_qlvl_ISR (USB_OTG_CORE_HANDLE *pdev) } break; - case GRXSTS_PKTSTS_IN_XFER_COMP: - - case GRXSTS_PKTSTS_DATA_TOGGLE_ERR: + case GRXSTS_PKTSTS_IN_XFER_COMP: + + case GRXSTS_PKTSTS_DATA_TOGGLE_ERR: case GRXSTS_PKTSTS_CH_HALTED: default: break; @@ -789,31 +812,34 @@ static uint32_t USB_OTG_USBH_handle_rx_qlvl_ISR (USB_OTG_CORE_HANDLE *pdev) } /** - * @brief USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR - * Handles the incomplete Periodic transfer Interrupt - * @param pdev: Selected device - * @retval status - */ +* @brief USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR +* Handles the incomplete Periodic transfer Interrupt +* @param pdev: Selected device +* @retval status +*/ +#if defined ( __ICCARM__ ) /*!< IAR Compiler */ +#pragma optimize = none +#endif /* __CC_ARM */ static uint32_t USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR (USB_OTG_CORE_HANDLE *pdev) { - USB_OTG_GINTSTS_TypeDef gintsts; - USB_OTG_HCCHAR_TypeDef hcchar; - - - - - hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[0]->HCCHAR); - hcchar.b.chen = 1; - hcchar.b.chdis = 1; - USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[0]->HCCHAR, hcchar.d32); - - gintsts.d32 = 0; - /* Clear interrupt */ - gintsts.b.incomplisoout = 1; - USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32); - - return 1; + USB_OTG_GINTSTS_TypeDef gintsts; + USB_OTG_HCCHAR_TypeDef hcchar; + + + + + hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[0]->HCCHAR); + hcchar.b.chen = 1; + hcchar.b.chdis = 1; + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[0]->HCCHAR, hcchar.d32); + + gintsts.d32 = 0; + /* Clear interrupt */ + gintsts.b.incomplisoout = 1; + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32); + + return 1; } /** @@ -828,5 +854,5 @@ static uint32_t USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR (USB_OTG_CORE_HAN * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/lib/main/STM32_USB_OTG_Driver/src/usb_otg.c b/lib/main/STM32_USB_OTG_Driver/src/usb_otg.c index fbb71ecb46..a3b9eabfda 100644 --- a/lib/main/STM32_USB_OTG_Driver/src/usb_otg.c +++ b/lib/main/STM32_USB_OTG_Driver/src/usb_otg.c @@ -2,20 +2,26 @@ ****************************************************************************** * @file usb_otg.c * @author MCD Application Team - * @version V2.0.0 - * @date 22-July-2011 + * @version V2.2.0 + * @date 09-November-2015 * @brief OTG Core Layer ****************************************************************************** * @attention * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * - *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** */ @@ -72,6 +78,10 @@ * @{ */ +uint32_t USB_OTG_HandleOTG_ISR(USB_OTG_CORE_HANDLE *pdev); + +static uint32_t USB_OTG_HandleConnectorIDStatusChange_ISR(USB_OTG_CORE_HANDLE *pdev); +static uint32_t USB_OTG_HandleSessionRequest_ISR(USB_OTG_CORE_HANDLE *pdev); static uint32_t USB_OTG_Read_itr(USB_OTG_CORE_HANDLE *pdev); /** @@ -106,15 +116,15 @@ uint32_t STM32_USBO_OTG_ISR_Handler(USB_OTG_CORE_HANDLE *pdev) } if (gintsts.b.otgintr) { - retval |= 1;//USB_OTG_HandleOTG_ISR(pdev); + retval |= USB_OTG_HandleOTG_ISR(pdev); } if (gintsts.b.conidstschng) { - retval |= 2;//USB_OTG_HandleConnectorIDStatusChange_ISR(pdev); + retval |= USB_OTG_HandleConnectorIDStatusChange_ISR(pdev); } if (gintsts.b.sessreqintr) { - retval |= 3;//USB_OTG_HandleSessionRequest_ISR(pdev); + retval |= USB_OTG_HandleSessionRequest_ISR(pdev); } return retval; } @@ -148,6 +158,239 @@ static uint32_t USB_OTG_Read_itr(USB_OTG_CORE_HANDLE *pdev) } +/** + * @brief USB_OTG_HandleOTG_ISR + * handles the OTG Interrupts + * @param None + * @retval : status + */ +static uint32_t USB_OTG_HandleOTG_ISR(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_GOTGINT_TypeDef gotgint; + USB_OTG_GOTGCTL_TypeDef gotgctl; + + + gotgint.d32 = 0; + gotgctl.d32 = 0; + + gotgint.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGINT); + gotgctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGCTL); + + if (gotgint.b.sesenddet) + { + gotgctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGCTL); + + + if (USB_OTG_IsDeviceMode(pdev)) + { + + } + else if (USB_OTG_IsHostMode(pdev)) + { + + } + } + + /* ----> SRP SUCCESS or FAILURE INTERRUPT <---- */ + if (gotgint.b.sesreqsucstschng) + { + gotgctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGCTL); + if (gotgctl.b.sesreqscs) /* Session request success */ + { + if (USB_OTG_IsDeviceMode(pdev)) + { + + } + /* Clear Session Request */ + gotgctl.d32 = 0; + gotgctl.b.sesreq = 1; + USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GOTGCTL, gotgctl.d32, 0); + } + else /* Session request failure */ + { + if (USB_OTG_IsDeviceMode(pdev)) + { + + } + } + } + /* ----> HNP SUCCESS or FAILURE INTERRUPT <---- */ + if (gotgint.b.hstnegsucstschng) + { + gotgctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGCTL); + + if (gotgctl.b.hstnegscs) /* Host negotiation success */ + { + if (USB_OTG_IsHostMode(pdev)) /* The core AUTOMATICALLY sets the Host mode */ + { + + } + } + else /* Host negotiation failure */ + { + + } + gotgint.b.hstnegsucstschng = 1; /* Ack "Host Negotiation Success Status Change" interrupt. */ + } + /* ----> HOST NEGOTIATION DETECTED INTERRUPT <---- */ + if (gotgint.b.hstnegdet) + { + if (USB_OTG_IsDeviceMode(pdev)) /* The core AUTOMATICALLY sets the Host mode */ + { + + } + else + { + + } + } + if (gotgint.b.adevtoutchng) + {} + if (gotgint.b.debdone) + { + USB_OTG_ResetPort(pdev); + } + /* Clear OTG INT */ + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GOTGINT, gotgint.d32); + return 1; +} + + +/** + * @brief USB_OTG_HandleConnectorIDStatusChange_ISR + * handles the Connector ID Status Change Interrupt + * @param None + * @retval : status + */ +static uint32_t USB_OTG_HandleConnectorIDStatusChange_ISR(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_GINTMSK_TypeDef gintmsk; + USB_OTG_GOTGCTL_TypeDef gotgctl; + USB_OTG_GINTSTS_TypeDef gintsts; + + gintsts.d32 = 0 ; + gintmsk.d32 = 0 ; + gotgctl.d32 = 0 ; + gintmsk.b.sofintr = 1; + + USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GINTMSK, gintmsk.d32, 0); + gotgctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGCTL); + + /* B-Device connector (Device Mode) */ + if (gotgctl.b.conidsts) + { + USB_OTG_DisableGlobalInt(pdev); + USB_OTG_CoreInitDev(pdev); + USB_OTG_EnableGlobalInt(pdev); + pdev->otg.OTG_State = B_PERIPHERAL; + } + else + { + USB_OTG_DisableGlobalInt(pdev); + USB_OTG_CoreInitHost(pdev); + USB_OTG_EnableGlobalInt(pdev); + pdev->otg.OTG_State = A_HOST; + } + /* Set flag and clear interrupt */ + gintsts.b.conidstschng = 1; + USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32); + return 1; +} + + +/** + * @brief USB_OTG_HandleSessionRequest_ISR + * Initiating the Session Request Protocol + * @param None + * @retval : status + */ +static uint32_t USB_OTG_HandleSessionRequest_ISR(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_GINTSTS_TypeDef gintsts; + USB_OTG_GOTGCTL_TypeDef gotgctl; + + + gotgctl.d32 = 0; + gintsts.d32 = 0; + + gotgctl.d32 = USB_OTG_READ_REG32( &pdev->regs.GREGS->GOTGCTL ); + if (USB_OTG_IsDeviceMode(pdev) && (gotgctl.b.bsesvld)) + { + + } + else if (gotgctl.b.asesvld) + { + } + /* Clear interrupt */ + gintsts.d32 = 0; + gintsts.b.sessreqintr = 1; + USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32); + return 1; +} + + +/** + * @brief USB_OTG_InitiateSRP + * Initiate an srp session + * @param None + * @retval : None + */ +void USB_OTG_InitiateSRP(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_GOTGCTL_TypeDef otgctl; + + otgctl.d32 = 0; + + otgctl.d32 = USB_OTG_READ_REG32( &pdev->regs.GREGS->GOTGCTL ); + if (otgctl.b.sesreq) + { + return; /* SRP in progress */ + } + otgctl.b.sesreq = 1; + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GOTGCTL, otgctl.d32); +} + + +/** + * @brief USB_OTG_InitiateHNP + * Initiate HNP + * @param None + * @retval : None + */ +void USB_OTG_InitiateHNP(USB_OTG_CORE_HANDLE *pdev , uint8_t state, uint8_t mode) +{ + USB_OTG_GOTGCTL_TypeDef otgctl; + USB_OTG_HPRT0_TypeDef hprt0; + + otgctl.d32 = 0; + hprt0.d32 = 0; + + otgctl.d32 = USB_OTG_READ_REG32( &pdev->regs.GREGS->GOTGCTL ); + if (mode) + { /* Device mode */ + if (state) + { + + otgctl.b.devhnpen = 1; /* B-Dev has been enabled to perform HNP */ + otgctl.b.hnpreq = 1; /* Initiate an HNP req. to the connected USB host*/ + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GOTGCTL, otgctl.d32); + } + } + else + { /* Host mode */ + if (state) + { + otgctl.b.hstsethnpen = 1; /* A-Dev has enabled B-device for HNP */ + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GOTGCTL, otgctl.d32); + /* Suspend the bus so that B-dev will disconnect indicating the initial condition for HNP to DWC_Core */ + hprt0.d32 = USB_OTG_ReadHPRT0(pdev); + hprt0.b.prtsusp = 1; /* The core clear this bit when disconnect interrupt generated (GINTSTS.DisconnInt = '1') */ + USB_OTG_WRITE_REG32(pdev->regs.HPRT0, hprt0.d32); + } + } +} + + /** * @brief USB_OTG_GetCurrentState * Return current OTG State @@ -172,4 +415,4 @@ uint32_t USB_OTG_GetCurrentState (USB_OTG_CORE_HANDLE *pdev) * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 5da0adcbfc..ed88dd40b1 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1227,7 +1227,7 @@ static bool blackboxWriteSysinfo() BLACKBOX_PRINT_HEADER_LINE("mag_hardware:%d", masterConfig.mag_hardware); BLACKBOX_PRINT_HEADER_LINE("gyro_cal_on_first_arm:%d", masterConfig.gyro_cal_on_first_arm); BLACKBOX_PRINT_HEADER_LINE("vbat_pid_compensation:%d", masterConfig.batteryConfig.vbatPidCompensation); - BLACKBOX_PRINT_HEADER_LINE("rc_smoothing:%d", masterConfig.rxConfig.rcSmoothing); + BLACKBOX_PRINT_HEADER_LINE("rc_smooth_interval:%d", masterConfig.rxConfig.rcSmoothInterval); BLACKBOX_PRINT_HEADER_LINE("airmode_activate_throttle:%d", masterConfig.rxConfig.airModeActivateThreshold); BLACKBOX_PRINT_HEADER_LINE("features:%d", masterConfig.enabledFeatures); diff --git a/src/main/common/atomic.h b/src/main/common/atomic.h index 00008b585c..9473c85a0e 100644 --- a/src/main/common/atomic.h +++ b/src/main/common/atomic.h @@ -31,10 +31,12 @@ __attribute__( ( always_inline ) ) static inline void __set_BASEPRI_MAX_nb(uint3 __ASM volatile ("\tMSR basepri_max, %0\n" : : "r" (basePri) ); } +#ifndef STM32F4 /* already defined in /lib/main/CMSIS/CM4/CoreSupport/core_cmFunc.h for F4 targets */ __attribute__( ( always_inline ) ) static inline void __set_BASEPRI_MAX(uint32_t basePri) { __ASM volatile ("\tMSR basepri_max, %0\n" : : "r" (basePri) : "memory" ); } +#endif // cleanup BASEPRI restore function, with global memory barrier static inline void __basepriRestoreMem(uint8_t *val) diff --git a/src/main/config/config.c b/src/main/config/config.c index aa88fb0c8e..c371ad2946 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -23,6 +23,8 @@ #include "build_config.h" +#include "blackbox/blackbox_io.h" + #include "common/color.h" #include "common/axis.h" #include "common/maths.h" @@ -169,7 +171,7 @@ static uint32_t activeFeaturesLatch = 0; static uint8_t currentControlRateProfileIndex = 0; controlRateConfig_t *currentControlRateProfile; -static const uint8_t EEPROM_CONF_VERSION = 140; +static const uint8_t EEPROM_CONF_VERSION = 141; static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims) { @@ -178,13 +180,13 @@ static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims) accelerometerTrims->values.yaw = 0; } -static void resetPidProfile(pidProfile_t *pidProfile) +void resetPidProfile(pidProfile_t *pidProfile) { #if (defined(STM32F10X)) - pidProfile->pidController = PID_CONTROLLER_MWREWRITE; + pidProfile->pidController = PID_CONTROLLER_INTEGER; #else - pidProfile->pidController = PID_CONTROLLER_LUX_FLOAT; + pidProfile->pidController = PID_CONTROLLER_FLOAT; #endif pidProfile->P8[ROLL] = 45; @@ -193,7 +195,7 @@ static void resetPidProfile(pidProfile_t *pidProfile) pidProfile->P8[PITCH] = 50; pidProfile->I8[PITCH] = 40; pidProfile->D8[PITCH] = 18; - pidProfile->P8[YAW] = 90; + pidProfile->P8[YAW] = 80; pidProfile->I8[YAW] = 45; pidProfile->D8[YAW] = 20; pidProfile->P8[PIDALT] = 50; @@ -218,9 +220,10 @@ static void resetPidProfile(pidProfile_t *pidProfile) pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX; pidProfile->yaw_lpf_hz = 80; - pidProfile->rollPitchItermIgnoreRate = 200; + pidProfile->rollPitchItermIgnoreRate = 180; pidProfile->yawItermIgnoreRate = 35; - pidProfile->dterm_lpf_hz = 50; // filtering ON by default + pidProfile->dterm_lpf_hz = 100; // filtering ON by default + pidProfile->deltaMethod = DELTA_FROM_MEASUREMENT; pidProfile->dynamic_pid = 1; #ifdef GTUNE @@ -396,7 +399,7 @@ uint8_t getCurrentControlRateProfile(void) static void setControlRateProfile(uint8_t profileIndex) { currentControlRateProfileIndex = profileIndex; - masterConfig.profile[getCurrentProfile()].activeRateProfile = profileIndex; + masterConfig.profile[getCurrentProfile()].activeRateProfile = profileIndex; currentControlRateProfile = &masterConfig.profile[getCurrentProfile()].controlRateProfile[profileIndex]; } @@ -494,7 +497,7 @@ static void resetConf(void) masterConfig.rxConfig.rssi_channel = 0; masterConfig.rxConfig.rssi_scale = RSSI_SCALE_DEFAULT; masterConfig.rxConfig.rssi_ppm_invert = 0; - masterConfig.rxConfig.rcSmoothing = 0; // TODO - Cleanup with next EEPROM changes + masterConfig.rxConfig.rcSmoothInterval = 0; // 0 is predefined masterConfig.rxConfig.fpvCamAngleDegrees = 0; #ifdef STM32F4 masterConfig.rxConfig.max_aux_channel = 99; @@ -535,10 +538,10 @@ static void resetConf(void) #ifdef GPS // gps/nav stuff - masterConfig.gpsConfig.provider = GPS_NMEA; - masterConfig.gpsConfig.sbasMode = SBAS_AUTO; + masterConfig.gpsConfig.provider = GPS_NMEA; + masterConfig.gpsConfig.sbasMode = SBAS_AUTO; masterConfig.gpsConfig.autoConfig = GPS_AUTOCONFIG_ON; - masterConfig.gpsConfig.autoBaud = GPS_AUTOBAUD_OFF; + masterConfig.gpsConfig.autoBaud = GPS_AUTOBAUD_OFF; #endif resetSerialConfig(&masterConfig.serialConfig); @@ -614,14 +617,14 @@ static void resetConf(void) masterConfig.vtx_mhz = 5740; //F0 #endif -#ifdef SPRACINGF3 - masterConfig.blackbox_device = 1; #ifdef TRANSPONDER static const uint8_t defaultTransponderData[6] = { 0x12, 0x34, 0x56, 0x78, 0x9A, 0xBC }; // Note, this is NOT a valid transponder code, it's just for testing production hardware memcpy(masterConfig.transponderData, &defaultTransponderData, sizeof(defaultTransponderData)); #endif +#ifdef BLACKBOX + #if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT) featureSet(FEATURE_BLACKBOX); masterConfig.blackbox_device = BLACKBOX_DEVICE_FLASH; @@ -629,13 +632,14 @@ static void resetConf(void) featureSet(FEATURE_BLACKBOX); masterConfig.blackbox_device = BLACKBOX_DEVICE_SDCARD; #else - masterConfig.blackbox_device = 0; + masterConfig.blackbox_device = BLACKBOX_DEVICE_SERIAL; #endif masterConfig.blackbox_rate_num = 1; masterConfig.blackbox_rate_denom = 1; -#endif +#endif // BLACKBOX + // alternative defaults settings for COLIBRI RACE targets #if defined(COLIBRI_RACE) masterConfig.escAndServoConfig.minthrottle = 1025; @@ -650,20 +654,21 @@ static void resetConf(void) #if defined(ALIENFLIGHT) featureClear(FEATURE_ONESHOT125); -#ifdef ALIENFLIGHTF3 +#ifdef ALIENFLIGHTF1 + masterConfig.serialConfig.portConfigs[1].functionMask = FUNCTION_RX_SERIAL; +#else masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL; +#endif +#ifdef ALIENFLIGHTF3 masterConfig.batteryConfig.vbatscale = 20; masterConfig.mag_hardware = MAG_NONE; // disabled by default -#else - masterConfig.serialConfig.portConfigs[1].functionMask = FUNCTION_RX_SERIAL; #endif - masterConfig.rxConfig.serialrx_provider = 1; + masterConfig.rxConfig.serialrx_provider = SERIALRX_SPEKTRUM2048; masterConfig.rxConfig.spektrum_sat_bind = 5; masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1; masterConfig.escAndServoConfig.minthrottle = 1000; masterConfig.escAndServoConfig.maxthrottle = 2000; masterConfig.motor_pwm_rate = 32000; - currentProfile->pidProfile.pidController = 2; masterConfig.failsafeConfig.failsafe_delay = 2; masterConfig.failsafeConfig.failsafe_off_delay = 0; currentControlRateProfile->rates[FD_PITCH] = 40; @@ -683,10 +688,6 @@ static void resetConf(void) #if defined(SINGULARITY) // alternative defaults settings for SINGULARITY target - masterConfig.blackbox_device = 1; - masterConfig.blackbox_rate_num = 1; - masterConfig.blackbox_rate_denom = 1; - masterConfig.batteryConfig.vbatscale = 77; masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL; @@ -1045,7 +1046,8 @@ void changeProfile(uint8_t profileIndex) beeperConfirmationBeeps(profileIndex + 1); } -void changeControlRateProfile(uint8_t profileIndex) { +void changeControlRateProfile(uint8_t profileIndex) +{ if (profileIndex > MAX_RATEPROFILES) { profileIndex = MAX_RATEPROFILES - 1; } @@ -1053,17 +1055,6 @@ void changeControlRateProfile(uint8_t profileIndex) { activateControlRateConfig(); } -void handleOneshotFeatureChangeOnRestart(void) -{ - // Shutdown PWM on all motors prior to soft restart - StopPwmAllMotors(); - delay(50); - // Apply additional delay when OneShot125 feature changed from on to off state - if (feature(FEATURE_ONESHOT125) && !featureConfigured(FEATURE_ONESHOT125)) { - delay(ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS); - } -} - void latchActiveFeatures() { activeFeaturesLatch = masterConfig.enabledFeatures; diff --git a/src/main/config/config.h b/src/main/config/config.h index 9150540cfd..c26bbe6455 100644 --- a/src/main/config/config.h +++ b/src/main/config/config.h @@ -50,7 +50,6 @@ typedef enum { FEATURE_VTX = 1 << 25, } features_e; -void handleOneshotFeatureChangeOnRestart(void); void latchActiveFeatures(void); bool featureConfigured(uint32_t mask); bool feature(uint32_t mask); diff --git a/src/main/drivers/accgyro_l3gd20.c b/src/main/drivers/accgyro_l3gd20.c index 7b14634b04..dd28aceb11 100644 --- a/src/main/drivers/accgyro_l3gd20.c +++ b/src/main/drivers/accgyro_l3gd20.c @@ -81,7 +81,7 @@ static void l3gd20SpiInit(SPI_TypeDef *SPIx) DISABLE_L3GD20; - spiSetDivisor(L3GD20_SPI, SPI_9MHZ_CLOCK_DIVIDER); + spiSetDivisor(L3GD20_SPI, SPI_CLOCK_STANDARD); } void l3gd20GyroInit(uint8_t lpf) diff --git a/src/main/drivers/accgyro_mpu.c b/src/main/drivers/accgyro_mpu.c index 316a7119cf..0882581d34 100644 --- a/src/main/drivers/accgyro_mpu.c +++ b/src/main/drivers/accgyro_mpu.c @@ -236,7 +236,7 @@ void mpuIntExtiInit(void) #if defined(USE_MPU_DATA_READY_SIGNAL) && defined(USE_EXTI) - IO_t mpuIntIO = IOGetByTag(mpuIntExtiConfig->io); + IO_t mpuIntIO = IOGetByTag(mpuIntExtiConfig->tag); #ifdef ENSURE_MPU_DATA_READY_IS_LOW uint8_t status = IORead(mpuIntIO); diff --git a/src/main/drivers/accgyro_spi_mpu6000.c b/src/main/drivers/accgyro_spi_mpu6000.c index 56143f0e4e..3d58913d0a 100644 --- a/src/main/drivers/accgyro_spi_mpu6000.c +++ b/src/main/drivers/accgyro_spi_mpu6000.c @@ -128,13 +128,13 @@ void mpu6000SpiGyroInit(uint8_t lpf) mpu6000AccAndGyroInit(); - spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER); + spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); // Accel and Gyro DLPF Setting mpu6000WriteRegister(MPU6000_CONFIG, lpf); delayMicroseconds(1); - spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER); // 18 MHz SPI clock + spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_FAST); // 18 MHz SPI clock int16_t data[3]; mpuGyroRead(data); @@ -162,7 +162,7 @@ bool mpu6000SpiDetect(void) IOInit(mpuSpi6000CsPin, OWNER_SYSTEM, RESOURCE_SPI); IOConfigGPIO(mpuSpi6000CsPin, SPI_IO_CS_CFG); - spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER); + spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); mpu6000WriteRegister(MPU_RA_PWR_MGMT_1, BIT_H_RESET); @@ -209,7 +209,7 @@ static void mpu6000AccAndGyroInit(void) { return; } - spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER); + spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); // Device Reset mpu6000WriteRegister(MPU_RA_PWR_MGMT_1, BIT_H_RESET); @@ -251,7 +251,7 @@ static void mpu6000AccAndGyroInit(void) { delayMicroseconds(15); #endif - spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER); // 18 MHz SPI clock + spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_FAST); delayMicroseconds(1); mpuSpi6000InitDone = true; diff --git a/src/main/drivers/accgyro_spi_mpu6500.c b/src/main/drivers/accgyro_spi_mpu6500.c index 316a296c3a..4df65c19cb 100755 --- a/src/main/drivers/accgyro_spi_mpu6500.c +++ b/src/main/drivers/accgyro_spi_mpu6500.c @@ -72,11 +72,7 @@ static void mpu6500SpiInit(void) IOInit(mpuSpi6500CsPin, OWNER_SYSTEM, RESOURCE_SPI); IOConfigGPIO(mpuSpi6500CsPin, SPI_IO_CS_CFG); -#if defined(STM32F4) - spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_SLOW_CLOCK); -#else - spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_STANDARD_CLOCK); -#endif + spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_CLOCK_FAST); hardwareInitialised = true; } diff --git a/src/main/drivers/accgyro_spi_mpu9250.c b/src/main/drivers/accgyro_spi_mpu9250.c index 2721d05594..2bad53bf35 100644 --- a/src/main/drivers/accgyro_spi_mpu9250.c +++ b/src/main/drivers/accgyro_spi_mpu9250.c @@ -55,7 +55,8 @@ static IO_t mpuSpi9250CsPin = IO_NONE; #define DISABLE_MPU9250 IOHi(mpuSpi9250CsPin) #define ENABLE_MPU9250 IOLo(mpuSpi9250CsPin) -void mpu9250ResetGyro(void) { +void mpu9250ResetGyro(void) +{ // Device Reset mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET); delay(150); @@ -105,7 +106,7 @@ void mpu9250SpiGyroInit(uint8_t lpf) spiResetErrorCounter(MPU9250_SPI_INSTANCE); - spiSetDivisor(MPU9250_SPI_INSTANCE, 5); //high speed now that we don't need to write to the slow registers + spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST); //high speed now that we don't need to write to the slow registers int16_t data[3]; mpuGyroRead(data); @@ -123,9 +124,8 @@ void mpu9250SpiAccInit(acc_t *acc) acc->acc_1G = 512 * 8; } - -bool verifympu9250WriteRegister(uint8_t reg, uint8_t data) { - +bool verifympu9250WriteRegister(uint8_t reg, uint8_t data) +{ uint8_t in; uint8_t attemptsRemaining = 20; @@ -151,7 +151,7 @@ static void mpu9250AccAndGyroInit(uint8_t lpf) { return; } - spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_SLOW_CLOCK); //low speed for writing to slow registers + spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); //low speed for writing to slow registers mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET); delay(50); @@ -177,6 +177,8 @@ static void mpu9250AccAndGyroInit(uint8_t lpf) { verifympu9250WriteRegister(MPU_RA_INT_ENABLE, 0x01); //this resets register MPU_RA_PWR_MGMT_1 and won't read back correctly. #endif + spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST); + mpuSpi9250InitDone = true; //init done } @@ -192,7 +194,7 @@ bool mpu9250SpiDetect(void) IOInit(mpuSpi9250CsPin, OWNER_SYSTEM, RESOURCE_SPI); IOConfigGPIO(mpuSpi9250CsPin, SPI_IO_CS_CFG); - spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_SLOW_CLOCK); //low speed + spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); //low speed mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET); do { @@ -207,6 +209,8 @@ bool mpu9250SpiDetect(void) } } while (attemptsRemaining--); + spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST); + return true; } diff --git a/src/main/drivers/adc.c b/src/main/drivers/adc.c index 37433d1311..46f987dfc7 100644 --- a/src/main/drivers/adc.c +++ b/src/main/drivers/adc.c @@ -33,6 +33,14 @@ adc_config_t adcConfig[ADC_CHANNEL_COUNT]; volatile uint16_t adcValues[ADC_CHANNEL_COUNT]; +uint8_t adcChannelByTag(ioTag_t ioTag) +{ + for (uint8_t i = 0; i < ARRAYLEN(adcTagMap); i++) { + if (ioTag == adcTagMap[i].tag) + return adcTagMap[i].channel; + } + return 0; +} uint16_t adcGetChannel(uint8_t channel) { diff --git a/src/main/drivers/adc_impl.h b/src/main/drivers/adc_impl.h index 8007308251..ee2e92d40f 100644 --- a/src/main/drivers/adc_impl.h +++ b/src/main/drivers/adc_impl.h @@ -17,5 +17,52 @@ #pragma once +#include "io.h" +#include "rcc.h" + +#if defined(STM32F4) +#define ADC_TAG_MAP_COUNT 16 +#elif defined(STM32F3) +#define ADC_TAG_MAP_COUNT 39 +#else +#define ADC_TAG_MAP_COUNT 10 +#endif + +typedef enum ADCDevice { + ADCINVALID = -1, + ADCDEV_1 = 0, +#if defined(STM32F3) + ADCDEV_2, + ADCDEV_MAX = ADCDEV_2, +#elif defined(STM32F4) + ADCDEV_2, + ADCDEV_3, + ADCDEV_MAX = ADCDEV_3, +#else + ADCDEV_MAX = ADCDEV_1, +#endif +} ADCDevice; + +typedef struct adcTagMap_s { + ioTag_t tag; + uint8_t channel; +} adcTagMap_t; + +typedef struct adcDevice_s { + ADC_TypeDef* ADCx; + rccPeriphTag_t rccADC; + rccPeriphTag_t rccDMA; +#if defined(STM32F4) + DMA_Stream_TypeDef* DMAy_Streamx; + uint32_t channel; +#else + DMA_Channel_TypeDef* DMAy_Channelx; +#endif +} adcDevice_t; + +extern const adcDevice_t adcHardware[]; +extern const adcTagMap_t adcTagMap[ADC_TAG_MAP_COUNT]; extern adc_config_t adcConfig[ADC_CHANNEL_COUNT]; extern volatile uint16_t adcValues[ADC_CHANNEL_COUNT]; + +uint8_t adcChannelByTag(ioTag_t ioTag); \ No newline at end of file diff --git a/src/main/drivers/adc_stm32f10x.c b/src/main/drivers/adc_stm32f10x.c index 11dec5bfc1..b082388fe2 100644 --- a/src/main/drivers/adc_stm32f10x.c +++ b/src/main/drivers/adc_stm32f10x.c @@ -29,17 +29,44 @@ #include "sensor.h" #include "accgyro.h" - #include "adc.h" #include "adc_impl.h" +#include "io.h" +#include "rcc.h" #ifndef ADC_INSTANCE -#define ADC_INSTANCE ADC1 -#define ADC_ABP2_PERIPHERAL RCC_APB2Periph_ADC1 -#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1 -#define ADC_DMA_CHANNEL DMA1_Channel1 +#define ADC_INSTANCE ADC1 #endif +const adcDevice_t adcHardware[] = { + { .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB(DMA1), .DMAy_Channelx = DMA1_Channel1 } +}; + +ADCDevice adcDeviceByInstance(ADC_TypeDef *instance) +{ + if (instance == ADC1) + return ADCDEV_1; + +/* TODO -- ADC2 available on large 10x devices. + if (instance == ADC2) + return ADCDEV_2; +*/ + return ADCINVALID; +} + +const adcTagMap_t adcTagMap[] = { + { DEFIO_TAG_E__PA0, ADC_Channel_0 }, // ADC12 + { DEFIO_TAG_E__PA1, ADC_Channel_1 }, // ADC12 + { DEFIO_TAG_E__PA2, ADC_Channel_2 }, // ADC12 + { DEFIO_TAG_E__PA3, ADC_Channel_3 }, // ADC12 + { DEFIO_TAG_E__PA4, ADC_Channel_4 }, // ADC12 + { DEFIO_TAG_E__PA5, ADC_Channel_5 }, // ADC12 + { DEFIO_TAG_E__PA6, ADC_Channel_6 }, // ADC12 + { DEFIO_TAG_E__PA7, ADC_Channel_7 }, // ADC12 + { DEFIO_TAG_E__PB0, ADC_Channel_8 }, // ADC12 + { DEFIO_TAG_E__PB1, ADC_Channel_9 }, // ADC12 +}; + // Driver for STM32F103CB onboard ADC // // Naze32 @@ -50,77 +77,78 @@ // NAZE rev.5 hardware has PA5 (ADC1_IN5) on breakout pad on bottom of board // - void adcInit(drv_adc_config_t *init) { -#if defined(CJMCU) || defined(CC3D) - UNUSED(init); + +#if !defined(VBAT_ADC_PIN) && !defined(EXTERNAL1_ADC_PIN) && !defined(RSSI_ADC_PIN) && !defined(CURRENT_METER_ADC_PIN) + UNUSED(init); #endif - uint8_t i; uint8_t configuredAdcChannels = 0; memset(&adcConfig, 0, sizeof(adcConfig)); - GPIO_InitTypeDef GPIO_InitStructure; - GPIO_StructInit(&GPIO_InitStructure); - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN; - -#ifdef VBAT_ADC_GPIO +#ifdef VBAT_ADC_PIN if (init->enableVBat) { - GPIO_InitStructure.GPIO_Pin = VBAT_ADC_GPIO_PIN; - GPIO_Init(VBAT_ADC_GPIO, &GPIO_InitStructure); - adcConfig[ADC_BATTERY].adcChannel = VBAT_ADC_CHANNEL; + IOInit(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); + IOConfigGPIO(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0)); + adcConfig[ADC_BATTERY].adcChannel = adcChannelByTag(IO_TAG(VBAT_ADC_PIN)); adcConfig[ADC_BATTERY].dmaIndex = configuredAdcChannels++; adcConfig[ADC_BATTERY].enabled = true; adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_239Cycles5; } #endif -#ifdef RSSI_ADC_GPIO +#ifdef RSSI_ADC_PIN if (init->enableRSSI) { - GPIO_InitStructure.GPIO_Pin = RSSI_ADC_GPIO_PIN; - GPIO_Init(RSSI_ADC_GPIO, &GPIO_InitStructure); - adcConfig[ADC_RSSI].adcChannel = RSSI_ADC_CHANNEL; + IOInit(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); + IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0)); + adcConfig[ADC_RSSI].adcChannel = adcChannelByTag(IO_TAG(RSSI_ADC_PIN)); adcConfig[ADC_RSSI].dmaIndex = configuredAdcChannels++; adcConfig[ADC_RSSI].enabled = true; adcConfig[ADC_RSSI].sampleTime = ADC_SampleTime_239Cycles5; } #endif -#ifdef EXTERNAL1_ADC_GPIO +#ifdef EXTERNAL1_ADC_PIN if (init->enableExternal1) { - GPIO_InitStructure.GPIO_Pin = EXTERNAL1_ADC_GPIO_PIN; - GPIO_Init(EXTERNAL1_ADC_GPIO, &GPIO_InitStructure); - adcConfig[ADC_EXTERNAL1].adcChannel = EXTERNAL1_ADC_CHANNEL; + IOInit(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); + IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0)); + adcConfig[ADC_EXTERNAL1].adcChannel = adcChannelByTag(IO_TAG(EXTERNAL1_ADC_PIN)); adcConfig[ADC_EXTERNAL1].dmaIndex = configuredAdcChannels++; adcConfig[ADC_EXTERNAL1].enabled = true; adcConfig[ADC_EXTERNAL1].sampleTime = ADC_SampleTime_239Cycles5; } #endif -#ifdef CURRENT_METER_ADC_GPIO +#ifdef CURRENT_METER_ADC_PIN if (init->enableCurrentMeter) { - GPIO_InitStructure.GPIO_Pin = CURRENT_METER_ADC_GPIO_PIN; - GPIO_Init(CURRENT_METER_ADC_GPIO, &GPIO_InitStructure); - adcConfig[ADC_CURRENT].adcChannel = CURRENT_METER_ADC_CHANNEL; + IOInit(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); + IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0)); + adcConfig[ADC_CURRENT].adcChannel = adcChannelByTag(IO_TAG(CURRENT_METER_ADC_PIN)); adcConfig[ADC_CURRENT].dmaIndex = configuredAdcChannels++; adcConfig[ADC_CURRENT].enabled = true; adcConfig[ADC_CURRENT].sampleTime = ADC_SampleTime_239Cycles5; } #endif + ADCDevice device = adcDeviceByInstance(ADC_INSTANCE); + if (device == ADCINVALID) + return; + + adcDevice_t adc = adcHardware[device]; + RCC_ADCCLKConfig(RCC_PCLK2_Div8); // 9MHz from 72MHz APB2 clock(HSE), 8MHz from 64MHz (HSI) - RCC_AHBPeriphClockCmd(ADC_AHB_PERIPHERAL, ENABLE); - RCC_APB2PeriphClockCmd(ADC_ABP2_PERIPHERAL, ENABLE); - + RCC_ClockCmd(adc.rccADC, ENABLE); + RCC_ClockCmd(adc.rccDMA, ENABLE); + // FIXME ADC driver assumes all the GPIO was already placed in 'AIN' mode - DMA_DeInit(ADC_DMA_CHANNEL); + DMA_DeInit(adc.DMAy_Channelx); DMA_InitTypeDef DMA_InitStructure; DMA_StructInit(&DMA_InitStructure); - DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&ADC_INSTANCE->DR; + DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&adc.ADCx->DR; DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)adcValues; DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC; DMA_InitStructure.DMA_BufferSize = configuredAdcChannels; @@ -131,8 +159,8 @@ void adcInit(drv_adc_config_t *init) DMA_InitStructure.DMA_Mode = DMA_Mode_Circular; DMA_InitStructure.DMA_Priority = DMA_Priority_High; DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; - DMA_Init(ADC_DMA_CHANNEL, &DMA_InitStructure); - DMA_Cmd(ADC_DMA_CHANNEL, ENABLE); + DMA_Init(adc.DMAy_Channelx, &DMA_InitStructure); + DMA_Cmd(adc.DMAy_Channelx, ENABLE); ADC_InitTypeDef ADC_InitStructure; ADC_StructInit(&ADC_InitStructure); @@ -142,23 +170,23 @@ void adcInit(drv_adc_config_t *init) ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None; ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right; ADC_InitStructure.ADC_NbrOfChannel = configuredAdcChannels; - ADC_Init(ADC_INSTANCE, &ADC_InitStructure); + ADC_Init(adc.ADCx, &ADC_InitStructure); uint8_t rank = 1; for (i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcConfig[i].enabled) { continue; } - ADC_RegularChannelConfig(ADC_INSTANCE, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime); + ADC_RegularChannelConfig(adc.ADCx, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime); } - ADC_DMACmd(ADC_INSTANCE, ENABLE); - ADC_Cmd(ADC_INSTANCE, ENABLE); + ADC_DMACmd(adc.ADCx, ENABLE); + ADC_Cmd(adc.ADCx, ENABLE); - ADC_ResetCalibration(ADC_INSTANCE); - while(ADC_GetResetCalibrationStatus(ADC_INSTANCE)); - ADC_StartCalibration(ADC_INSTANCE); - while(ADC_GetCalibrationStatus(ADC_INSTANCE)); + ADC_ResetCalibration(adc.ADCx); + while (ADC_GetResetCalibrationStatus(adc.ADCx)); + ADC_StartCalibration(adc.ADCx); + while (ADC_GetCalibrationStatus(adc.ADCx)); - ADC_SoftwareStartConvCmd(ADC_INSTANCE, ENABLE); + ADC_SoftwareStartConvCmd(adc.ADCx, ENABLE); } diff --git a/src/main/drivers/adc_stm32f30x.c b/src/main/drivers/adc_stm32f30x.c index 97f6ee525b..dc9c98ee51 100644 --- a/src/main/drivers/adc_stm32f30x.c +++ b/src/main/drivers/adc_stm32f30x.c @@ -29,35 +29,88 @@ #include "adc.h" #include "adc_impl.h" +#include "io.h" +#include "rcc.h" #ifndef ADC_INSTANCE #define ADC_INSTANCE ADC1 -#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1 -#define ADC_DMA_CHANNEL DMA1_Channel1 #endif +const adcDevice_t adcHardware[] = { + { .ADCx = ADC1, .rccADC = RCC_AHB(ADC12), .rccDMA = RCC_AHB(DMA1), .DMAy_Channelx = DMA1_Channel1 }, + { .ADCx = ADC2, .rccADC = RCC_AHB(ADC12), .rccDMA = RCC_AHB(DMA2), .DMAy_Channelx = DMA2_Channel1 } +}; + +const adcTagMap_t adcTagMap[] = { + { DEFIO_TAG_E__PA0, ADC_Channel_1 }, // ADC1 + { DEFIO_TAG_E__PA1, ADC_Channel_2 }, // ADC1 + { DEFIO_TAG_E__PA2, ADC_Channel_3 }, // ADC1 + { DEFIO_TAG_E__PA3, ADC_Channel_4 }, // ADC1 + { DEFIO_TAG_E__PA4, ADC_Channel_1 }, // ADC2 + { DEFIO_TAG_E__PA5, ADC_Channel_2 }, // ADC2 + { DEFIO_TAG_E__PA6, ADC_Channel_3 }, // ADC2 + { DEFIO_TAG_E__PA7, ADC_Channel_4 }, // ADC2 + { DEFIO_TAG_E__PB0, ADC_Channel_12 }, // ADC3 + { DEFIO_TAG_E__PB1, ADC_Channel_1 }, // ADC3 + { DEFIO_TAG_E__PB2, ADC_Channel_12 }, // ADC2 + { DEFIO_TAG_E__PB12, ADC_Channel_3 }, // ADC4 + { DEFIO_TAG_E__PB13, ADC_Channel_5 }, // ADC3 + { DEFIO_TAG_E__PB14, ADC_Channel_4 }, // ADC4 + { DEFIO_TAG_E__PB15, ADC_Channel_5 }, // ADC4 + { DEFIO_TAG_E__PC0, ADC_Channel_6 }, // ADC12 + { DEFIO_TAG_E__PC1, ADC_Channel_7 }, // ADC12 + { DEFIO_TAG_E__PC2, ADC_Channel_8 }, // ADC12 + { DEFIO_TAG_E__PC3, ADC_Channel_9 }, // ADC12 + { DEFIO_TAG_E__PC4, ADC_Channel_5 }, // ADC2 + { DEFIO_TAG_E__PC5, ADC_Channel_11 }, // ADC2 + { DEFIO_TAG_E__PD8, ADC_Channel_12 }, // ADC4 + { DEFIO_TAG_E__PD9, ADC_Channel_13 }, // ADC4 + { DEFIO_TAG_E__PD10, ADC_Channel_7 }, // ADC34 + { DEFIO_TAG_E__PD11, ADC_Channel_8 }, // ADC34 + { DEFIO_TAG_E__PD12, ADC_Channel_9 }, // ADC34 + { DEFIO_TAG_E__PD13, ADC_Channel_10 }, // ADC34 + { DEFIO_TAG_E__PD14, ADC_Channel_11 }, // ADC34 + { DEFIO_TAG_E__PE7, ADC_Channel_13 }, // ADC3 + { DEFIO_TAG_E__PE8, ADC_Channel_6 }, // ADC34 + { DEFIO_TAG_E__PE9, ADC_Channel_2 }, // ADC3 + { DEFIO_TAG_E__PE10, ADC_Channel_14 }, // ADC3 + { DEFIO_TAG_E__PE11, ADC_Channel_15 }, // ADC3 + { DEFIO_TAG_E__PE12, ADC_Channel_16 }, // ADC3 + { DEFIO_TAG_E__PE13, ADC_Channel_3 }, // ADC3 + { DEFIO_TAG_E__PE14, ADC_Channel_1 }, // ADC4 + { DEFIO_TAG_E__PE15, ADC_Channel_2 }, // ADC4 + { DEFIO_TAG_E__PF2, ADC_Channel_10 }, // ADC12 + { DEFIO_TAG_E__PF4, ADC_Channel_5 }, // ADC1 +}; + +ADCDevice adcDeviceByInstance(ADC_TypeDef *instance) +{ + if (instance == ADC1) + return ADCDEV_1; + + if (instance == ADC2) + return ADCDEV_2; + + return ADCINVALID; +} + void adcInit(drv_adc_config_t *init) { UNUSED(init); ADC_InitTypeDef ADC_InitStructure; DMA_InitTypeDef DMA_InitStructure; - GPIO_InitTypeDef GPIO_InitStructure; uint8_t i; uint8_t adcChannelCount = 0; memset(&adcConfig, 0, sizeof(adcConfig)); - GPIO_StructInit(&GPIO_InitStructure); - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AN; - GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL ; - -#ifdef VBAT_ADC_GPIO +#ifdef VBAT_ADC_PIN if (init->enableVBat) { - GPIO_InitStructure.GPIO_Pin = VBAT_ADC_GPIO_PIN; - GPIO_Init(VBAT_ADC_GPIO, &GPIO_InitStructure); + IOInit(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); + IOConfigGPIO(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); - adcConfig[ADC_BATTERY].adcChannel = VBAT_ADC_CHANNEL; + adcConfig[ADC_BATTERY].adcChannel = adcChannelByTag(IO_TAG(VBAT_ADC_PIN)); adcConfig[ADC_BATTERY].dmaIndex = adcChannelCount; adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_601Cycles5; adcConfig[ADC_BATTERY].enabled = true; @@ -65,12 +118,12 @@ void adcInit(drv_adc_config_t *init) } #endif -#ifdef RSSI_ADC_GPIO +#ifdef RSSI_ADC_PIN if (init->enableRSSI) { - GPIO_InitStructure.GPIO_Pin = RSSI_ADC_GPIO_PIN; - GPIO_Init(RSSI_ADC_GPIO, &GPIO_InitStructure); + IOInit(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); + IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); - adcConfig[ADC_RSSI].adcChannel = RSSI_ADC_CHANNEL; + adcConfig[ADC_RSSI].adcChannel = adcChannelByTag(IO_TAG(RSSI_ADC_PIN)); adcConfig[ADC_RSSI].dmaIndex = adcChannelCount; adcConfig[ADC_RSSI].sampleTime = ADC_SampleTime_601Cycles5; adcConfig[ADC_RSSI].enabled = true; @@ -80,10 +133,10 @@ void adcInit(drv_adc_config_t *init) #ifdef CURRENT_METER_ADC_GPIO if (init->enableCurrentMeter) { - GPIO_InitStructure.GPIO_Pin = CURRENT_METER_ADC_GPIO_PIN; - GPIO_Init(CURRENT_METER_ADC_GPIO, &GPIO_InitStructure); + IOInit(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); + IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); - adcConfig[ADC_CURRENT].adcChannel = CURRENT_METER_ADC_CHANNEL; + adcConfig[ADC_CURRENT].adcChannel = adcChannelByTag(IO_TAG(CURRENT_METER_ADC_PIN)); adcConfig[ADC_CURRENT].dmaIndex = adcChannelCount; adcConfig[ADC_CURRENT].sampleTime = ADC_SampleTime_601Cycles5; adcConfig[ADC_CURRENT].enabled = true; @@ -93,10 +146,10 @@ void adcInit(drv_adc_config_t *init) #ifdef EXTERNAL1_ADC_GPIO if (init->enableExternal1) { - GPIO_InitStructure.GPIO_Pin = EXTERNAL1_ADC_GPIO_PIN; - GPIO_Init(EXTERNAL1_ADC_GPIO, &GPIO_InitStructure); + IOInit(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); + IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); - adcConfig[ADC_EXTERNAL1].adcChannel = EXTERNAL1_ADC_CHANNEL; + adcConfig[ADC_EXTERNAL1].adcChannel = adcChannelByTag(IO_TAG(EXTERNAL1_ADC_PIN)); adcConfig[ADC_EXTERNAL1].dmaIndex = adcChannelCount; adcConfig[ADC_EXTERNAL1].sampleTime = ADC_SampleTime_601Cycles5; adcConfig[ADC_EXTERNAL1].enabled = true; @@ -104,13 +157,20 @@ void adcInit(drv_adc_config_t *init) } #endif - RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz - RCC_AHBPeriphClockCmd(ADC_AHB_PERIPHERAL | RCC_AHBPeriph_ADC12, ENABLE); + ADCDevice device = adcDeviceByInstance(ADC_INSTANCE); + if (device == ADCINVALID) + return; + + adcDevice_t adc = adcHardware[device]; - DMA_DeInit(ADC_DMA_CHANNEL); + RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz + RCC_ClockCmd(adc.rccADC, ENABLE); + RCC_ClockCmd(adc.rccDMA, ENABLE); + + DMA_DeInit(adc.DMAy_Channelx); DMA_StructInit(&DMA_InitStructure); - DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&ADC_INSTANCE->DR; + DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&adc.ADCx->DR; DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)adcValues; DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC; DMA_InitStructure.DMA_BufferSize = adcChannelCount; @@ -122,20 +182,18 @@ void adcInit(drv_adc_config_t *init) DMA_InitStructure.DMA_Priority = DMA_Priority_High; DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; - DMA_Init(ADC_DMA_CHANNEL, &DMA_InitStructure); - - DMA_Cmd(ADC_DMA_CHANNEL, ENABLE); + DMA_Init(adc.DMAy_Channelx, &DMA_InitStructure); + DMA_Cmd(adc.DMAy_Channelx, ENABLE); // calibrate - ADC_VoltageRegulatorCmd(ADC_INSTANCE, ENABLE); + ADC_VoltageRegulatorCmd(adc.ADCx, ENABLE); delay(10); - ADC_SelectCalibrationMode(ADC_INSTANCE, ADC_CalibrationMode_Single); - ADC_StartCalibration(ADC_INSTANCE); - while(ADC_GetCalibrationStatus(ADC_INSTANCE) != RESET); - ADC_VoltageRegulatorCmd(ADC_INSTANCE, DISABLE); - + ADC_SelectCalibrationMode(adc.ADCx, ADC_CalibrationMode_Single); + ADC_StartCalibration(adc.ADCx); + while (ADC_GetCalibrationStatus(adc.ADCx) != RESET); + ADC_VoltageRegulatorCmd(adc.ADCx, DISABLE); ADC_CommonInitTypeDef ADC_CommonInitStructure; @@ -145,7 +203,7 @@ void adcInit(drv_adc_config_t *init) ADC_CommonInitStructure.ADC_DMAAccessMode = ADC_DMAAccessMode_1; ADC_CommonInitStructure.ADC_DMAMode = ADC_DMAMode_Circular; ADC_CommonInitStructure.ADC_TwoSamplingDelay = 0; - ADC_CommonInit(ADC_INSTANCE, &ADC_CommonInitStructure); + ADC_CommonInit(adc.ADCx, &ADC_CommonInitStructure); ADC_StructInit(&ADC_InitStructure); @@ -158,24 +216,24 @@ void adcInit(drv_adc_config_t *init) ADC_InitStructure.ADC_AutoInjMode = ADC_AutoInjec_Disable; ADC_InitStructure.ADC_NbrOfRegChannel = adcChannelCount; - ADC_Init(ADC_INSTANCE, &ADC_InitStructure); + ADC_Init(adc.ADCx, &ADC_InitStructure); uint8_t rank = 1; for (i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcConfig[i].enabled) { continue; } - ADC_RegularChannelConfig(ADC_INSTANCE, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime); + ADC_RegularChannelConfig(adc.ADCx, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime); } - ADC_Cmd(ADC_INSTANCE, ENABLE); + ADC_Cmd(adc.ADCx, ENABLE); - while(!ADC_GetFlagStatus(ADC_INSTANCE, ADC_FLAG_RDY)); + while (!ADC_GetFlagStatus(adc.ADCx, ADC_FLAG_RDY)); - ADC_DMAConfig(ADC_INSTANCE, ADC_DMAMode_Circular); + ADC_DMAConfig(adc.ADCx, ADC_DMAMode_Circular); - ADC_DMACmd(ADC_INSTANCE, ENABLE); + ADC_DMACmd(adc.ADCx, ENABLE); - ADC_StartConversion(ADC_INSTANCE); + ADC_StartConversion(adc.ADCx); } diff --git a/src/main/drivers/adc_stm32f4xx.c b/src/main/drivers/adc_stm32f4xx.c index 0d051fc118..90ca22d12a 100644 --- a/src/main/drivers/adc_stm32f4xx.c +++ b/src/main/drivers/adc_stm32f4xx.c @@ -23,6 +23,8 @@ #include "system.h" #include "io.h" +#include "io_impl.h" +#include "rcc.h" #include "sensors/sensors.h" // FIXME dependency into the main code @@ -32,6 +34,56 @@ #include "adc.h" #include "adc_impl.h" +#ifndef ADC_INSTANCE +#define ADC_INSTANCE ADC1 +#endif + +const adcDevice_t adcHardware[] = { + { .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream4, .channel = DMA_Channel_0 }, + //{ .ADCx = ADC2, .rccADC = RCC_APB2(ADC2), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream1, .channel = DMA_Channel_0 } +}; + +/* note these could be packed up for saving space */ +const adcTagMap_t adcTagMap[] = { +/* + { DEFIO_TAG_E__PF3, ADC_Channel_9 }, + { DEFIO_TAG_E__PF4, ADC_Channel_14 }, + { DEFIO_TAG_E__PF5, ADC_Channel_15 }, + { DEFIO_TAG_E__PF6, ADC_Channel_4 }, + { DEFIO_TAG_E__PF7, ADC_Channel_5 }, + { DEFIO_TAG_E__PF8, ADC_Channel_6 }, + { DEFIO_TAG_E__PF9, ADC_Channel_7 }, + { DEFIO_TAG_E__PF10, ADC_Channel_8 }, +*/ + { DEFIO_TAG_E__PC0, ADC_Channel_10 }, + { DEFIO_TAG_E__PC1, ADC_Channel_11 }, + { DEFIO_TAG_E__PC2, ADC_Channel_12 }, + { DEFIO_TAG_E__PC3, ADC_Channel_13 }, + { DEFIO_TAG_E__PC4, ADC_Channel_14 }, + { DEFIO_TAG_E__PC5, ADC_Channel_15 }, + { DEFIO_TAG_E__PB0, ADC_Channel_8 }, + { DEFIO_TAG_E__PB1, ADC_Channel_9 }, + { DEFIO_TAG_E__PA0, ADC_Channel_0 }, + { DEFIO_TAG_E__PA1, ADC_Channel_1 }, + { DEFIO_TAG_E__PA2, ADC_Channel_2 }, + { DEFIO_TAG_E__PA3, ADC_Channel_3 }, + { DEFIO_TAG_E__PA4, ADC_Channel_4 }, + { DEFIO_TAG_E__PA5, ADC_Channel_5 }, + { DEFIO_TAG_E__PA6, ADC_Channel_6 }, + { DEFIO_TAG_E__PA7, ADC_Channel_7 }, +}; + +ADCDevice adcDeviceByInstance(ADC_TypeDef *instance) +{ + if (instance == ADC1) + return ADCDEV_1; +/* + if (instance == ADC2) // TODO add ADC2 and 3 + return ADCDEV_2; +*/ + return ADCINVALID; +} + void adcInit(drv_adc_config_t *init) { ADC_InitTypeDef ADC_InitStructure; @@ -50,7 +102,7 @@ void adcInit(drv_adc_config_t *init) if (init->enableVBat) { IOInit(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); IOConfigGPIO(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); - adcConfig[ADC_BATTERY].adcChannel = VBAT_ADC_CHANNEL; + adcConfig[ADC_BATTERY].adcChannel = adcChannelByTag(IO_TAG(VBAT_ADC_PIN)); //VBAT_ADC_CHANNEL; adcConfig[ADC_BATTERY].dmaIndex = configuredAdcChannels++; adcConfig[ADC_BATTERY].enabled = true; adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_480Cycles; @@ -61,7 +113,7 @@ void adcInit(drv_adc_config_t *init) if (init->enableExternal1) { IOInit(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); - adcConfig[ADC_EXTERNAL1].adcChannel = EXTERNAL1_ADC_CHANNEL; + adcConfig[ADC_EXTERNAL1].adcChannel = adcChannelByTag(IO_TAG(EXTERNAL1_ADC_PIN)); //EXTERNAL1_ADC_CHANNEL; adcConfig[ADC_EXTERNAL1].dmaIndex = configuredAdcChannels++; adcConfig[ADC_EXTERNAL1].enabled = true; adcConfig[ADC_EXTERNAL1].sampleTime = ADC_SampleTime_480Cycles; @@ -72,7 +124,7 @@ void adcInit(drv_adc_config_t *init) if (init->enableRSSI) { IOInit(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); - adcConfig[ADC_RSSI].adcChannel = RSSI_ADC_CHANNEL; + adcConfig[ADC_RSSI].adcChannel = adcChannelByTag(IO_TAG(RSSI_ADC_PIN)); //RSSI_ADC_CHANNEL; adcConfig[ADC_RSSI].dmaIndex = configuredAdcChannels++; adcConfig[ADC_RSSI].enabled = true; adcConfig[ADC_RSSI].sampleTime = ADC_SampleTime_480Cycles; @@ -83,7 +135,7 @@ void adcInit(drv_adc_config_t *init) if (init->enableCurrentMeter) { IOInit(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); - adcConfig[ADC_CURRENT].adcChannel = CURRENT_METER_ADC_CHANNEL; + adcConfig[ADC_CURRENT].adcChannel = adcChannelByTag(IO_TAG(CURRENT_METER_ADC_PIN)); //CURRENT_METER_ADC_CHANNEL; adcConfig[ADC_CURRENT].dmaIndex = configuredAdcChannels++; adcConfig[ADC_CURRENT].enabled = true; adcConfig[ADC_CURRENT].sampleTime = ADC_SampleTime_480Cycles; @@ -92,15 +144,20 @@ void adcInit(drv_adc_config_t *init) //RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz - RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA2, ENABLE); - RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOC, ENABLE); - RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1, ENABLE); + ADCDevice device = adcDeviceByInstance(ADC_INSTANCE); + if (device == ADCINVALID) + return; + + adcDevice_t adc = adcHardware[device]; + + RCC_ClockCmd(adc.rccDMA, ENABLE); + RCC_ClockCmd(adc.rccADC, ENABLE); - DMA_DeInit(DMA2_Stream4); + DMA_DeInit(adc.DMAy_Streamx); DMA_StructInit(&DMA_InitStructure); - DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&ADC1->DR; - DMA_InitStructure.DMA_Channel = DMA_Channel_0; + DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&adc.ADCx->DR; + DMA_InitStructure.DMA_Channel = adc.channel; DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)adcValues; DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory; DMA_InitStructure.DMA_BufferSize = configuredAdcChannels; @@ -110,20 +167,9 @@ void adcInit(drv_adc_config_t *init) DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord; DMA_InitStructure.DMA_Mode = DMA_Mode_Circular; DMA_InitStructure.DMA_Priority = DMA_Priority_High; - DMA_Init(DMA2_Stream4, &DMA_InitStructure); + DMA_Init(adc.DMAy_Streamx, &DMA_InitStructure); - DMA_Cmd(DMA2_Stream4, ENABLE); - - // calibrate - - /* - ADC_VoltageRegulatorCmd(ADC1, ENABLE); - delay(10); - ADC_SelectCalibrationMode(ADC1, ADC_CalibrationMode_Single); - ADC_StartCalibration(ADC1); - while(ADC_GetCalibrationStatus(ADC1) != RESET); - ADC_VoltageRegulatorCmd(ADC1, DISABLE); - */ + DMA_Cmd(adc.DMAy_Streamx, ENABLE); ADC_CommonInitTypeDef ADC_CommonInitStructure; @@ -144,19 +190,19 @@ void adcInit(drv_adc_config_t *init) ADC_InitStructure.ADC_NbrOfConversion = configuredAdcChannels; ADC_InitStructure.ADC_ScanConvMode = configuredAdcChannels > 1 ? ENABLE : DISABLE; // 1=scan more that one channel in group - ADC_Init(ADC1, &ADC_InitStructure); + ADC_Init(adc.ADCx, &ADC_InitStructure); uint8_t rank = 1; for (i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcConfig[i].enabled) { continue; } - ADC_RegularChannelConfig(ADC1, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime); + ADC_RegularChannelConfig(adc.ADCx, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime); } - ADC_DMARequestAfterLastTransferCmd(ADC1, ENABLE); + ADC_DMARequestAfterLastTransferCmd(adc.ADCx, ENABLE); - ADC_DMACmd(ADC1, ENABLE); - ADC_Cmd(ADC1, ENABLE); + ADC_DMACmd(adc.ADCx, ENABLE); + ADC_Cmd(adc.ADCx, ENABLE); - ADC_SoftwareStartConv(ADC1); + ADC_SoftwareStartConv(adc.ADCx); } diff --git a/src/main/drivers/barometer_spi_bmp280.c b/src/main/drivers/barometer_spi_bmp280.c index 0e047383a1..3838ba4328 100644 --- a/src/main/drivers/barometer_spi_bmp280.c +++ b/src/main/drivers/barometer_spi_bmp280.c @@ -28,12 +28,14 @@ #include "barometer.h" #include "barometer_bmp280.h" -#define DISABLE_BMP280 GPIO_SetBits(BMP280_CS_GPIO, BMP280_CS_PIN) -#define ENABLE_BMP280 GPIO_ResetBits(BMP280_CS_GPIO, BMP280_CS_PIN) +#define DISABLE_BMP280 IOHi(bmp280CsPin) +#define ENABLE_BMP280 IOLo(bmp280CsPin) extern int32_t bmp280_up; extern int32_t bmp280_ut; +static IO_t bmp280CsPin = IO_NONE; + bool bmp280WriteRegister(uint8_t reg, uint8_t data) { ENABLE_BMP280; @@ -62,32 +64,13 @@ void bmp280SpiInit(void) return; } -#ifdef STM32F303 - RCC_AHBPeriphClockCmd(BMP280_CS_GPIO_CLK_PERIPHERAL, ENABLE); + bmp280CsPin = IOGetByTag(IO_TAG(BMP280_CS_PIN)); + IOInit(bmp280CsPin, OWNER_BARO, RESOURCE_SPI); + IOConfigGPIO(bmp280CsPin, IOCFG_OUT_PP); - GPIO_InitTypeDef GPIO_InitStructure; - GPIO_InitStructure.GPIO_Pin = BMP280_CS_PIN; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; + DISABLE_BMP280; - GPIO_Init(BMP280_CS_GPIO, &GPIO_InitStructure); -#endif - -#ifdef STM32F10X - RCC_APB2PeriphClockCmd(BMP280_CS_GPIO_CLK_PERIPHERAL, ENABLE); - - gpio_config_t gpio; - gpio.mode = Mode_Out_PP; - gpio.pin = BMP280_CS_PIN; - gpio.speed = Speed_50MHz; - gpioInit(BMP280_CS_GPIO, &gpio); -#endif - - GPIO_SetBits(BMP280_CS_GPIO, BMP280_CS_PIN); - - spiSetDivisor(BMP280_SPI_INSTANCE, SPI_9MHZ_CLOCK_DIVIDER); + spiSetDivisor(BMP280_SPI_INSTANCE, SPI_CLOCK_STANDARD); hardwareInitialised = true; } diff --git a/src/main/drivers/bus_i2c_stm32f10x.c b/src/main/drivers/bus_i2c_stm32f10x.c index a444332aba..c7e972b2d7 100644 --- a/src/main/drivers/bus_i2c_stm32f10x.c +++ b/src/main/drivers/bus_i2c_stm32f10x.c @@ -82,10 +82,10 @@ static void i2cUnstick(IO_t scl, IO_t sda); #endif static i2cDevice_t i2cHardwareMap[] = { - { .dev = I2C1, .scl = IO_TAG(I2C1_SCL), .sda = IO_TAG(I2C1_SDA), .rcc = RCC_APB1(I2C1), .overClock = false, .ev_irq = I2C1_EV_IRQn, .er_irq = I2C1_ER_IRQn }, - { .dev = I2C2, .scl = IO_TAG(I2C2_SCL), .sda = IO_TAG(I2C2_SDA), .rcc = RCC_APB1(I2C2), .overClock = false, .ev_irq = I2C2_EV_IRQn, .er_irq = I2C2_ER_IRQn }, + { .dev = I2C1, .scl = IO_TAG(I2C1_SCL), .sda = IO_TAG(I2C1_SDA), .rcc = RCC_APB1(I2C1), .overClock = I2C1_OVERCLOCK, .ev_irq = I2C1_EV_IRQn, .er_irq = I2C1_ER_IRQn }, + { .dev = I2C2, .scl = IO_TAG(I2C2_SCL), .sda = IO_TAG(I2C2_SDA), .rcc = RCC_APB1(I2C2), .overClock = I2C2_OVERCLOCK, .ev_irq = I2C2_EV_IRQn, .er_irq = I2C2_ER_IRQn }, #ifdef STM32F4 - { .dev = I2C3, .scl = IO_TAG(I2C3_SCL), .sda = IO_TAG(I2C3_SDA), .rcc = RCC_APB1(I2C3), .overClock = false, .ev_irq = I2C3_EV_IRQn, .er_irq = I2C3_ER_IRQn } + { .dev = I2C3, .scl = IO_TAG(I2C3_SCL), .sda = IO_TAG(I2C3_SDA), .rcc = RCC_APB1(I2C3), .overClock = I2C2_OVERCLOCK, .ev_irq = I2C3_EV_IRQn, .er_irq = I2C3_ER_IRQn } #endif }; @@ -396,7 +396,7 @@ void i2cInit(I2CDevice device) i2cUnstick(scl, sda); // Init pins -#if defined(STM32F40_41xxx) || defined(STM32F411xE) +#ifdef STM32F4 IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_I2C); IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_I2C); #else @@ -416,8 +416,7 @@ void i2cInit(I2CDevice device) if (i2c->overClock) { i2cInit.I2C_ClockSpeed = 800000; // 800khz Maximum speed tested on various boards without issues - } - else { + } else { i2cInit.I2C_ClockSpeed = 400000; // 400khz Operation according specs } diff --git a/src/main/drivers/bus_i2c_stm32f30x.c b/src/main/drivers/bus_i2c_stm32f30x.c index 8f9225ef74..c324d03e7a 100644 --- a/src/main/drivers/bus_i2c_stm32f30x.c +++ b/src/main/drivers/bus_i2c_stm32f30x.c @@ -54,8 +54,8 @@ static volatile uint16_t i2cErrorCount = 0; //static volatile uint16_t i2c2ErrorCount = 0; static i2cDevice_t i2cHardwareMap[] = { - { .dev = I2C1, .scl = IO_TAG(I2C1_SCL), .sda = IO_TAG(I2C1_SDA), .rcc = RCC_APB1(I2C1), .overClock = false }, - { .dev = I2C2, .scl = IO_TAG(I2C2_SCL), .sda = IO_TAG(I2C2_SDA), .rcc = RCC_APB1(I2C2), .overClock = false } + { .dev = I2C1, .scl = IO_TAG(I2C1_SCL), .sda = IO_TAG(I2C1_SDA), .rcc = RCC_APB1(I2C1), .overClock = I2C1_OVERCLOCK }, + { .dev = I2C2, .scl = IO_TAG(I2C2_SCL), .sda = IO_TAG(I2C2_SDA), .rcc = RCC_APB1(I2C2), .overClock = I2C2_OVERCLOCK } }; /////////////////////////////////////////////////////////////////////////////// @@ -64,190 +64,189 @@ static i2cDevice_t i2cHardwareMap[] = { uint32_t i2cTimeoutUserCallback(void) { - i2cErrorCount++; - return false; + i2cErrorCount++; + return false; } void i2cInit(I2CDevice device) { - i2cDevice_t *i2c; - i2c = &(i2cHardwareMap[device]); + i2cDevice_t *i2c; + i2c = &(i2cHardwareMap[device]); - I2C_TypeDef *I2Cx; - I2Cx = i2c->dev; + I2C_TypeDef *I2Cx; + I2Cx = i2c->dev; - IO_t scl = IOGetByTag(i2c->scl); - IO_t sda = IOGetByTag(i2c->sda); + IO_t scl = IOGetByTag(i2c->scl); + IO_t sda = IOGetByTag(i2c->sda); - RCC_ClockCmd(i2c->rcc, ENABLE); - RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK); + RCC_ClockCmd(i2c->rcc, ENABLE); + RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK); - IOConfigGPIOAF(scl, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_NOPULL), GPIO_AF_4); - IOConfigGPIOAF(sda, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_NOPULL), GPIO_AF_4); + IOConfigGPIOAF(scl, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_NOPULL), GPIO_AF_4); + IOConfigGPIOAF(sda, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_NOPULL), GPIO_AF_4); - I2C_InitTypeDef i2cInit = { - .I2C_Mode = I2C_Mode_I2C, - .I2C_AnalogFilter = I2C_AnalogFilter_Enable, - .I2C_DigitalFilter = 0x00, - .I2C_OwnAddress1 = 0x00, - .I2C_Ack = I2C_Ack_Enable, - .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, - .I2C_Timing = 0x00E0257A, // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10. - //.I2C_Timing = 0x8000050B; - }; + I2C_InitTypeDef i2cInit = { + .I2C_Mode = I2C_Mode_I2C, + .I2C_AnalogFilter = I2C_AnalogFilter_Enable, + .I2C_DigitalFilter = 0x00, + .I2C_OwnAddress1 = 0x00, + .I2C_Ack = I2C_Ack_Enable, + .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, + .I2C_Timing = i2c->overClock ? + 0x00500E30 : // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4. + 0x00E0257A, // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10. + //.I2C_Timing = 0x8000050B; + }; - if (i2c->overClock) { - i2cInit.I2C_Timing = 0x00500E30; // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4. - } - I2C_Init(I2Cx, &i2cInit); + I2C_Init(I2Cx, &i2cInit); - I2C_Cmd(I2Cx, ENABLE); + I2C_Cmd(I2Cx, ENABLE); } uint16_t i2cGetErrorCounter(void) { - return i2cErrorCount; + return i2cErrorCount; } bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data) { - addr_ <<= 1; + addr_ <<= 1; - I2C_TypeDef *I2Cx; - I2Cx = i2cHardwareMap[device].dev; + I2C_TypeDef *I2Cx; + I2Cx = i2cHardwareMap[device].dev; - /* Test on BUSY Flag */ - i2cTimeout = I2C_LONG_TIMEOUT; - while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) { - if ((i2cTimeout--) == 0) { - return i2cTimeoutUserCallback(); - } - } + /* Test on BUSY Flag */ + i2cTimeout = I2C_LONG_TIMEOUT; + while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) { + if ((i2cTimeout--) == 0) { + return i2cTimeoutUserCallback(); + } + } - /* Configure slave address, nbytes, reload, end mode and start or stop generation */ - I2C_TransferHandling(I2Cx, addr_, 1, I2C_Reload_Mode, I2C_Generate_Start_Write); + /* Configure slave address, nbytes, reload, end mode and start or stop generation */ + I2C_TransferHandling(I2Cx, addr_, 1, I2C_Reload_Mode, I2C_Generate_Start_Write); - /* Wait until TXIS flag is set */ - i2cTimeout = I2C_LONG_TIMEOUT; - while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) { - if ((i2cTimeout--) == 0) { - return i2cTimeoutUserCallback(); - } - } + /* Wait until TXIS flag is set */ + i2cTimeout = I2C_LONG_TIMEOUT; + while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) { + if ((i2cTimeout--) == 0) { + return i2cTimeoutUserCallback(); + } + } - /* Send Register address */ - I2C_SendData(I2Cx, (uint8_t) reg); + /* Send Register address */ + I2C_SendData(I2Cx, (uint8_t) reg); - /* Wait until TCR flag is set */ - i2cTimeout = I2C_LONG_TIMEOUT; - while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TCR) == RESET) - { - if ((i2cTimeout--) == 0) { - return i2cTimeoutUserCallback(); - } - } + /* Wait until TCR flag is set */ + i2cTimeout = I2C_LONG_TIMEOUT; + while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TCR) == RESET) + { + if ((i2cTimeout--) == 0) { + return i2cTimeoutUserCallback(); + } + } - /* Configure slave address, nbytes, reload, end mode and start or stop generation */ - I2C_TransferHandling(I2Cx, addr_, 1, I2C_AutoEnd_Mode, I2C_No_StartStop); + /* Configure slave address, nbytes, reload, end mode and start or stop generation */ + I2C_TransferHandling(I2Cx, addr_, 1, I2C_AutoEnd_Mode, I2C_No_StartStop); - /* Wait until TXIS flag is set */ - i2cTimeout = I2C_LONG_TIMEOUT; - while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) { - if ((i2cTimeout--) == 0) { - return i2cTimeoutUserCallback(); - } - } + /* Wait until TXIS flag is set */ + i2cTimeout = I2C_LONG_TIMEOUT; + while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) { + if ((i2cTimeout--) == 0) { + return i2cTimeoutUserCallback(); + } + } - /* Write data to TXDR */ - I2C_SendData(I2Cx, data); + /* Write data to TXDR */ + I2C_SendData(I2Cx, data); - /* Wait until STOPF flag is set */ - i2cTimeout = I2C_LONG_TIMEOUT; - while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) { - if ((i2cTimeout--) == 0) { - return i2cTimeoutUserCallback(); - } - } + /* Wait until STOPF flag is set */ + i2cTimeout = I2C_LONG_TIMEOUT; + while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) { + if ((i2cTimeout--) == 0) { + return i2cTimeoutUserCallback(); + } + } - /* Clear STOPF flag */ - I2C_ClearFlag(I2Cx, I2C_ICR_STOPCF); + /* Clear STOPF flag */ + I2C_ClearFlag(I2Cx, I2C_ICR_STOPCF); - return true; + return true; } bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf) { - addr_ <<= 1; + addr_ <<= 1; - I2C_TypeDef *I2Cx; - I2Cx = i2cHardwareMap[device].dev; + I2C_TypeDef *I2Cx; + I2Cx = i2cHardwareMap[device].dev; - /* Test on BUSY Flag */ - i2cTimeout = I2C_LONG_TIMEOUT; - while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) { - if ((i2cTimeout--) == 0) { - return i2cTimeoutUserCallback(); - } - } + /* Test on BUSY Flag */ + i2cTimeout = I2C_LONG_TIMEOUT; + while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) { + if ((i2cTimeout--) == 0) { + return i2cTimeoutUserCallback(); + } + } - /* Configure slave address, nbytes, reload, end mode and start or stop generation */ - I2C_TransferHandling(I2Cx, addr_, 1, I2C_SoftEnd_Mode, I2C_Generate_Start_Write); + /* Configure slave address, nbytes, reload, end mode and start or stop generation */ + I2C_TransferHandling(I2Cx, addr_, 1, I2C_SoftEnd_Mode, I2C_Generate_Start_Write); - /* Wait until TXIS flag is set */ - i2cTimeout = I2C_LONG_TIMEOUT; - while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) { - if ((i2cTimeout--) == 0) { - return i2cTimeoutUserCallback(); - } - } + /* Wait until TXIS flag is set */ + i2cTimeout = I2C_LONG_TIMEOUT; + while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) { + if ((i2cTimeout--) == 0) { + return i2cTimeoutUserCallback(); + } + } - /* Send Register address */ - I2C_SendData(I2Cx, (uint8_t) reg); + /* Send Register address */ + I2C_SendData(I2Cx, (uint8_t) reg); - /* Wait until TC flag is set */ - i2cTimeout = I2C_LONG_TIMEOUT; - while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TC) == RESET) { - if ((i2cTimeout--) == 0) { - return i2cTimeoutUserCallback(); - } - } + /* Wait until TC flag is set */ + i2cTimeout = I2C_LONG_TIMEOUT; + while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TC) == RESET) { + if ((i2cTimeout--) == 0) { + return i2cTimeoutUserCallback(); + } + } - /* Configure slave address, nbytes, reload, end mode and start or stop generation */ - I2C_TransferHandling(I2Cx, addr_, len, I2C_AutoEnd_Mode, I2C_Generate_Start_Read); + /* Configure slave address, nbytes, reload, end mode and start or stop generation */ + I2C_TransferHandling(I2Cx, addr_, len, I2C_AutoEnd_Mode, I2C_Generate_Start_Read); - /* Wait until all data are received */ - while (len) { - /* Wait until RXNE flag is set */ - i2cTimeout = I2C_LONG_TIMEOUT; - while (I2C_GetFlagStatus(I2Cx, I2C_ISR_RXNE) == RESET) { - if ((i2cTimeout--) == 0) { - return i2cTimeoutUserCallback(); - } - } + /* Wait until all data are received */ + while (len) { + /* Wait until RXNE flag is set */ + i2cTimeout = I2C_LONG_TIMEOUT; + while (I2C_GetFlagStatus(I2Cx, I2C_ISR_RXNE) == RESET) { + if ((i2cTimeout--) == 0) { + return i2cTimeoutUserCallback(); + } + } - /* Read data from RXDR */ - *buf = I2C_ReceiveData(I2Cx); - /* Point to the next location where the byte read will be saved */ - buf++; + /* Read data from RXDR */ + *buf = I2C_ReceiveData(I2Cx); + /* Point to the next location where the byte read will be saved */ + buf++; - /* Decrement the read bytes counter */ - len--; - } + /* Decrement the read bytes counter */ + len--; + } - /* Wait until STOPF flag is set */ - i2cTimeout = I2C_LONG_TIMEOUT; - while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) { - if ((i2cTimeout--) == 0) { - return i2cTimeoutUserCallback(); - } - } + /* Wait until STOPF flag is set */ + i2cTimeout = I2C_LONG_TIMEOUT; + while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) { + if ((i2cTimeout--) == 0) { + return i2cTimeoutUserCallback(); + } + } - /* Clear STOPF flag */ - I2C_ClearFlag(I2Cx, I2C_ICR_STOPCF); + /* Clear STOPF flag */ + I2C_ClearFlag(I2Cx, I2C_ICR_STOPCF); - /* If all operations OK */ - return true; + /* If all operations OK */ + return true; } #endif diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c index c4d53145cc..4ad5e6077b 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -36,7 +36,7 @@ #define GPIO_AF_SPI2 GPIO_AF_5 #endif #ifndef GPIO_AF_SPI3 -#define GPIO_AF_SPI3 GPIO_AF_6 +#define GPIO_AF_SPI3 GPIO_AF_6 #endif #endif @@ -72,169 +72,169 @@ #endif static spiDevice_t spiHardwareMap[] = { -#if defined(STM32F10X) - { .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .af = 0, false }, - { .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .af = 0, false }, +#if defined(STM32F1) + { .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .af = 0, false }, + { .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .af = 0, false }, #else - { .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .af = GPIO_AF_SPI1, false }, - { .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .af = GPIO_AF_SPI2, false }, + { .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .af = GPIO_AF_SPI1, false }, + { .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .af = GPIO_AF_SPI2, false }, #endif -#if defined(STM32F303xC) || defined(STM32F40_41xxx) || defined(STM32F411xE) - { .dev = SPI3, .nss = IO_TAG(SPI3_NSS_PIN), .sck = IO_TAG(SPI3_SCK_PIN), .miso = IO_TAG(SPI3_MISO_PIN), .mosi = IO_TAG(SPI3_MOSI_PIN), .rcc = RCC_APB1(SPI3), .af = GPIO_AF_SPI3, false } +#if defined(STM32F3) || defined(STM32F4) + { .dev = SPI3, .nss = IO_TAG(SPI3_NSS_PIN), .sck = IO_TAG(SPI3_SCK_PIN), .miso = IO_TAG(SPI3_MISO_PIN), .mosi = IO_TAG(SPI3_MOSI_PIN), .rcc = RCC_APB1(SPI3), .af = GPIO_AF_SPI3, false } #endif }; SPIDevice spiDeviceByInstance(SPI_TypeDef *instance) { - if (instance == SPI1) - return SPIDEV_1; + if (instance == SPI1) + return SPIDEV_1; - if (instance == SPI2) - return SPIDEV_2; + if (instance == SPI2) + return SPIDEV_2; - if (instance == SPI3) - return SPIDEV_3; + if (instance == SPI3) + return SPIDEV_3; - return SPIINVALID; + return SPIINVALID; } void spiInitDevice(SPIDevice device) { - SPI_InitTypeDef spiInit; + SPI_InitTypeDef spiInit; - spiDevice_t *spi = &(spiHardwareMap[device]); + spiDevice_t *spi = &(spiHardwareMap[device]); #ifdef SDCARD_SPI_INSTANCE - if (spi->dev == SDCARD_SPI_INSTANCE) - spi->sdcard = true; + if (spi->dev == SDCARD_SPI_INSTANCE) + spi->sdcard = true; #endif - // Enable SPI clock - RCC_ClockCmd(spi->rcc, ENABLE); - RCC_ResetCmd(spi->rcc, ENABLE); + // Enable SPI clock + RCC_ClockCmd(spi->rcc, ENABLE); + RCC_ResetCmd(spi->rcc, ENABLE); - IOInit(IOGetByTag(spi->sck), OWNER_SYSTEM, RESOURCE_SPI); - IOInit(IOGetByTag(spi->miso), OWNER_SYSTEM, RESOURCE_SPI); - IOInit(IOGetByTag(spi->mosi), OWNER_SYSTEM, RESOURCE_SPI); + IOInit(IOGetByTag(spi->sck), OWNER_SYSTEM, RESOURCE_SPI); + IOInit(IOGetByTag(spi->miso), OWNER_SYSTEM, RESOURCE_SPI); + IOInit(IOGetByTag(spi->mosi), OWNER_SYSTEM, RESOURCE_SPI); #if defined(STM32F303xC) || defined(STM32F4) - if (spi->sdcard) { - IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG, spi->af); - IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG, spi->af); - } - else { - IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af); - IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_CFG, spi->af); - } - IOConfigGPIOAF(IOGetByTag(spi->mosi), SPI_IO_AF_CFG, spi->af); + if (spi->sdcard) { + IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG, spi->af); + IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG, spi->af); + } + else { + IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af); + IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_CFG, spi->af); + } + IOConfigGPIOAF(IOGetByTag(spi->mosi), SPI_IO_AF_CFG, spi->af); - if (spi->nss) - IOConfigGPIOAF(IOGetByTag(spi->nss), SPI_IO_CS_CFG, spi->af); + if (spi->nss) + IOConfigGPIOAF(IOGetByTag(spi->nss), SPI_IO_CS_CFG, spi->af); #endif #if defined(STM32F10X) - IOConfigGPIO(IOGetByTag(spi->sck), SPI_IO_AF_CFG); - IOConfigGPIO(IOGetByTag(spi->miso), SPI_IO_AF_CFG); - IOConfigGPIO(IOGetByTag(spi->mosi), SPI_IO_AF_CFG); + IOConfigGPIO(IOGetByTag(spi->sck), SPI_IO_AF_CFG); + IOConfigGPIO(IOGetByTag(spi->miso), SPI_IO_AF_CFG); + IOConfigGPIO(IOGetByTag(spi->mosi), SPI_IO_AF_CFG); - if (spi->nss) - IOConfigGPIO(IOGetByTag(spi->nss), SPI_IO_CS_CFG); + if (spi->nss) + IOConfigGPIO(IOGetByTag(spi->nss), SPI_IO_CS_CFG); #endif - // Init SPI hardware - SPI_I2S_DeInit(spi->dev); + // Init SPI hardware + SPI_I2S_DeInit(spi->dev); - spiInit.SPI_Mode = SPI_Mode_Master; - spiInit.SPI_Direction = SPI_Direction_2Lines_FullDuplex; - spiInit.SPI_DataSize = SPI_DataSize_8b; - spiInit.SPI_NSS = SPI_NSS_Soft; - spiInit.SPI_FirstBit = SPI_FirstBit_MSB; - spiInit.SPI_CRCPolynomial = 7; - spiInit.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8; + spiInit.SPI_Mode = SPI_Mode_Master; + spiInit.SPI_Direction = SPI_Direction_2Lines_FullDuplex; + spiInit.SPI_DataSize = SPI_DataSize_8b; + spiInit.SPI_NSS = SPI_NSS_Soft; + spiInit.SPI_FirstBit = SPI_FirstBit_MSB; + spiInit.SPI_CRCPolynomial = 7; + spiInit.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8; - if (spi->sdcard) { - spiInit.SPI_CPOL = SPI_CPOL_Low; - spiInit.SPI_CPHA = SPI_CPHA_1Edge; - } - else { - spiInit.SPI_CPOL = SPI_CPOL_High; - spiInit.SPI_CPHA = SPI_CPHA_2Edge; - } + if (spi->sdcard) { + spiInit.SPI_CPOL = SPI_CPOL_Low; + spiInit.SPI_CPHA = SPI_CPHA_1Edge; + } + else { + spiInit.SPI_CPOL = SPI_CPOL_High; + spiInit.SPI_CPHA = SPI_CPHA_2Edge; + } #ifdef STM32F303xC - // Configure for 8-bit reads. - SPI_RxFIFOThresholdConfig(spi->dev, SPI_RxFIFOThreshold_QF); + // Configure for 8-bit reads. + SPI_RxFIFOThresholdConfig(spi->dev, SPI_RxFIFOThreshold_QF); #endif - SPI_Init(spi->dev, &spiInit); - SPI_Cmd(spi->dev, ENABLE); + SPI_Init(spi->dev, &spiInit); + SPI_Cmd(spi->dev, ENABLE); - if (spi->nss) - IOHi(IOGetByTag(spi->nss)); + if (spi->nss) + IOHi(IOGetByTag(spi->nss)); } bool spiInit(SPIDevice device) { - switch (device) - { - case SPIINVALID: - return false; - case SPIDEV_1: + switch (device) + { + case SPIINVALID: + return false; + case SPIDEV_1: #ifdef USE_SPI_DEVICE_1 - spiInitDevice(device); - return true; + spiInitDevice(device); + return true; #else - break; + break; #endif - case SPIDEV_2: + case SPIDEV_2: #ifdef USE_SPI_DEVICE_2 - spiInitDevice(device); - return true; + spiInitDevice(device); + return true; #else - break; + break; #endif - case SPIDEV_3: + case SPIDEV_3: #if defined(USE_SPI_DEVICE_3) && (defined(STM32F303xC) || defined(STM32F4)) - spiInitDevice(device); - return true; + spiInitDevice(device); + return true; #else - break; + break; #endif - } - return false; + } + return false; } uint32_t spiTimeoutUserCallback(SPI_TypeDef *instance) { - SPIDevice device = spiDeviceByInstance(instance); - if (device == SPIINVALID) - return -1; - spiHardwareMap[device].errorCount++; - return spiHardwareMap[device].errorCount; + SPIDevice device = spiDeviceByInstance(instance); + if (device == SPIINVALID) + return -1; + spiHardwareMap[device].errorCount++; + return spiHardwareMap[device].errorCount; } // return uint8_t value or -1 when failure uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t data) { - uint16_t spiTimeout = 1000; + uint16_t spiTimeout = 1000; - while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET) - if ((spiTimeout--) == 0) - return spiTimeoutUserCallback(instance); + while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET) + if ((spiTimeout--) == 0) + return spiTimeoutUserCallback(instance); #ifdef STM32F303xC - SPI_SendData8(instance, data); + SPI_SendData8(instance, data); #else - SPI_I2S_SendData(instance, data); + SPI_I2S_SendData(instance, data); #endif - spiTimeout = 1000; - while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET) - if ((spiTimeout--) == 0) - return spiTimeoutUserCallback(instance); + spiTimeout = 1000; + while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET) + if ((spiTimeout--) == 0) + return spiTimeoutUserCallback(instance); #ifdef STM32F303xC - return ((uint8_t)SPI_ReceiveData8(instance)); + return ((uint8_t)SPI_ReceiveData8(instance)); #else - return ((uint8_t)SPI_I2S_ReceiveData(instance)); + return ((uint8_t)SPI_I2S_ReceiveData(instance)); #endif } @@ -244,119 +244,115 @@ uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t data) bool spiIsBusBusy(SPI_TypeDef *instance) { #ifdef STM32F303xC - return SPI_GetTransmissionFIFOStatus(instance) != SPI_TransmissionFIFOStatus_Empty || SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_BSY) == SET; + return SPI_GetTransmissionFIFOStatus(instance) != SPI_TransmissionFIFOStatus_Empty || SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_BSY) == SET; #else - return SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET || SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_BSY) == SET; + return SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET || SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_BSY) == SET; #endif } bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len) { - uint16_t spiTimeout = 1000; + uint16_t spiTimeout = 1000; - uint8_t b; - instance->DR; - while (len--) { - b = in ? *(in++) : 0xFF; - while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET) { - if ((spiTimeout--) == 0) - return spiTimeoutUserCallback(instance); - } + uint8_t b; + instance->DR; + while (len--) { + b = in ? *(in++) : 0xFF; + while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET) { + if ((spiTimeout--) == 0) + return spiTimeoutUserCallback(instance); + } #ifdef STM32F303xC - SPI_SendData8(instance, b); - //SPI_I2S_SendData16(instance, b); + SPI_SendData8(instance, b); #else - SPI_I2S_SendData(instance, b); + SPI_I2S_SendData(instance, b); #endif - spiTimeout = 1000; - while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET) { - if ((spiTimeout--) == 0) - return spiTimeoutUserCallback(instance); - } + spiTimeout = 1000; + while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET) { + if ((spiTimeout--) == 0) + return spiTimeoutUserCallback(instance); + } #ifdef STM32F303xC - b = SPI_ReceiveData8(instance); - //b = SPI_I2S_ReceiveData16(instance); + b = SPI_ReceiveData8(instance); #else - b = SPI_I2S_ReceiveData(instance); + b = SPI_I2S_ReceiveData(instance); #endif - if (out) - *(out++) = b; - } + if (out) + *(out++) = b; + } - return true; + return true; } - void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor) { #define BR_CLEAR_MASK 0xFFC7 - uint16_t tempRegister; + uint16_t tempRegister; - SPI_Cmd(instance, DISABLE); + SPI_Cmd(instance, DISABLE); - tempRegister = instance->CR1; + tempRegister = instance->CR1; - switch (divisor) { - case 2: - tempRegister &= BR_CLEAR_MASK; - tempRegister |= SPI_BaudRatePrescaler_2; - break; + switch (divisor) { + case 2: + tempRegister &= BR_CLEAR_MASK; + tempRegister |= SPI_BaudRatePrescaler_2; + break; - case 4: - tempRegister &= BR_CLEAR_MASK; - tempRegister |= SPI_BaudRatePrescaler_4; - break; + case 4: + tempRegister &= BR_CLEAR_MASK; + tempRegister |= SPI_BaudRatePrescaler_4; + break; - case 8: - tempRegister &= BR_CLEAR_MASK; - tempRegister |= SPI_BaudRatePrescaler_8; - break; + case 8: + tempRegister &= BR_CLEAR_MASK; + tempRegister |= SPI_BaudRatePrescaler_8; + break; - case 16: - tempRegister &= BR_CLEAR_MASK; - tempRegister |= SPI_BaudRatePrescaler_16; - break; + case 16: + tempRegister &= BR_CLEAR_MASK; + tempRegister |= SPI_BaudRatePrescaler_16; + break; - case 32: - tempRegister &= BR_CLEAR_MASK; - tempRegister |= SPI_BaudRatePrescaler_32; - break; + case 32: + tempRegister &= BR_CLEAR_MASK; + tempRegister |= SPI_BaudRatePrescaler_32; + break; - case 64: - tempRegister &= BR_CLEAR_MASK; - tempRegister |= SPI_BaudRatePrescaler_64; - break; + case 64: + tempRegister &= BR_CLEAR_MASK; + tempRegister |= SPI_BaudRatePrescaler_64; + break; - case 128: - tempRegister &= BR_CLEAR_MASK; - tempRegister |= SPI_BaudRatePrescaler_128; - break; + case 128: + tempRegister &= BR_CLEAR_MASK; + tempRegister |= SPI_BaudRatePrescaler_128; + break; - case 256: - tempRegister &= BR_CLEAR_MASK; - tempRegister |= SPI_BaudRatePrescaler_256; - break; - } + case 256: + tempRegister &= BR_CLEAR_MASK; + tempRegister |= SPI_BaudRatePrescaler_256; + break; + } - instance->CR1 = tempRegister; + instance->CR1 = tempRegister; - SPI_Cmd(instance, ENABLE); + SPI_Cmd(instance, ENABLE); } uint16_t spiGetErrorCounter(SPI_TypeDef *instance) { - SPIDevice device = spiDeviceByInstance(instance); - if (device == SPIINVALID) - return 0; - return spiHardwareMap[device].errorCount; + SPIDevice device = spiDeviceByInstance(instance); + if (device == SPIINVALID) + return 0; + return spiHardwareMap[device].errorCount; } void spiResetErrorCounter(SPI_TypeDef *instance) { - SPIDevice device = spiDeviceByInstance(instance); - if (device != SPIINVALID) - spiHardwareMap[device].errorCount = 0; + SPIDevice device = spiDeviceByInstance(instance); + if (device != SPIINVALID) + spiHardwareMap[device].errorCount = 0; } - diff --git a/src/main/drivers/bus_spi.h b/src/main/drivers/bus_spi.h index 1d5eca6bc0..d408eac2f7 100644 --- a/src/main/drivers/bus_spi.h +++ b/src/main/drivers/bus_spi.h @@ -17,41 +17,39 @@ #pragma once -#define SPI_0_28125MHZ_CLOCK_DIVIDER 256 -#define SPI_0_5625MHZ_CLOCK_DIVIDER 128 -#define SPI_18MHZ_CLOCK_DIVIDER 2 -#define SPI_9MHZ_CLOCK_DIVIDER 4 - #include #include "io.h" #include "rcc.h" -#if defined(STM32F40_41xxx) || defined (STM32F411xE) || defined(STM32F303xC) -#define SPI_IO_AF_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL) -#define SPI_IO_AF_SCK_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_DOWN) -#define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP) -#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL) -#elif defined(STM32F10X) -#define SPI_IO_AF_CFG IO_CONFIG(GPIO_Mode_AF_OD, GPIO_Speed_50MHz) -#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_Out_OD, GPIO_Speed_50MHz) +#if defined(STM32F4) || defined(STM32F3) +#define SPI_IO_AF_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL) +#define SPI_IO_AF_SCK_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_DOWN) +#define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP) +#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL) +#elif defined(STM32F1) +#define SPI_IO_AF_CFG IO_CONFIG(GPIO_Mode_AF_OD, GPIO_Speed_50MHz) +#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_Out_OD, GPIO_Speed_50MHz) #else #error "Unknown processor" #endif -#if defined(STM32F40_41xxx) || defined (STM32F411xE) - -#define SPI_SLOW_CLOCK 128 //00.65625 MHz -#define SPI_STANDARD_CLOCK 8 //11.50000 MHz -#define SPI_FAST_CLOCK 4 //21.00000 MHz -#define SPI_ULTRAFAST_CLOCK 2 //42.00000 MHz +/* + Flash M25p16 tolerates 20mhz, SPI_CLOCK_FAST should sit around 20 or less. +*/ +typedef enum { + SPI_CLOCK_INITIALIZATON = 256, +#if defined(STM32F4) + SPI_CLOCK_SLOW = 128, //00.65625 MHz + SPI_CLOCK_STANDARD = 8, //10.50000 MHz + SPI_CLOCK_FAST = 4, //21.00000 MHz + SPI_CLOCK_ULTRAFAST = 2, //42.00000 MHz #else - -#define SPI_SLOW_CLOCK 128 //00.56250 MHz -#define SPI_STANDARD_CLOCK 4 //09.00000 MHz -#define SPI_FAST_CLOCK 2 //18.00000 MHz -#define SPI_ULTRAFAST_CLOCK 2 //18.00000 MHz - + SPI_CLOCK_SLOW = 128, //00.56250 MHz + SPI_CLOCK_STANDARD = 4, //09.00000 MHz + SPI_CLOCK_FAST = 2, //18.00000 MHz + SPI_CLOCK_ULTRAFAST = 2, //18.00000 MHz #endif +} SPIClockDivider_e; typedef enum SPIDevice { SPIINVALID = -1, diff --git a/src/main/drivers/compass_ak8963.c b/src/main/drivers/compass_ak8963.c index 726f4f85a1..7b60fe5c46 100644 --- a/src/main/drivers/compass_ak8963.c +++ b/src/main/drivers/compass_ak8963.c @@ -33,6 +33,7 @@ #include "gpio.h" #include "exti.h" #include "bus_i2c.h" +#include "bus_spi.h" #include "sensors/boardalignment.h" #include "sensors/sensors.h" @@ -42,7 +43,9 @@ #include "accgyro.h" #include "accgyro_mpu.h" +#include "accgyro_mpu6500.h" #include "accgyro_spi_mpu6500.h" +#include "accgyro_spi_mpu9250.h" #include "compass_ak8963.h" // This sensor is available in MPU-9250. @@ -83,18 +86,10 @@ #define CNTL_MODE_SELF_TEST 0x08 #define CNTL_MODE_FUSE_ROM 0x0F -typedef bool (*ak8963ReadRegisterFunc)(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *buf); -typedef bool (*ak8963WriteRegisterFunc)(uint8_t addr_, uint8_t reg_, uint8_t data); - -typedef struct ak8963Configuration_s { - ak8963ReadRegisterFunc read; - ak8963WriteRegisterFunc write; -} ak8963Configuration_t; - -ak8963Configuration_t ak8963config; static float magGain[3] = { 1.0f, 1.0f, 1.0f }; // FIXME pretend we have real MPU9250 support +// Is an separate MPU9250 driver really needed? The GYRO/ACC part between MPU6500 and MPU9250 is exactly the same. #if defined(MPU6500_SPI_INSTANCE) && !defined(MPU9250_SPI_INSTANCE) #define MPU9250_SPI_INSTANCE #define verifympu9250WriteRegister mpu6500WriteRegister @@ -102,30 +97,7 @@ static float magGain[3] = { 1.0f, 1.0f, 1.0f }; #define mpu9250ReadRegister mpu6500ReadRegister #endif -#ifdef USE_SPI -bool ak8963SPIRead(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *buf) -{ - mpu6500WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_ | READ_FLAG); // set I2C slave address for read - mpu6500WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register - mpu6500WriteRegister(MPU_RA_I2C_SLV0_CTRL, len_ | 0x80); // read number of bytes - delay(8); - __disable_irq(); - mpu6500ReadRegister(MPU_RA_EXT_SENS_DATA_00, len_, buf); // read I2C - __enable_irq(); - return true; -} - -bool ak8963SPIWrite(uint8_t addr_, uint8_t reg_, uint8_t data) -{ - mpu6500WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_); // set I2C slave address for write - mpu6500WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register - mpu6500WriteRegister(MPU_RA_I2C_SLV0_DO, data); // set I2C salve value - mpu6500WriteRegister(MPU_RA_I2C_SLV0_CTRL, 0x81); // write 1 byte - return true; -} -#endif - -#ifdef SPRACINGF3EVO +#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE) typedef struct queuedReadState_s { bool waiting; @@ -133,9 +105,36 @@ typedef struct queuedReadState_s { uint32_t readStartedAt; // time read was queued in micros. } queuedReadState_t; +typedef enum { + CHECK_STATUS = 0, + WAITING_FOR_STATUS, + WAITING_FOR_DATA +} ak8963ReadState_e; + static queuedReadState_t queuedRead = { false, 0, 0}; -bool ak8963SPIStartRead(uint8_t addr_, uint8_t reg_, uint8_t len_) +bool ak8963SensorRead(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *buf) +{ + verifympu9250WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_ | READ_FLAG); // set I2C slave address for read + verifympu9250WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register + verifympu9250WriteRegister(MPU_RA_I2C_SLV0_CTRL, len_ | 0x80); // read number of bytes + delay(10); + __disable_irq(); + mpu9250ReadRegister(MPU_RA_EXT_SENS_DATA_00, len_, buf); // read I2C + __enable_irq(); + return true; +} + +bool ak8963SensorWrite(uint8_t addr_, uint8_t reg_, uint8_t data) +{ + verifympu9250WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_); // set I2C slave address for write + verifympu9250WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register + verifympu9250WriteRegister(MPU_RA_I2C_SLV0_DO, data); // set I2C salve value + verifympu9250WriteRegister(MPU_RA_I2C_SLV0_CTRL, 0x81); // write 1 byte + return true; +} + +bool ak8963SensorStartRead(uint8_t addr_, uint8_t reg_, uint8_t len_) { if (queuedRead.waiting) { return false; @@ -153,7 +152,7 @@ bool ak8963SPIStartRead(uint8_t addr_, uint8_t reg_, uint8_t len_) return true; } -static uint32_t ak8963SPIQueuedReadTimeRemaining(void) +static uint32_t ak8963SensorQueuedReadTimeRemaining(void) { if (!queuedRead.waiting) { return 0; @@ -170,9 +169,9 @@ static uint32_t ak8963SPIQueuedReadTimeRemaining(void) return timeRemaining; } -bool ak8963SPICompleteRead(uint8_t *buf) +bool ak8963SensorCompleteRead(uint8_t *buf) { - uint32_t timeRemaining = ak8963SPIQueuedReadTimeRemaining(); + uint32_t timeRemaining = ak8963SensorQueuedReadTimeRemaining(); if (timeRemaining > 0) { delayMicroseconds(timeRemaining); @@ -183,18 +182,15 @@ bool ak8963SPICompleteRead(uint8_t *buf) mpu9250ReadRegister(MPU_RA_EXT_SENS_DATA_00, queuedRead.len, buf); // read I2C buffer return true; } - -#endif - -#ifdef USE_I2C -bool c_i2cWrite(uint8_t addr_, uint8_t reg_, uint8_t data) +#else +bool ak8963SensorRead(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf) { - return i2cWrite(MAG_I2C_INSTANCE, addr_, reg_, data); + return i2cRead(MAG_I2C_INSTANCE, addr_, reg_, len, buf); } -bool c_i2cRead(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf) +bool ak8963SensorWrite(uint8_t addr_, uint8_t reg_, uint8_t data) { - return i2cRead(MAG_I2C_INSTANCE, addr_, reg_, len, buf); + return i2cWrite(MAG_I2C_INSTANCE, addr_, reg_, data); } #endif @@ -203,43 +199,28 @@ bool ak8963Detect(mag_t *mag) bool ack = false; uint8_t sig = 0; -#ifdef USE_I2C - // check for AK8963 on I2C bus - ack = i2cRead(MAG_I2C_INSTANCE, AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_WHO_AM_I, 1, &sig); +#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE) + // initialze I2C master via SPI bus (MPU9250) + + ack = verifympu9250WriteRegister(MPU_RA_INT_PIN_CFG, 0x10); // INT_ANYRD_2CLEAR + delay(10); + + ack = verifympu9250WriteRegister(MPU_RA_I2C_MST_CTRL, 0x0D); // I2C multi-master / 400kHz + delay(10); + + ack = verifympu9250WriteRegister(MPU_RA_USER_CTRL, 0x30); // I2C master mode, SPI mode only + delay(10); +#endif + + // check for AK8963 + ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_WHO_AM_I, 1, &sig); if (ack && sig == AK8963_Device_ID) // 0x48 / 01001000 / 'H' { - ak8963config.read = c_i2cRead; - ak8963config.write = c_i2cWrite; mag->init = ak8963Init; mag->read = ak8963Read; return true; } -#endif - -#ifdef USE_SPI - // check for AK8963 on I2C master via SPI bus (as part of MPU9250) - - ack = mpu6500WriteRegister(MPU_RA_INT_PIN_CFG, 0x10); // INT_ANYRD_2CLEAR - delay(10); - - ack = mpu6500WriteRegister(MPU_RA_I2C_MST_CTRL, 0x0D); // I2C multi-master / 400kHz - delay(10); - - ack = mpu6500WriteRegister(MPU_RA_USER_CTRL, 0x30); // I2C master mode, SPI mode only - delay(10); - - ack = ak8963SPIRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_WHO_AM_I, 1, &sig); - if (ack && sig == AK8963_Device_ID) // 0x48 / 01001000 / 'H' - { - ak8963config.read = ak8963SPIRead; - ak8963config.write = ak8963SPIWrite; - mag->init = ak8963Init; - mag->read = ak8963Read; - - return true; - } -#endif return false; } @@ -250,49 +231,43 @@ void ak8963Init() uint8_t calibration[3]; uint8_t status; - ack = ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_POWER_DOWN); // power down before entering fuse mode + ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_POWER_DOWN); // power down before entering fuse mode delay(20); - ack = ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_FUSE_ROM); // Enter Fuse ROM access mode + ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_FUSE_ROM); // Enter Fuse ROM access mode delay(10); - ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_ASAX, sizeof(calibration), calibration); // Read the x-, y-, and z-axis calibration values + ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_ASAX, sizeof(calibration), calibration); // Read the x-, y-, and z-axis calibration values delay(10); magGain[X] = (((((float)(int8_t)calibration[X] - 128) / 256) + 1) * 30); magGain[Y] = (((((float)(int8_t)calibration[Y] - 128) / 256) + 1) * 30); magGain[Z] = (((((float)(int8_t)calibration[Z] - 128) / 256) + 1) * 30); - ack = ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_POWER_DOWN); // power down after reading. + ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_POWER_DOWN); // power down after reading. delay(10); // Clear status registers - ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1, &status); - ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS2, 1, &status); + ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1, &status); + ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS2, 1, &status); // Trigger first measurement -#ifdef SPRACINGF3EVO - ack = ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_CONT1); +#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE) + ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_CONT1); #else - ack = ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE); + ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE); #endif } -typedef enum { - CHECK_STATUS = 0, - WAITING_FOR_STATUS, - WAITING_FOR_DATA -} ak8963ReadState_e; - bool ak8963Read(int16_t *magData) { - bool ack; + bool ack = false; uint8_t buf[7]; -#ifdef SPRACINGF3EVO +#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE) - // we currently need a different approach on the SPRacingF3EVO which has an MPU9250 connected via SPI. - // we cannot use the ak8963SPIRead() method, it is to slow and blocks for far too long. + // we currently need a different approach for the MPU9250 connected via SPI. + // we cannot use the ak8963SensorRead() method for SPI, it is to slow and blocks for far too long. static ak8963ReadState_e state = CHECK_STATUS; @@ -301,17 +276,17 @@ bool ak8963Read(int16_t *magData) restart: switch (state) { case CHECK_STATUS: - ak8963SPIStartRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1); + ak8963SensorStartRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1); state++; return false; case WAITING_FOR_STATUS: { - uint32_t timeRemaining = ak8963SPIQueuedReadTimeRemaining(); + uint32_t timeRemaining = ak8963SensorQueuedReadTimeRemaining(); if (timeRemaining) { return false; } - ack = ak8963SPICompleteRead(&buf[0]); + ack = ak8963SensorCompleteRead(&buf[0]); uint8_t status = buf[0]; @@ -327,7 +302,7 @@ restart: // read the 6 bytes of data and the status2 register - ak8963SPIStartRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_HXL, 7); + ak8963SensorStartRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_HXL, 7); state++; @@ -335,31 +310,16 @@ restart: } case WAITING_FOR_DATA: { - uint32_t timeRemaining = ak8963SPIQueuedReadTimeRemaining(); + uint32_t timeRemaining = ak8963SensorQueuedReadTimeRemaining(); if (timeRemaining) { return false; } - ack = ak8963SPICompleteRead(&buf[0]); - - uint8_t status2 = buf[6]; - if (!ack || (status2 & STATUS2_DATA_ERROR) || (status2 & STATUS2_MAG_SENSOR_OVERFLOW)) { - return false; - } - - magData[X] = -(int16_t)(buf[1] << 8 | buf[0]) * magGain[X]; - magData[Y] = -(int16_t)(buf[3] << 8 | buf[2]) * magGain[Y]; - magData[Z] = -(int16_t)(buf[5] << 8 | buf[4]) * magGain[Z]; - - state = CHECK_STATUS; - - return true; + ack = ak8963SensorCompleteRead(&buf[0]); } } - - return false; #else - ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1, &buf[0]); + ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1, &buf[0]); uint8_t status = buf[0]; @@ -367,8 +327,8 @@ restart: return false; } - ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_HXL, 7, &buf[0]); - + ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_HXL, 7, &buf[0]); +#endif uint8_t status2 = buf[6]; if (!ack || (status2 & STATUS2_DATA_ERROR) || (status2 & STATUS2_MAG_SENSOR_OVERFLOW)) { return false; @@ -378,6 +338,10 @@ restart: magData[Y] = -(int16_t)(buf[3] << 8 | buf[2]) * magGain[Y]; magData[Z] = -(int16_t)(buf[5] << 8 | buf[4]) * magGain[Z]; - return ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE); // start reading again +#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE) + state = CHECK_STATUS; + return true; +#else + return ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE); // start reading again #endif } diff --git a/src/main/drivers/exti.h b/src/main/drivers/exti.h index 4d0fef446c..8071c65e33 100644 --- a/src/main/drivers/exti.h +++ b/src/main/drivers/exti.h @@ -22,7 +22,7 @@ // old EXTI interface, to be replaced typedef struct extiConfig_s { - ioTag_t io; + ioTag_t tag; } extiConfig_t; typedef struct extiCallbackRec_s extiCallbackRec_t; diff --git a/src/main/drivers/flash_m25p16.c b/src/main/drivers/flash_m25p16.c index 7640ab768f..1063debae6 100644 --- a/src/main/drivers/flash_m25p16.c +++ b/src/main/drivers/flash_m25p16.c @@ -95,7 +95,7 @@ static void m25p16_writeEnable() static uint8_t m25p16_readStatus() { - uint8_t command[2] = {M25P16_INSTRUCTION_READ_STATUS_REG, 0}; + uint8_t command[2] = { M25P16_INSTRUCTION_READ_STATUS_REG, 0 }; uint8_t in[2]; ENABLE_M25P16; @@ -134,7 +134,7 @@ bool m25p16_waitForReady(uint32_t timeoutMillis) */ static bool m25p16_readIdentification() { - uint8_t out[] = { M25P16_INSTRUCTION_RDID, 0, 0, 0}; + uint8_t out[] = { M25P16_INSTRUCTION_RDID, 0, 0, 0 }; uint8_t in[4]; uint32_t chipID; @@ -210,7 +210,7 @@ bool m25p16_init() #ifndef M25P16_SPI_SHARED //Maximum speed for standard READ command is 20mHz, other commands tolerate 25mHz - spiSetDivisor(M25P16_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER); + spiSetDivisor(M25P16_SPI_INSTANCE, SPI_CLOCK_FAST); #endif return m25p16_readIdentification(); diff --git a/src/main/drivers/max7456.c b/src/main/drivers/max7456.c index fa2fbc245e..239c294125 100644 --- a/src/main/drivers/max7456.c +++ b/src/main/drivers/max7456.c @@ -147,7 +147,8 @@ void MAX7456_DMA_IRQ_HANDLER_FUNCTION (void) { } #endif -void max7456_init(uint8_t video_system) { +void max7456_init(uint8_t video_system) +{ uint8_t max_screen_rows; uint8_t srdata = 0; uint16_t x; @@ -159,7 +160,7 @@ void max7456_init(uint8_t video_system) { IOConfigGPIO(max7456CsPin, SPI_IO_CS_CFG); //Minimum spi clock period for max7456 is 100ns (10Mhz) - spiSetDivisor(MAX7456_SPI_INSTANCE, SPI_STANDARD_CLOCK); + spiSetDivisor(MAX7456_SPI_INSTANCE, SPI_CLOCK_STANDARD); delay(1000); // force soft reset on Max7456 @@ -168,10 +169,10 @@ void max7456_init(uint8_t video_system) { delay(100); srdata = max7456_send(0xA0, 0xFF); - if ((0x01 & srdata) == 0x01){ //PAL + if ((0x01 & srdata) == 0x01) { //PAL video_signal_type = VIDEO_MODE_PAL; } - else if((0x02 & srdata) == 0x02){ //NTSC + else if ((0x02 & srdata) == 0x02) { //NTSC video_signal_type = VIDEO_MODE_NTSC; } diff --git a/src/main/drivers/nvic.h b/src/main/drivers/nvic.h index e87fb6bfad..9712f89153 100644 --- a/src/main/drivers/nvic.h +++ b/src/main/drivers/nvic.h @@ -38,7 +38,6 @@ #define NVIC_PRIO_MPU_DATA_READY NVIC_BUILD_PRIORITY(0x0f, 0x0f) #define NVIC_PRIO_MAG_DATA_READY NVIC_BUILD_PRIORITY(0x0f, 0x0f) #define NVIC_PRIO_CALLBACK NVIC_BUILD_PRIORITY(0x0f, 0x0f) -#define NVIC_PRIO_BST_READ_DATA NVIC_BUILD_PRIORITY(1, 1) #define NVIC_PRIO_MAX7456_DMA NVIC_BUILD_PRIORITY(3, 0) // utility macros to join/split priority diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 32cafd6915..50061fb790 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -31,7 +31,7 @@ #include "pwm_rx.h" #include "pwm_mapping.h" -void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse); +void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate); void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse); void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t fastPwmProtocolType, uint16_t motorPwmRate, uint16_t idlePulse); void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse); @@ -144,7 +144,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) #if defined(STM32F303xC) && defined(USE_USART3) // skip UART3 ports (PB10/PB11) - if (init->useUART3 && (CheckGPIOPin(timerHardwarePtr->pin, UART3_GPIO, UART3_TX_PIN) || CheckGPIOPin(timerHardwarePtr->pin, UART3_GPIO, UART3_RX_PIN))) + if (init->useUART3 && (CheckGPIOPin(timerHardwarePtr->tag, UART3_GPIO, UART3_TX_PIN) || CheckGPIOPin(timerHardwarePtr->tag, UART3_GPIO, UART3_RX_PIN))) continue; #endif @@ -163,7 +163,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) if (timerHardwarePtr->tim == LED_STRIP_TIMER) continue; #if defined(STM32F303xC) && defined(WS2811_GPIO) && defined(WS2811_PIN_SOURCE) - if (CheckGPIOPinSource(timerHardwarePtr->pin, WS2811_GPIO, WS2811_PIN_SOURCE)) + if (CheckGPIOPinSource(timerHardwarePtr->tag, WS2811_GPIO, WS2811_PIN_SOURCE)) continue; #endif } @@ -171,28 +171,28 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) #endif #ifdef VBAT_ADC_GPIO - if (init->useVbat && CheckGPIOPin(timerHardwarePtr->pin, VBAT_ADC_GPIO, VBAT_ADC_GPIO_PIN)) { + if (init->useVbat && CheckGPIOPin(timerHardwarePtr->tag, VBAT_ADC_GPIO, VBAT_ADC_GPIO_PIN)) { continue; } #endif #ifdef RSSI_ADC_GPIO - if (init->useRSSIADC && CheckGPIOPin(timerHardwarePtr->pin, RSSI_ADC_GPIO, RSSI_ADC_GPIO_PIN)) { + if (init->useRSSIADC && CheckGPIOPin(timerHardwarePtr->tag, RSSI_ADC_GPIO, RSSI_ADC_GPIO_PIN)) { continue; } #endif #ifdef CURRENT_METER_ADC_GPIO - if (init->useCurrentMeterADC && CheckGPIOPin(timerHardwarePtr->pin, CURRENT_METER_ADC_GPIO, CURRENT_METER_ADC_GPIO_PIN)) { + if (init->useCurrentMeterADC && CheckGPIOPin(timerHardwarePtr->tag, CURRENT_METER_ADC_GPIO, CURRENT_METER_ADC_GPIO_PIN)) { continue; } #endif #ifdef SONAR - if (init->sonarConfig && + if (init->useSonar && ( - timerHardwarePtr->pin == init->sonarConfig->triggerPin || - timerHardwarePtr->pin == init->sonarConfig->echoPin + timerHardwarePtr->tag == init->sonarConfig.triggerTag || + timerHardwarePtr->tag == init->sonarConfig.echoTag )) { continue; } @@ -327,7 +327,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->pwmProtocolType, init->motorPwmRate, init->idlePulse); pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_ONESHOT|PWM_PF_OUTPUT_PROTOCOL_PWM ; } else if (init->pwmProtocolType == PWM_TYPE_BRUSHED) { - pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse); + pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate); pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_MOTOR_MODE_BRUSHED | PWM_PF_OUTPUT_PROTOCOL_PWM; } else { pwmBrushlessMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse); diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 63625f6af0..2212153cde 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -30,21 +30,18 @@ #error Invalid motor/servo/port configuration #endif - #define PULSE_1MS (1000) // 1ms pulse width - #define MAX_INPUTS 8 - #define PWM_TIMER_MHZ 1 -#define PWM_BRUSHED_TIMER_MHZ 8 -#define MULTISHOT_TIMER_MHZ 72 -#define ONESHOT42_TIMER_MHZ 24 -#define ONESHOT125_TIMER_MHZ 8 +#define PWM_BRUSHED_TIMER_MHZ 24 +#define MULTISHOT_TIMER_MHZ 72 +#define ONESHOT42_TIMER_MHZ 24 +#define ONESHOT125_TIMER_MHZ 8 typedef struct sonarIOConfig_s { - ioTag_t triggerPin; - ioTag_t echoPin; + ioTag_t triggerTag; + ioTag_t echoTag; } sonarIOConfig_t; typedef struct drv_pwm_config_s { @@ -77,7 +74,7 @@ typedef struct drv_pwm_config_s { uint16_t motorPwmRate; uint16_t idlePulse; // PWM value to use when initializing the driver. set this to either PULSE_1MS (regular pwm), // some higher value (used by 3d mode), or 0, for brushed pwm drivers. - sonarIOConfig_t *sonarConfig; + sonarIOConfig_t sonarConfig; } drv_pwm_config_t; enum { diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 7fc326f4bd..b445949381 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -95,7 +95,7 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8 pwmOutputPort_t *p = &pwmOutputPorts[allocatedOutputPortCount++]; configTimeBase(timerHardware->tim, period, mhz); - pwmGPIOConfig(timerHardware->pin, IOCFG_AF_PP); + pwmGPIOConfig(timerHardware->tag, IOCFG_AF_PP); pwmOCConfig(timerHardware->tim, timerHardware->channel, value, timerHardware->outputInverted); @@ -170,12 +170,11 @@ void pwmCompleteOneshotMotorUpdate(uint8_t motorCount) uint8_t index; TIM_TypeDef *lastTimerPtr = NULL; - for(index = 0; index < motorCount; index++){ + for (index = 0; index < motorCount; index++) { // Force the timer to overflow if it's the first motor to output, or if we change timers - if(motors[index]->tim != lastTimerPtr){ + if (motors[index]->tim != lastTimerPtr) { lastTimerPtr = motors[index]->tim; - timerForceOverflow(motors[index]->tim); } @@ -185,10 +184,10 @@ void pwmCompleteOneshotMotorUpdate(uint8_t motorCount) } } -void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse) +void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate) { uint32_t hz = PWM_BRUSHED_TIMER_MHZ * 1000000; - motors[motorIndex] = pwmOutConfig(timerHardware, PWM_BRUSHED_TIMER_MHZ, hz / motorPwmRate, idlePulse); + motors[motorIndex] = pwmOutConfig(timerHardware, PWM_BRUSHED_TIMER_MHZ, hz / motorPwmRate, 0); motors[motorIndex]->pwmWritePtr = pwmWriteBrushed; } diff --git a/src/main/drivers/pwm_rx.c b/src/main/drivers/pwm_rx.c index 50a24e28e7..9452a89eae 100644 --- a/src/main/drivers/pwm_rx.c +++ b/src/main/drivers/pwm_rx.c @@ -372,7 +372,7 @@ void pwmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t channel) self->mode = INPUT_MODE_PWM; self->timerHardware = timerHardwarePtr; - pwmGPIOConfig(timerHardwarePtr->pin, timerHardwarePtr->ioMode); + pwmGPIOConfig(timerHardwarePtr->tag, timerHardwarePtr->ioMode); pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising); timerConfigure(timerHardwarePtr, (uint16_t)PWM_TIMER_PERIOD, PWM_TIMER_MHZ); @@ -401,7 +401,7 @@ void ppmInConfig(const timerHardware_t *timerHardwarePtr) self->mode = INPUT_MODE_PPM; self->timerHardware = timerHardwarePtr; - pwmGPIOConfig(timerHardwarePtr->pin, timerHardwarePtr->ioMode); + pwmGPIOConfig(timerHardwarePtr->tag, timerHardwarePtr->ioMode); pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising); timerConfigure(timerHardwarePtr, (uint16_t)PPM_TIMER_PERIOD, PWM_TIMER_MHZ); diff --git a/src/main/drivers/resource.h b/src/main/drivers/resource.h index dc1d71f3d5..a81739bf12 100644 --- a/src/main/drivers/resource.h +++ b/src/main/drivers/resource.h @@ -23,7 +23,9 @@ typedef enum { OWNER_FLASH, OWNER_USB, OWNER_BEEPER, - OWNER_OSD + OWNER_OSD, + OWNER_BARO, + OWNER_TOTAL_COUNT } resourceOwner_t; // Currently TIMER should be shared resource (softserial dualtimer and timerqueue needs to allocate timer channel, but pin can be used for other function) diff --git a/src/main/drivers/serial.c b/src/main/drivers/serial.c index bb81d3dd89..8a17ce6793 100644 --- a/src/main/drivers/serial.c +++ b/src/main/drivers/serial.c @@ -56,7 +56,7 @@ void serialWriteBuf(serialPort_t *instance, uint8_t *data, int count) } } -uint8_t serialRxBytesWaiting(serialPort_t *instance) +uint32_t serialRxBytesWaiting(serialPort_t *instance) { return instance->vTable->serialTotalRxWaiting(instance); } diff --git a/src/main/drivers/serial.h b/src/main/drivers/serial.h index 288721ad6b..1f75e931d3 100644 --- a/src/main/drivers/serial.h +++ b/src/main/drivers/serial.h @@ -62,7 +62,7 @@ typedef struct serialPort_s { struct serialPortVTable { void (*serialWrite)(serialPort_t *instance, uint8_t ch); - uint8_t (*serialTotalRxWaiting)(serialPort_t *instance); + uint32_t (*serialTotalRxWaiting)(serialPort_t *instance); uint8_t (*serialTotalTxFree)(serialPort_t *instance); uint8_t (*serialRead)(serialPort_t *instance); @@ -81,7 +81,7 @@ struct serialPortVTable { }; void serialWrite(serialPort_t *instance, uint8_t ch); -uint8_t serialRxBytesWaiting(serialPort_t *instance); +uint32_t serialRxBytesWaiting(serialPort_t *instance); uint8_t serialTxBytesFree(serialPort_t *instance); void serialWriteBuf(serialPort_t *instance, uint8_t *data, int count); uint8_t serialRead(serialPort_t *instance); diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c index 6ab1f26bad..a2ad403b26 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -218,11 +218,11 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb softSerial->softSerialPortIndex = portIndex; - softSerial->txIO = IOGetByTag(softSerial->txTimerHardware->pin); - serialOutputPortConfig(softSerial->txTimerHardware->pin); + softSerial->txIO = IOGetByTag(softSerial->txTimerHardware->tag); + serialOutputPortConfig(softSerial->txTimerHardware->tag); - softSerial->rxIO = IOGetByTag(softSerial->rxTimerHardware->pin); - serialInputPortConfig(softSerial->rxTimerHardware->pin); + softSerial->rxIO = IOGetByTag(softSerial->rxTimerHardware->tag); + serialInputPortConfig(softSerial->rxTimerHardware->tag); setTxSignal(softSerial, ENABLE); delay(50); @@ -408,7 +408,7 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture) } } -uint8_t softSerialRxBytesWaiting(serialPort_t *instance) +uint32_t softSerialRxBytesWaiting(serialPort_t *instance) { if ((instance->mode & MODE_RX) == 0) { return 0; diff --git a/src/main/drivers/serial_softserial.h b/src/main/drivers/serial_softserial.h index daa9c5c64e..af80423b07 100644 --- a/src/main/drivers/serial_softserial.h +++ b/src/main/drivers/serial_softserial.h @@ -28,7 +28,7 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb // serialPort API void softSerialWriteByte(serialPort_t *instance, uint8_t ch); -uint8_t softSerialRxBytesWaiting(serialPort_t *instance); +uint32_t softSerialRxBytesWaiting(serialPort_t *instance); uint8_t softSerialTxBytesFree(serialPort_t *instance); uint8_t softSerialReadByte(serialPort_t *instance); void softSerialSetBaudRate(serialPort_t *s, uint32_t baudRate); diff --git a/src/main/drivers/serial_uart.c b/src/main/drivers/serial_uart.c index 4b51024216..8a7999bea5 100644 --- a/src/main/drivers/serial_uart.c +++ b/src/main/drivers/serial_uart.c @@ -165,7 +165,7 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; #endif DMA_InitStructure.DMA_BufferSize = s->port.rxBufferSize; - + #ifdef STM32F4 DMA_InitStructure.DMA_Channel = s->rxDMAChannel; DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory; @@ -176,7 +176,7 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, DMA_Cmd(s->rxDMAStream, ENABLE); USART_DMACmd(s->USARTx, USART_DMAReq_Rx, ENABLE); s->rxDMAPos = DMA_GetCurrDataCounter(s->rxDMAStream); -#else +#else DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC; DMA_InitStructure.DMA_Mode = DMA_Mode_Circular; DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)s->port.rxBuffer; @@ -228,7 +228,7 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, DMA_Init(s->txDMAStream, &DMA_InitStructure); DMA_ITConfig(s->txDMAStream, DMA_IT_TC | DMA_IT_FE | DMA_IT_TE | DMA_IT_DME, ENABLE); DMA_SetCurrDataCounter(s->txDMAStream, 0); -#else +#else DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST; DMA_InitStructure.DMA_Mode = DMA_Mode_Normal; DMA_DeInit(s->txDMAChannel); @@ -292,7 +292,7 @@ void uartStartTxDMA(uartPort_t *s) #endif } -uint8_t uartTotalRxBytesWaiting(serialPort_t *instance) +uint32_t uartTotalRxBytesWaiting(serialPort_t *instance) { uartPort_t *s = (uartPort_t*)instance; #ifdef STM32F4 diff --git a/src/main/drivers/serial_uart.h b/src/main/drivers/serial_uart.h index 78b6d7042f..a332edebf7 100644 --- a/src/main/drivers/serial_uart.h +++ b/src/main/drivers/serial_uart.h @@ -38,7 +38,7 @@ typedef struct { serialPort_t port; - + #ifdef STM32F4 DMA_Stream_TypeDef *rxDMAStream; DMA_Stream_TypeDef *txDMAStream; @@ -65,7 +65,7 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, // serialPort API void uartWrite(serialPort_t *instance, uint8_t ch); -uint8_t uartTotalRxBytesWaiting(serialPort_t *instance); +uint32_t uartTotalRxBytesWaiting(serialPort_t *instance); uint8_t uartTotalTxBytesFree(serialPort_t *instance); uint8_t uartRead(serialPort_t *instance); void uartSetBaudRate(serialPort_t *s, uint32_t baudRate); diff --git a/src/main/drivers/serial_usb_vcp.c b/src/main/drivers/serial_usb_vcp.c index 45a3702562..e9ccef82fb 100644 --- a/src/main/drivers/serial_usb_vcp.c +++ b/src/main/drivers/serial_usb_vcp.c @@ -66,11 +66,11 @@ static bool isUsbVcpTransmitBufferEmpty(serialPort_t *instance) return true; } -static uint8_t usbVcpAvailable(serialPort_t *instance) +static uint32_t usbVcpAvailable(serialPort_t *instance) { UNUSED(instance); - return receiveLength & 0xFF; // FIXME use uint32_t return type everywhere + return receiveLength; } static uint8_t usbVcpRead(serialPort_t *instance) @@ -117,10 +117,11 @@ static bool usbVcpFlush(vcpPort_t *port) if (count == 0) { return true; } + if (!usbIsConnected() || !usbIsConfigured()) { return false; } - + uint32_t txed; uint32_t start = millis(); @@ -147,7 +148,8 @@ static void usbVcpBeginWrite(serialPort_t *instance) port->buffering = true; } -uint8_t usbTxBytesFree() { +uint8_t usbTxBytesFree() +{ // Because we block upon transmit and don't buffer bytes, our "buffer" capacity is effectively unlimited. return 255; } @@ -194,6 +196,7 @@ serialPort_t *usbVcpOpen(void) return (serialPort_t *)s; } + uint32_t usbVcpGetBaudRate(serialPort_t *instance) { UNUSED(instance); diff --git a/src/main/drivers/sonar_hcsr04.c b/src/main/drivers/sonar_hcsr04.c index dbe72acd3f..6374f81d3f 100644 --- a/src/main/drivers/sonar_hcsr04.c +++ b/src/main/drivers/sonar_hcsr04.c @@ -39,7 +39,7 @@ #if defined(SONAR) STATIC_UNIT_TESTED volatile int32_t measurement = -1; static uint32_t lastMeasurementAt; -static sonarHardware_t const *sonarHardware; +sonarHardware_t sonarHardwareHCSR04; extiCallbackRec_t hcsr04_extiCallbackRec; @@ -63,9 +63,8 @@ void hcsr04_extiHandler(extiCallbackRec_t* cb) } } -void hcsr04_init(const sonarHardware_t *initialSonarHardware, sonarRange_t *sonarRange) +void hcsr04_init(sonarRange_t *sonarRange) { - sonarHardware = initialSonarHardware; sonarRange->maxRangeCm = HCSR04_MAX_RANGE_CM; sonarRange->detectionConeDeciDegrees = HCSR04_DETECTION_CONE_DECIDEGREES; sonarRange->detectionConeExtendedDeciDegrees = HCSR04_DETECTION_CONE_EXTENDED_DECIDEGREES; @@ -83,12 +82,12 @@ void hcsr04_init(const sonarHardware_t *initialSonarHardware, sonarRange_t *sona #endif // trigger pin - triggerIO = IOGetByTag(sonarHardware->triggerIO); + triggerIO = IOGetByTag(sonarHardwareHCSR04.triggerTag); IOInit(triggerIO, OWNER_SONAR, RESOURCE_INPUT); IOConfigGPIO(triggerIO, IOCFG_OUT_PP); // echo pin - echoIO = IOGetByTag(sonarHardware->echoIO); + echoIO = IOGetByTag(sonarHardwareHCSR04.echoTag); IOInit(echoIO, OWNER_SONAR, RESOURCE_INPUT); IOConfigGPIO(echoIO, IOCFG_IN_FLOATING); diff --git a/src/main/drivers/sonar_hcsr04.h b/src/main/drivers/sonar_hcsr04.h index 311fa233f5..d734f62f4f 100644 --- a/src/main/drivers/sonar_hcsr04.h +++ b/src/main/drivers/sonar_hcsr04.h @@ -21,8 +21,8 @@ #include "io.h" typedef struct sonarHardware_s { - ioTag_t triggerIO; - ioTag_t echoIO; + ioTag_t triggerTag; + ioTag_t echoTag; } sonarHardware_t; typedef struct sonarRange_s { @@ -38,6 +38,6 @@ typedef struct sonarRange_s { #define HCSR04_DETECTION_CONE_DECIDEGREES 300 // recommended cone angle30 degrees, from HC-SR04 spec sheet #define HCSR04_DETECTION_CONE_EXTENDED_DECIDEGREES 450 // in practice 45 degrees seems to work well -void hcsr04_init(const sonarHardware_t *sonarHardware, sonarRange_t *sonarRange); +void hcsr04_init(sonarRange_t *sonarRange); void hcsr04_start_reading(void); int32_t hcsr04_get_distance(void); diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index ba732d42f9..673265f545 100755 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -364,8 +364,8 @@ void timerChClearCCFlag(const timerHardware_t *timHw) // configure timer channel GPIO mode void timerChConfigGPIO(const timerHardware_t* timHw, ioConfig_t mode) { - IOInit(IOGetByTag(timHw->pin), OWNER_TIMER, RESOURCE_TIMER); - IOConfigGPIO(IOGetByTag(timHw->pin), mode); + IOInit(IOGetByTag(timHw->tag), OWNER_TIMER, RESOURCE_TIMER); + IOConfigGPIO(IOGetByTag(timHw->tag), mode); } // calculate input filter constant @@ -657,7 +657,7 @@ void timerInit(void) #if defined(STM32F3) || defined(STM32F4) for (uint8_t timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) { const timerHardware_t *timerHardwarePtr = &timerHardware[timerIndex]; - IOConfigGPIOAF(IOGetByTag(timerHardwarePtr->pin), timerHardwarePtr->ioMode, timerHardwarePtr->alternateFunction); + IOConfigGPIOAF(IOGetByTag(timerHardwarePtr->tag), timerHardwarePtr->ioMode, timerHardwarePtr->alternateFunction); } #endif diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h index f7ca6b445e..0cd5f684ec 100644 --- a/src/main/drivers/timer.h +++ b/src/main/drivers/timer.h @@ -47,9 +47,10 @@ typedef uint32_t timCCER_t; typedef uint32_t timSR_t; typedef uint32_t timCNT_t; #else -# error "Unknown CPU defined" +#error "Unknown CPU defined" #endif + // use different types from capture and overflow - multiple overflow handlers are implemented as linked list struct timerCCHandlerRec_s; struct timerOvrHandlerRec_s; @@ -70,9 +71,9 @@ typedef struct timerDef_s { rccPeriphTag_t rcc; } timerDef_t; -typedef struct { +typedef struct timerHardware_s { TIM_TypeDef *tim; - ioTag_t pin; + ioTag_t tag; uint8_t channel; uint8_t irq; uint8_t outputEnable; diff --git a/src/main/drivers/timer_stm32f30x.c b/src/main/drivers/timer_stm32f30x.c index ca80287522..4bce8a70f3 100644 --- a/src/main/drivers/timer_stm32f30x.c +++ b/src/main/drivers/timer_stm32f30x.c @@ -68,8 +68,7 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint32_t tmp = (uint32_t) TIMx; tmp += CCMR_OFFSET; - if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3)) - { + if ((TIM_Channel == TIM_Channel_1) || (TIM_Channel == TIM_Channel_3)) { tmp += (TIM_Channel>>1); /* Reset the OCxM bits in the CCMRx register */ @@ -77,9 +76,7 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint32_t /* Configure the OCxM bits in the CCMRx register */ *(__IO uint32_t *) tmp |= TIM_OCMode; - } - else - { + } else { tmp += (uint32_t)(TIM_Channel - (uint32_t)4)>> (uint32_t)1; /* Reset the OCxM bits in the CCMRx register */ diff --git a/src/main/drivers/vtx_rtc6705.c b/src/main/drivers/vtx_rtc6705.c index 423bd94ed6..35e78fe0dc 100644 --- a/src/main/drivers/vtx_rtc6705.c +++ b/src/main/drivers/vtx_rtc6705.c @@ -133,7 +133,7 @@ static uint32_t reverse32(uint32_t in) bool rtc6705Init(void) { DISABLE_RTC6705; - spiSetDivisor(RTC6705_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER); + spiSetDivisor(RTC6705_SPI_INSTANCE, SPI_CLOCK_SLOW); return rtc6705IsReady(); } diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 717f0df01f..e677237899 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -855,7 +855,7 @@ void mixTable(void) } // Motor stop handling - if (feature(FEATURE_MOTOR_STOP) && ARMING_FLAG(ARMED) && !feature(FEATURE_3D) && !IS_RC_MODE_ACTIVE(BOXAIRMODE)) { + if (feature(FEATURE_MOTOR_STOP) && ARMING_FLAG(ARMED) && !feature(FEATURE_3D) && !isAirmodeActive()) { if (((rcData[THROTTLE]) < rxConfig->mincheck)) { motor[i] = escAndServoConfig->mincommand; } diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 5b77c8c0b5..e1ba582272 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -51,7 +51,7 @@ extern uint8_t motorCount; uint32_t targetPidLooptime; extern float errorLimiter; -extern float angleRate[3], angleRateSmooth[2]; +extern float angleRate[3], angleRateSmooth[3]; int16_t axisPID[3]; @@ -67,16 +67,18 @@ static int32_t errorGyroI[3]; static float errorGyroIf[3]; #endif -static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, uint16_t max_angle_inclination, +static void pidInteger(const pidProfile_t *pidProfile, uint16_t max_angle_inclination, const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig); -pidControllerFuncPtr pid_controller = pidMultiWiiRewrite; // which pid controller are we using, defaultMultiWii +pidControllerFuncPtr pid_controller = pidInteger; // which pid controller are we using -void setTargetPidLooptime(uint8_t pidProcessDenom) { - targetPidLooptime = targetLooptime * pidProcessDenom; +void setTargetPidLooptime(uint8_t pidProcessDenom) +{ + targetPidLooptime = targetLooptime * pidProcessDenom; } -uint16_t getDynamicKi(int axis, const pidProfile_t *pidProfile, int32_t angleRate) { +uint16_t getDynamicKi(int axis, const pidProfile_t *pidProfile, int32_t angleRate) +{ uint16_t dynamicKi; uint16_t resetRate; @@ -101,7 +103,8 @@ void pidResetErrorGyroState(void) } } -float getdT (void) { +float getdT (void) +{ static float dT; if (!dT) dT = (float)targetPidLooptime * 0.000001f; @@ -114,10 +117,10 @@ static filterStatePt1_t deltaFilterState[3]; static filterStatePt1_t yawFilterState; #ifndef SKIP_PID_LUXFLOAT -static void pidLuxFloat(const pidProfile_t *pidProfile, uint16_t max_angle_inclination, +static void pidFloat(const pidProfile_t *pidProfile, uint16_t max_angle_inclination, const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig) { - float RateError, gyroRate, RateErrorSmooth; + float RateError = 0, gyroRate = 0, RateErrorSmooth = 0; float ITerm,PTerm,DTerm; static float lastRateError[2]; float delta; @@ -126,7 +129,7 @@ static void pidLuxFloat(const pidProfile_t *pidProfile, uint16_t max_angle_incli float tpaFactor = PIDweight[0] / 100.0f; // tpa is now float - // Scaling factors for Pids to match rewrite and use same defaults + // Scaling factors for Pids for better tunable range in configurator static const float luxPTermScale = 1.0f / 128; static const float luxITermScale = 1000000.0f / 0x1000000; static const float luxDTermScale = (0.000001f * (float)0xFFFF) / 508; @@ -168,7 +171,7 @@ static void pidLuxFloat(const pidProfile_t *pidProfile, uint16_t max_angle_incli } } - gyroRate = gyroADCf[axis] / 4.0f; // gyro output scaled to old rewrite scale + gyroRate = gyroADCf[axis] / 4.0f; // gyro output scaled for easier int conversion // --------low-level gyro-based PID. ---------- // Used in stand-alone mode for ACRO, controlled by higher level regulators in other modes @@ -176,11 +179,12 @@ static void pidLuxFloat(const pidProfile_t *pidProfile, uint16_t max_angle_incli // multiplication of rcCommand corresponds to changing the sticks scaling here RateError = angleRate[axis] - gyroRate; - // Smoothed Error for Derivative - if (flightModeFlags && axis != YAW) { - RateErrorSmooth = RateError; - } else { - RateErrorSmooth = angleRateSmooth[axis] - gyroRate; + if (pidProfile->deltaMethod == DELTA_FROM_ERROR) { + // Smoothed Error for Derivative when delta from error selected + if (flightModeFlags && axis != YAW) + RateErrorSmooth = RateError; + else + RateErrorSmooth = angleRateSmooth[axis] - gyroRate; } // -----calculate P component @@ -215,8 +219,13 @@ static void pidLuxFloat(const pidProfile_t *pidProfile, uint16_t max_angle_incli DTerm = 0.0f; // needed for blackbox } else { - delta = RateErrorSmooth - lastRateError[axis]; - lastRateError[axis] = RateErrorSmooth; + if (pidProfile->deltaMethod == DELTA_FROM_ERROR) { + delta = RateErrorSmooth - lastRateError[axis]; + lastRateError[axis] = RateErrorSmooth; + } else { + delta = -(gyroRate - lastRateError[axis]); + lastRateError[axis] = gyroRate; + } // Divide delta by targetLooptime to get differential (ie dr/dt) delta *= (1.0f / getdT()); @@ -245,13 +254,13 @@ static void pidLuxFloat(const pidProfile_t *pidProfile, uint16_t max_angle_incli } #endif -static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, uint16_t max_angle_inclination, +static void pidInteger(const pidProfile_t *pidProfile, uint16_t max_angle_inclination, const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig) { int axis; int32_t PTerm, ITerm, DTerm, delta; static int32_t lastRateError[3]; - int32_t AngleRateTmp, AngleRateTmpSmooth, RateError, gyroRate, RateErrorSmooth; + int32_t AngleRateTmp = 0, AngleRateTmpSmooth = 0, RateError = 0, gyroRate = 0, RateErrorSmooth = 0; int8_t horizonLevelStrength = 100; @@ -301,11 +310,12 @@ static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, uint16_t max_angl RateError = AngleRateTmp - gyroRate; - // Smoothed Error for Derivative - if (flightModeFlags && axis != YAW) { - RateErrorSmooth = RateError; - } else { - RateErrorSmooth = AngleRateTmpSmooth - gyroRate; + if (pidProfile->deltaMethod == DELTA_FROM_ERROR) { + // Smoothed Error for Derivative when delta from error selected + if (flightModeFlags && axis != YAW) + RateErrorSmooth = RateError; + else + RateErrorSmooth = AngleRateTmpSmooth - gyroRate; } // -----calculate P component @@ -348,8 +358,13 @@ static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, uint16_t max_angl DTerm = 0; // needed for blackbox } else { - delta = RateErrorSmooth - lastRateError[axis]; - lastRateError[axis] = RateErrorSmooth; + if (pidProfile->deltaMethod == DELTA_FROM_ERROR) { + delta = RateErrorSmooth - lastRateError[axis]; + lastRateError[axis] = RateErrorSmooth; + } else { + delta = -(gyroRate - lastRateError[axis]); + lastRateError[axis] = gyroRate; + } // Divide delta by targetLooptime to get differential (ie dr/dt) delta = (delta * ((uint16_t) 0xFFFF / ((uint16_t)targetPidLooptime >> 4))) >> 5; @@ -382,12 +397,12 @@ void pidSetController(pidControllerType_e type) { switch (type) { default: - case PID_CONTROLLER_MWREWRITE: - pid_controller = pidMultiWiiRewrite; + case PID_CONTROLLER_INTEGER: + pid_controller = pidInteger; break; #ifndef SKIP_PID_LUXFLOAT - case PID_CONTROLLER_LUX_FLOAT: - pid_controller = pidLuxFloat; + case PID_CONTROLLER_FLOAT: + pid_controller = pidFloat; #endif } } diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 85f5695241..a407aeb80a 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -41,14 +41,14 @@ typedef enum { } pidIndex_e; typedef enum { - PID_CONTROLLER_MWREWRITE = 1, - PID_CONTROLLER_LUX_FLOAT, + PID_CONTROLLER_INTEGER = 1, // Integer math to gain some more performance from F1 targets + PID_CONTROLLER_FLOAT, PID_COUNT } pidControllerType_e; typedef enum { - DELTA_FROM_ERROR = 0, - DELTA_FROM_MEASUREMENT + DELTA_FROM_ERROR = 0, + DELTA_FROM_MEASUREMENT } pidDeltaType_e; typedef enum { @@ -68,6 +68,7 @@ typedef struct pidProfile_s { uint16_t dterm_lpf_hz; // Delta Filter in hz uint16_t yaw_lpf_hz; // Additional yaw filter when yaw axis too noisy + uint8_t deltaMethod; // Alternative delta Calculation uint16_t rollPitchItermIgnoreRate; // Experimental threshold for resetting iterm for pitch and roll on certain rates uint16_t yawItermIgnoreRate; // Experimental threshold for resetting iterm for yaw on certain rates uint16_t yaw_p_limit; diff --git a/src/main/io/serial_4way.c b/src/main/io/serial_4way.c index 91ed53db4e..6d96a36ec1 100644 --- a/src/main/io/serial_4way.c +++ b/src/main/io/serial_4way.c @@ -100,43 +100,32 @@ static void setDisconnected(void) bool isEscHi(uint8_t selEsc) { - return (digitalIn(escHardware[selEsc].gpio, escHardware[selEsc].pin) != Bit_RESET); + return (IORead(escHardware[selEsc].io) != Bit_RESET); } bool isEscLo(uint8_t selEsc) { - return (digitalIn(escHardware[selEsc].gpio, escHardware[selEsc].pin) == Bit_RESET); + return (IORead(escHardware[selEsc].io) == Bit_RESET); } void setEscHi(uint8_t selEsc) { - digitalHi(escHardware[selEsc].gpio, escHardware[selEsc].pin); + IOHi(escHardware[selEsc].io); } void setEscLo(uint8_t selEsc) { - digitalLo(escHardware[selEsc].gpio, escHardware[selEsc].pin); + IOLo(escHardware[selEsc].io); } void setEscInput(uint8_t selEsc) { - gpioInit(escHardware[selEsc].gpio, &escHardware[selEsc].gpio_config_INPUT); + IOConfigGPIO(escHardware[selEsc].io, IOCFG_IPU); } void setEscOutput(uint8_t selEsc) { - gpioInit(escHardware[selEsc].gpio, &escHardware[selEsc].gpio_config_OUTPUT); -} - -static uint32_t getPinPos(uint32_t pin) -{ - for (int pinPos = 0; pinPos < 16; pinPos++) { - uint32_t pinMask = (0x1 << pinPos); - if (pin & pinMask) { - return pinPos; - } - } - return 0; + IOConfigGPIO(escHardware[selEsc].io, IOCFG_OUT_PP); } // Initialize 4way ESC interface @@ -151,14 +140,7 @@ int esc4wayInit(void) for (volatile uint8_t i = 0; i < pwmOutputConfiguration->outputCount; i++) { if ((pwmOutputConfiguration->portConfigurations[i].flags & PWM_PF_MOTOR) == PWM_PF_MOTOR) { if(motor[pwmOutputConfiguration->portConfigurations[i].index] > 0) { - escHardware[escIdx].gpio = IO_GPIO(IOGetByTag(pwmOutputConfiguration->portConfigurations[i].timerHardware->pin)); - escHardware[escIdx].pin = IO_Pin(IOGetByTag(pwmOutputConfiguration->portConfigurations[i].timerHardware->pin)); - escHardware[escIdx].pinpos = getPinPos(escHardware[escIdx].pin); - escHardware[escIdx].gpio_config_INPUT.pin = escHardware[escIdx].pin; - escHardware[escIdx].gpio_config_INPUT.speed = Speed_2MHz; // see pwmOutConfig() - escHardware[escIdx].gpio_config_INPUT.mode = Mode_IPU; - escHardware[escIdx].gpio_config_OUTPUT = escHardware[escIdx].gpio_config_INPUT; - escHardware[escIdx].gpio_config_OUTPUT.mode = Mode_Out_PP; + escHardware[escIdx].io = IOGetByTag(pwmOutputConfiguration->portConfigurations[i].timerHardware->tag); escIdx++; } } @@ -183,7 +165,7 @@ void esc4wayStart(void) void esc4wayRelease(void) { for(int i = 0; i < escCount; i++) { - escHardware[i].gpio_config_OUTPUT.mode = Mode_AF_PP; // see pwmOutConfig() + IOConfigGPIO(escHardware[i].io, IOCFG_AF_PP); // see pwmOutConfig() setEscOutput(i); setEscLo(i); } @@ -397,6 +379,10 @@ void esc4wayProcess(serialPort_t *serial) writeByte(crcOut >> 8); writeByte(crcOut & 0xff); serialEndWrite(port); + +#ifdef STM32F4 + delay(50); +#endif TX_LED_OFF; } diff --git a/src/main/io/serial_4way_impl.h b/src/main/io/serial_4way_impl.h index c9adc7f916..ca1012b284 100644 --- a/src/main/io/serial_4way_impl.h +++ b/src/main/io/serial_4way_impl.h @@ -17,11 +17,7 @@ */ typedef struct { - GPIO_TypeDef* gpio; - uint16_t pinpos; - uint16_t pin; - gpio_config_t gpio_config_INPUT; - gpio_config_t gpio_config_OUTPUT; + IO_t io; } escHardware_t; extern uint8_t escSelected; diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 027ea44d82..36d254556a 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -386,7 +386,7 @@ static const char * const lookupTableBlackboxDevice[] = { static const char * const lookupTablePidController[] = { - "UNUSED", "MWREWRITE", "LUX" + "UNUSED", "INT", "FLOAT" }; static const char * const lookupTableSerialRX[] = { @@ -463,10 +463,14 @@ static const char * const lookupTableSuperExpoYaw[] = { "OFF", "ON", "ALWAYS" }; -static const char * const lookupTableFastPwm[] = { +static const char * const lookupTablePwmProtocol[] = { "OFF", "ONESHOT125", "ONESHOT42", "MULTISHOT", "BRUSHED" }; +static const char * const lookupDeltaMethod[] = { + "ERROR", "MEASUREMENT" +}; + typedef struct lookupTableEntry_s { const char * const *values; const uint8_t valueCount; @@ -494,6 +498,7 @@ typedef enum { TABLE_DEBUG, TABLE_SUPEREXPO_YAW, TABLE_MOTOR_PWM_PROTOCOL, + TABLE_DELTA_METHOD, #ifdef OSD TABLE_OSD, #endif @@ -520,7 +525,8 @@ static const lookupTableEntry_t lookupTables[] = { { lookupTableMagHardware, sizeof(lookupTableMagHardware) / sizeof(char *) }, { lookupTableDebug, sizeof(lookupTableDebug) / sizeof(char *) }, { lookupTableSuperExpoYaw, sizeof(lookupTableSuperExpoYaw) / sizeof(char *) }, - { lookupTableFastPwm, sizeof(lookupTableFastPwm) / sizeof(char *) }, + { lookupTablePwmProtocol, sizeof(lookupTablePwmProtocol) / sizeof(char *) }, + { lookupDeltaMethod, sizeof(lookupDeltaMethod) / sizeof(char *) }, #ifdef OSD { lookupTableOsdType, sizeof(lookupTableOsdType) / sizeof(char *) }, #endif @@ -576,12 +582,12 @@ typedef struct { const clivalue_t valueTable[] = { // { "emf_avoidance", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.emf_avoidance, .config.lookup = { TABLE_OFF_ON } }, - { "mid_rc", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.midrc, .config.minmax = { 1200, 1700 } }, { "min_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.mincheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "max_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.maxcheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "rssi_channel", VAR_INT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_channel, .config.minmax = { 0, MAX_SUPPORTED_RC_CHANNEL_COUNT } }, { "rssi_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_scale, .config.minmax = { RSSI_SCALE_MIN, RSSI_SCALE_MAX } }, + { "rc_smooth_interval_ms", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.rcSmoothInterval, .config.minmax = { 0, 255 } }, { "rssi_ppm_invert", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.rssi_ppm_invert, .config.lookup = { TABLE_OFF_ON } }, { "input_filtering_mode", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.inputFilteringMode, .config.lookup = { TABLE_OFF_ON } }, { "roll_yaw_cam_mix_degrees", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.fpvCamAngleDegrees, .config.minmax = { 0, 50 } }, @@ -685,7 +691,7 @@ const clivalue_t valueTable[] = { { "align_board_yaw", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.yawDegrees, .config.minmax = { -180, 360 } }, { "max_angle_inclination", VAR_UINT16 | MASTER_VALUE, &masterConfig.max_angle_inclination, .config.minmax = { 100, 900 } }, - + { "pid_delta_method", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.deltaMethod, .config.lookup = { TABLE_DELTA_METHOD } }, { "gyro_lpf", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_lpf, .config.lookup = { TABLE_GYRO_LPF } }, { "gyro_sync_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_sync_denom, .config.minmax = { 1, 8 } }, { "gyro_lowpass", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_soft_lpf_hz, .config.minmax = { 0, 255 } }, @@ -1896,10 +1902,11 @@ static void dumpValues(uint16_t valueSection) cliPrintf("set %s = ", valueTable[i].name); cliPrintVar(value, 0); cliPrint("\r\n"); - -#ifdef STM32F4 - delayMicroseconds(1000); + +#ifdef USE_SLOW_SERIAL_CLI + delay(2); #endif + } } @@ -1973,6 +1980,9 @@ static void cliDump(char *cmdline) if (yaw < 0) cliWrite(' '); cliPrintf("%s\r\n", ftoa(yaw, buf)); +#ifdef USE_SLOW_SERIAL_CLI + delay(2); +#endif } #ifdef USE_SERVOS @@ -1994,6 +2004,10 @@ static void cliDump(char *cmdline) masterConfig.customServoMixer[i].max, masterConfig.customServoMixer[i].box ); + +#ifdef USE_SLOW_SERIAL_CLI + delay(2); +#endif } #endif @@ -2006,12 +2020,18 @@ static void cliDump(char *cmdline) if (featureNames[i] == NULL) break; cliPrintf("feature -%s\r\n", featureNames[i]); +#ifdef USE_SLOW_SERIAL_CLI + delay(2); +#endif } for (i = 0; ; i++) { // reenable what we want. if (featureNames[i] == NULL) break; if (mask & (1 << i)) cliPrintf("feature %s\r\n", featureNames[i]); +#ifdef USE_SLOW_SERIAL_CLI + delay(2); +#endif } @@ -2071,6 +2091,9 @@ static void cliDump(char *cmdline) for (channel = 0; channel < INPUT_SOURCE_COUNT; channel++) { if (servoDirection(i, channel) < 0) { cliPrintf("smix reverse %d %d r\r\n", i , channel); +#ifdef USE_SLOW_SERIAL_CLI + delay(2); +#endif } } } @@ -2103,6 +2126,9 @@ static void cliDump(char *cmdline) changeControlRateProfile(currentRateIndex); cliRateProfile(""); +#ifdef USE_SLOW_SERIAL_CLI + delay(2); +#endif } cliPrint("\r\n# restore original profile selection\r\n"); @@ -2127,7 +2153,8 @@ static void cliDump(char *cmdline) } } -void cliDumpProfile(uint8_t profileIndex) { +void cliDumpProfile(uint8_t profileIndex) +{ if (profileIndex >= MAX_PROFILE_COUNT) // Faulty values return; @@ -2142,7 +2169,8 @@ void cliDumpProfile(uint8_t profileIndex) { cliRateProfile(""); } -void cliDumpRateProfile(uint8_t rateProfileIndex) { +void cliDumpRateProfile(uint8_t rateProfileIndex) +{ if (rateProfileIndex >= MAX_RATEPROFILES) // Faulty values return; @@ -2535,12 +2563,12 @@ static void cliRateProfile(char *cmdline) { } } -static void cliReboot(void) { +static void cliReboot(void) +{ cliPrint("\r\nRebooting"); bufWriterFlush(cliWriter); waitForSerialPortToFinishTransmitting(cliPort); stopMotors(); - handleOneshotFeatureChangeOnRestart(); systemReset(); } @@ -2647,7 +2675,7 @@ static void cliPrintVarRange(const clivalue_t *var) { switch (var->type & VALUE_MODE_MASK) { case (MODE_DIRECT): { - cliPrintf("Allowed range: %d - %d\n", var->config.minmax.min, var->config.minmax.max); + cliPrintf("Allowed range: %d - %d\r\n", var->config.minmax.min, var->config.minmax.max); } break; case (MODE_LOOKUP): { @@ -2659,7 +2687,7 @@ static void cliPrintVarRange(const clivalue_t *var) cliPrint(","); cliPrintf(" %s", tableEntry->values[i]); } - cliPrint("\n"); + cliPrint("\r\n"); } break; } @@ -2711,6 +2739,10 @@ static void cliSet(char *cmdline) cliPrintf("%s = ", valueTable[i].name); cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui cliPrint("\r\n"); + +#ifdef USE_SLOW_SERIAL_CLI + delay(2); +#endif } } else if ((eqptr = strstr(cmdline, "=")) != NULL) { // has equals @@ -2885,14 +2917,14 @@ static void cliTasks(char *cmdline) subTaskFrequency = (uint16_t)(1.0f / ((float)cycleTime * 0.000001f)); if (masterConfig.pid_process_denom > 1) { taskFrequency = subTaskFrequency / masterConfig.pid_process_denom; - cliPrintf("%d - (%s) ", taskId, taskInfo.taskName); + cliPrintf("%02d - (%s) ", taskId, taskInfo.taskName); } else { taskFrequency = subTaskFrequency; - cliPrintf("%d - (%s/%s) ", taskId, taskInfo.subTaskName, taskInfo.taskName); + cliPrintf("%02d - (%s/%s) ", taskId, taskInfo.subTaskName, taskInfo.taskName); } } else { taskFrequency = (uint16_t)(1.0f / ((float)taskInfo.latestDeltaTime * 0.000001f)); - cliPrintf("%d - (%s) ", taskId, taskInfo.taskName); + cliPrintf("%02d - (%s) ", taskId, taskInfo.taskName); } cliPrintf("max: %dus, avg: %dus, rate: %dhz, total: ", taskInfo.maxExecutionTime, taskInfo.averageExecutionTime, taskFrequency); @@ -2903,7 +2935,7 @@ static void cliTasks(char *cmdline) cliPrintf("%dms", taskTotalTime); } - if (taskId == TASK_GYROPID && masterConfig.pid_process_denom > 1) cliPrintf("\r\n- - (%s) rate: %dhz", taskInfo.subTaskName, subTaskFrequency); + if (taskId == TASK_GYROPID && masterConfig.pid_process_denom > 1) cliPrintf("\r\n - - (%s) rate: %dhz", taskInfo.subTaskName, subTaskFrequency); cliPrintf("\r\n", taskTotalTime); } } @@ -3032,7 +3064,7 @@ void cliProcess(void) } } -const char * const ownerNames[] = { +const char * const ownerNames[OWNER_TOTAL_COUNT] = { "FREE", "PWM IN", "PPM IN", @@ -3054,6 +3086,8 @@ const char * const ownerNames[] = { "FLASH", "USB", "BEEPER", + "OSD", + "BARO", }; static void cliResource(char *cmdline) diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 693d988dc2..3bd8d14415 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -148,13 +148,13 @@ void setGyroSamplingSpeed(uint16_t looptime) { gyroSampleRate = 125; maxDivider = 8; masterConfig.pid_process_denom = 1; - if (currentProfile->pidProfile.pidController == PID_CONTROLLER_LUX_FLOAT) { + if (currentProfile->pidProfile.pidController == PID_CONTROLLER_FLOAT) { masterConfig.pid_process_denom = 2; } if (looptime < 250) { masterConfig.pid_process_denom = 4; } else if (looptime < 375) { - if (currentProfile->pidProfile.pidController == PID_CONTROLLER_LUX_FLOAT) { + if (currentProfile->pidProfile.pidController == PID_CONTROLLER_FLOAT) { masterConfig.pid_process_denom = 3; } else { masterConfig.pid_process_denom = 2; @@ -1272,14 +1272,19 @@ static bool processOutCommand(uint8_t cmdMSP) serialize16(currentProfile->pidProfile.yaw_lpf_hz); break; case MSP_ADVANCED_TUNING: - headSerialReply(3 * 2); + headSerialReply(3 * 2 + 2); serialize16(currentProfile->pidProfile.rollPitchItermIgnoreRate); serialize16(currentProfile->pidProfile.yawItermIgnoreRate); serialize16(currentProfile->pidProfile.yaw_p_limit); + serialize8(currentProfile->pidProfile.deltaMethod); + serialize8(masterConfig.batteryConfig.vbatPidCompensation); break; - case MSP_TEMPORARY_COMMANDS: - headSerialReply(1); + case MSP_SPECIAL_PARAMETERS: + headSerialReply(1 + 2 + 1 + 2); serialize8(currentControlRateProfile->rcYawRate8); + serialize16(masterConfig.rxConfig.airModeActivateThreshold); + serialize8(masterConfig.rxConfig.rcSmoothInterval); + serialize16(masterConfig.escAndServoConfig.escDesyncProtection); break; case MSP_SENSOR_CONFIG: headSerialReply(3); @@ -1510,7 +1515,7 @@ static bool processInCommand(void) break; case MSP_SET_RESET_CURR_PID: - //resetPidProfile(¤tProfile->pidProfile); + resetPidProfile(¤tProfile->pidProfile); break; case MSP_SET_SENSOR_ALIGNMENT: @@ -1850,9 +1855,14 @@ static bool processInCommand(void) currentProfile->pidProfile.rollPitchItermIgnoreRate = read16(); currentProfile->pidProfile.yawItermIgnoreRate = read16(); currentProfile->pidProfile.yaw_p_limit = read16(); + currentProfile->pidProfile.deltaMethod = read8(); + masterConfig.batteryConfig.vbatPidCompensation = read8(); break; - case MSP_SET_TEMPORARY_COMMANDS: + case MSP_SET_SPECIAL_PARAMETERS: currentControlRateProfile->rcYawRate8 = read8(); + masterConfig.rxConfig.airModeActivateThreshold = read16(); + masterConfig.rxConfig.rcSmoothInterval = read8(); + masterConfig.escAndServoConfig.escDesyncProtection = read16(); break; case MSP_SET_SENSOR_CONFIG: masterConfig.acc_hardware = read8(); @@ -1959,7 +1969,6 @@ void mspProcess(void) if (isRebootScheduled) { waitForSerialPortToFinishTransmitting(candidatePort->port); stopMotors(); - handleOneshotFeatureChangeOnRestart(); // On real flight controllers, systemReset() will do a soft reset of the device, // reloading the program. But to support offline testing this flag needs to be // cleared so that the software doesn't continuously attempt to reboot itself. diff --git a/src/main/io/serial_msp.h b/src/main/io/serial_msp.h index 7acb92a252..1a63b2b20d 100644 --- a/src/main/io/serial_msp.h +++ b/src/main/io/serial_msp.h @@ -206,8 +206,8 @@ static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER; #define MSP_SENSOR_CONFIG 96 #define MSP_SET_SENSOR_CONFIG 97 -#define MSP_TEMPORARY_COMMANDS 98 // Temporary Commands before cleanup -#define MSP_SET_TEMPORARY_COMMANDS 99 // Temporary Commands before cleanup +#define MSP_SPECIAL_PARAMETERS 98 // Temporary betaflight parameters before cleanup and keep CF compatibility +#define MSP_SET_SPECIAL_PARAMETERS 99 // Temporary betaflight parameters before cleanup and keep CF compatibility // // Multwii original MSP commands diff --git a/src/main/main.c b/src/main/main.c index ba6026f4f3..dba36d3f43 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -137,8 +137,7 @@ void imuInit(void); void displayInit(rxConfig_t *intialRxConfig); void ledStripInit(ledConfig_t *ledConfigsToUse, hsvColor_t *colorsToUse); void spektrumBind(rxConfig_t *rxConfig); -const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig); -void sonarInit(const sonarHardware_t *sonarHardware); +const sonarHardware_t *sonarGetHardwareConfiguration(currentSensor_e currentSensor); void osdInit(void); typedef enum { @@ -264,15 +263,13 @@ void init(void) memset(&pwm_params, 0, sizeof(pwm_params)); #ifdef SONAR - const sonarHardware_t *sonarHardware = NULL; - if (feature(FEATURE_SONAR)) { - sonarHardware = sonarGetHardwareConfiguration(&masterConfig.batteryConfig); - sonarIOConfig_t sonarConfig = { - .triggerPin = sonarHardware->triggerIO, - .echoPin = sonarHardware->echoIO - }; - pwm_params.sonarConfig = &sonarConfig; + const sonarHardware_t *sonarHardware = sonarGetHardwareConfiguration(masterConfig.batteryConfig.currentMeterType); + if (sonarHardware) { + pwm_params.useSonar = true; + pwm_params.sonarConfig.triggerTag = sonarHardware->triggerTag; + pwm_params.sonarConfig.echoTag = sonarHardware->echoTag; + } } #endif @@ -302,9 +299,6 @@ void init(void) pwm_params.useLEDStrip = feature(FEATURE_LED_STRIP); pwm_params.usePPM = feature(FEATURE_RX_PPM); pwm_params.useSerialRx = feature(FEATURE_RX_SERIAL); -#ifdef SONAR - pwm_params.useSonar = feature(FEATURE_SONAR); -#endif #ifdef USE_SERVOS pwm_params.useServos = isMixerUsingServos(); @@ -320,7 +314,7 @@ void init(void) } bool use_unsyncedPwm = masterConfig.use_unsyncedPwm; - + // Configurator feature abused for enabling Fast PWM pwm_params.useFastPwm = (masterConfig.motor_pwm_protocol != PWM_TYPE_CONVENTIONAL && masterConfig.motor_pwm_protocol != PWM_TYPE_BRUSHED); pwm_params.pwmProtocolType = masterConfig.motor_pwm_protocol; @@ -328,7 +322,9 @@ void init(void) pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand; if (feature(FEATURE_3D)) pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d; + if (masterConfig.motor_pwm_protocol == PWM_TYPE_BRUSHED) { + featureClear(FEATURE_3D); pwm_params.idlePulse = 0; // brushed motors use_unsyncedPwm = false; } @@ -341,9 +337,12 @@ void init(void) mixerUsePWMOutputConfiguration(pwmOutputConfiguration, use_unsyncedPwm); +/* + // TODO is this needed here? enables at the end if (!feature(FEATURE_ONESHOT125)) motorControlEnable = true; +*/ systemState |= SYSTEM_STATE_MOTORS_READY; #ifdef BEEPER @@ -548,7 +547,7 @@ void init(void) #ifdef SONAR if (feature(FEATURE_SONAR)) { - sonarInit(sonarHardware); + sonarInit(); } #endif @@ -730,7 +729,7 @@ void main_init(void) #endif #ifdef MAG setTaskEnabled(TASK_COMPASS, sensors(SENSOR_MAG)); -#ifdef SPRACINGF3EVO +#if defined(USE_SPI) && defined(USE_MAG_AK8963) // fixme temporary solution for AK6983 via slave I2C on MPU9250 rescheduleTask(TASK_COMPASS, 1000000 / 40); #endif diff --git a/src/main/mw.c b/src/main/mw.c index 5a95f1c924..e2819b722c 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -123,7 +123,7 @@ extern uint8_t PIDweight[3]; uint16_t filteredCycleTime; static bool isRXDataNew; static bool armingCalibrationWasInitialised; -float angleRate[3], angleRateSmooth[2]; +float angleRate[3], angleRateSmooth[3]; extern pidControllerFuncPtr pid_controller; @@ -197,7 +197,11 @@ void processRcCommand(void) int axis; // Set RC refresh rate for sampling and channels to filter - initRxRefreshRate(&rxRefreshRate); + if (masterConfig.rxConfig.rcSmoothInterval) { + rxRefreshRate = 1000 * masterConfig.rxConfig.rcSmoothInterval; + } else { + initRxRefreshRate(&rxRefreshRate); + } rcInterpolationFactor = rxRefreshRate / targetPidLooptime + 1; @@ -694,6 +698,8 @@ void subTaskMainSubprocesses(void) { #endif #if defined(BARO) || defined(SONAR) + // updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState + updateRcCommands(); if (sensors(SENSOR_BARO) || sensors(SENSOR_SONAR)) { if (FLIGHT_MODE(BARO_MODE) || FLIGHT_MODE(SONAR_MODE)) { applyAltHold(&masterConfig.airplaneConfig); @@ -874,8 +880,10 @@ void taskUpdateRxMain(void) processRx(); isRXDataNew = true; +#if !defined(BARO) && !defined(SONAR) // updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState updateRcCommands(); +#endif updateLEDs(); #ifdef BARO diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index b76873fb15..1cec24053a 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -121,7 +121,7 @@ typedef struct rxConfig_s { uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here uint16_t mincheck; // minimum rc end uint16_t maxcheck; // maximum rc end - uint8_t rcSmoothing; + uint8_t rcSmoothInterval; uint8_t fpvCamAngleDegrees; // Camera angle to be scaled into rc commands uint8_t max_aux_channel; uint16_t airModeActivateThreshold; // Throttle setpoint where airmode gets activated diff --git a/src/main/sensors/compass.c b/src/main/sensors/compass.c index 5df25737b9..7ee14da4c7 100644 --- a/src/main/sensors/compass.c +++ b/src/main/sensors/compass.c @@ -43,6 +43,7 @@ mag_t mag; // mag access functions extern uint32_t currentTime; // FIXME dependency on global variable, pass it in instead. +int16_t magADCRaw[XYZ_AXIS_COUNT]; int32_t magADC[XYZ_AXIS_COUNT]; sensor_align_e magAlign = 0; #ifdef MAG @@ -57,27 +58,19 @@ void compassInit(void) magInit = 1; } -#define COMPASS_UPDATE_FREQUENCY_10HZ (1000 * 100) - void updateCompass(flightDynamicsTrims_t *magZero) { - static uint32_t nextUpdateAt, tCal = 0; + static uint32_t tCal = 0; static flightDynamicsTrims_t magZeroTempMin; static flightDynamicsTrims_t magZeroTempMax; - int16_t magADCRaw[XYZ_AXIS_COUNT]; uint32_t axis; - if ((int32_t)(currentTime - nextUpdateAt) < 0) - return; - - nextUpdateAt = currentTime + COMPASS_UPDATE_FREQUENCY_10HZ; - mag.read(magADCRaw); - for (axis = 0; axis < XYZ_AXIS_COUNT; axis++) magADC[axis] = magADCRaw[axis]; + for (axis = 0; axis < XYZ_AXIS_COUNT; axis++) magADC[axis] = magADCRaw[axis]; // int32_t copy to work with alignSensors(magADC, magADC, magAlign); if (STATE(CALIBRATE_MAG)) { - tCal = nextUpdateAt; + tCal = currentTime; for (axis = 0; axis < 3; axis++) { magZero->raw[axis] = 0; magZeroTempMin.raw[axis] = magADC[axis]; @@ -93,7 +86,7 @@ void updateCompass(flightDynamicsTrims_t *magZero) } if (tCal != 0) { - if ((nextUpdateAt - tCal) < 30000000) { // 30s: you have 30s to turn the multi in all directions + if ((currentTime - tCal) < 30000000) { // 30s: you have 30s to turn the multi in all directions LED0_TOGGLE; for (axis = 0; axis < 3; axis++) { if (magADC[axis] < magZeroTempMin.raw[axis]) diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index b22955cead..bce60a1fca 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -56,7 +56,7 @@ void useGyroConfig(gyroConfig_t *gyroConfigToUse, float gyro_lpf_hz) } void initGyroFilterCoefficients(void) { - int axis; + int axis; if (gyroLpfCutFreq && targetLooptime) { /* Initialisation needs to happen once samplingrate is known */ for (axis = 0; axis < 3; axis++) BiQuadNewLpf(gyroLpfCutFreq, &gyroFilterState[axis], targetLooptime); gyroFilterStateIsSet = true; @@ -137,8 +137,8 @@ static void applyGyroZero(void) void gyroUpdate(void) { - int16_t gyroADCRaw[XYZ_AXIS_COUNT]; - int axis; + int16_t gyroADCRaw[XYZ_AXIS_COUNT]; + int axis; // range: +/- 8192; +/- 2000 deg/sec if (!gyro.read(gyroADCRaw)) { @@ -161,10 +161,12 @@ void gyroUpdate(void) if (gyroLpfCutFreq) { if (!gyroFilterStateIsSet) initGyroFilterCoefficients(); /* initialise filter coefficients */ - if (gyroFilterStateIsSet) { - for (axis = 0; axis < XYZ_AXIS_COUNT; axis++){ + for (axis = 0; axis < XYZ_AXIS_COUNT; axis++) { + if (gyroFilterStateIsSet) { gyroADCf[axis] = applyBiQuadFilter((float) gyroADC[axis], &gyroFilterState[axis]); gyroADC[axis] = lrintf(gyroADCf[axis]); + } else { + gyroADCf[axis] = gyroADC[axis]; // Otherwise float pid controller will not have gyro input when filter disabled } } } diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index a69a976b67..00093d18e6 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -86,7 +86,7 @@ uint8_t detectedSensors[MAX_SENSORS_TO_DETECT] = { GYRO_NONE, ACC_NONE, BARO_NON const extiConfig_t *selectMPUIntExtiConfig(void) { #if defined(MPU_INT_EXTI) - static const extiConfig_t mpuIntExtiConfig = { .io = IO_TAG(MPU_INT_EXTI) }; + static const extiConfig_t mpuIntExtiConfig = { .tag = IO_TAG(MPU_INT_EXTI) }; return &mpuIntExtiConfig; #elif defined(USE_HARDWARE_REVISION_DETECTION) return selectMPUIntExtiConfigByHardwareRevision(); @@ -97,7 +97,7 @@ const extiConfig_t *selectMPUIntExtiConfig(void) #ifdef USE_FAKE_GYRO int16_t fake_gyro_values[XYZ_AXIS_COUNT] = { 0,0,0 }; -static void fakeGyroInit(uint16_t lpf) +static void fakeGyroInit(uint8_t lpf) { UNUSED(lpf); } @@ -129,7 +129,7 @@ bool fakeGyroDetect(gyro_t *gyro) #ifdef USE_FAKE_ACC int16_t fake_acc_values[XYZ_AXIS_COUNT] = {0,0,0}; -static void fakeAccInit(void) {} +static void fakeAccInit(acc_t *acc) {UNUSED(acc);} static bool fakeAccRead(int16_t *accData) { for(int i=0;i 1) { - if(readData[1]+1 == bufferPointer) { - crc8Cal(0); - bstProcessInCommand(); - } else { - crc8Cal(data); - } - } - bufferPointer++; - I2C_ClearITPendingBit(BSTx, I2C_IT_RXNE); - } else if(I2C_GetITStatus(BSTx, I2C_IT_TXIS)) { - if(receiverAddress) { - if(currentWriteBufferPointer > 0) { - if(writeData[0] == currentWriteBufferPointer) { - receiverAddress = false; - crc8Cal(0); - I2C_SendData(BSTx, (uint8_t) CRC8); - I2C_ITConfig(BSTx, I2C_IT_TXI, DISABLE); - } else { - crc8Cal((uint8_t) writeData[currentWriteBufferPointer]); - I2C_SendData(BSTx, (uint8_t) writeData[currentWriteBufferPointer++]); - } - } - } else if(bstWriteDataLen) { - I2C_SendData(BSTx, (uint8_t) dataBuffer[dataBufferPointer]); - if(bstWriteDataLen > 1) - dataBufferPointer++; - if(dataBufferPointer == bstWriteDataLen) { - I2C_ITConfig(BSTx, I2C_IT_TXI, DISABLE); - dataBufferPointer = 0; - bstWriteDataLen = 0; - } - } else { - } - I2C_ClearITPendingBit(BSTx, I2C_IT_TXIS); - } else if(I2C_GetITStatus(BSTx, I2C_IT_NACKF)) { - if(receiverAddress) { - receiverAddress = false; - I2C_ITConfig(BSTx, I2C_IT_TXI, DISABLE); - } - I2C_ClearITPendingBit(BSTx, I2C_IT_NACKF); - } else if(I2C_GetITStatus(BSTx, I2C_IT_STOPF)) { - if(bstWriteDataLen && dataBufferPointer == bstWriteDataLen) { - dataBufferPointer = 0; - bstWriteDataLen = 0; - } - I2C_ClearITPendingBit(BSTx, I2C_IT_STOPF); - } else if(I2C_GetITStatus(BSTx, I2C_IT_BERR) - || I2C_GetITStatus(BSTx, I2C_IT_ARLO) - || I2C_GetITStatus(BSTx, I2C_IT_OVR)) { - bstTimeoutUserCallback(); - I2C_ClearITPendingBit(BSTx, I2C_IT_BERR | I2C_IT_ARLO | I2C_IT_OVR); - } + if(I2C_GetITStatus(BSTx, I2C_IT_ADDR)) { + CRC8 = 0; + if(I2C_GetTransferDirection(BSTx) == I2C_Direction_Receiver) { + currentWriteBufferPointer = 0; + receiverAddress = true; + I2C_SendData(BSTx, (uint8_t) writeData[currentWriteBufferPointer++]); + I2C_ITConfig(BSTx, I2C_IT_TXI, ENABLE); + } else { + readData[0] = I2C_GetAddressMatched(BSTx); + bufferPointer = 1; + } + I2C_ClearITPendingBit(BSTx, I2C_IT_ADDR); + } else if(I2C_GetITStatus(BSTx, I2C_IT_RXNE)) { + uint8_t data = I2C_ReceiveData(BSTx); + readData[bufferPointer] = data; + if(bufferPointer > 1) { + if(readData[1]+1 == bufferPointer) { + crc8Cal(0); + bstProcessInCommand(); + } else { + crc8Cal(data); + } + } + bufferPointer++; + I2C_ClearITPendingBit(BSTx, I2C_IT_RXNE); + } else if(I2C_GetITStatus(BSTx, I2C_IT_TXIS)) { + if(receiverAddress) { + if(currentWriteBufferPointer > 0) { + if(!cleanflight_data_ready) { + I2C_ClearITPendingBit(BSTx, I2C_IT_TXIS); + return; + } + if(interruptCounter < DELAY_SENDING_BYTE) { + interruptCounter++; + I2C_ClearITPendingBit(BSTx, I2C_IT_TXIS); + return; + } else { + interruptCounter = 0; + } + if(writeData[0] == currentWriteBufferPointer) { + receiverAddress = false; + crc8Cal(0); + I2C_SendData(BSTx, (uint8_t) CRC8); + I2C_ITConfig(BSTx, I2C_IT_TXI, DISABLE); + } else { + crc8Cal((uint8_t) writeData[currentWriteBufferPointer]); + I2C_SendData(BSTx, (uint8_t) writeData[currentWriteBufferPointer++]); + } + } + } else if(bstWriteDataLen) { + I2C_SendData(BSTx, (uint8_t) dataBuffer[dataBufferPointer]); + if(bstWriteDataLen > 1) + dataBufferPointer++; + if(dataBufferPointer == bstWriteDataLen) { + I2C_ITConfig(BSTx, I2C_IT_TXI, DISABLE); + dataBufferPointer = 0; + bstWriteDataLen = 0; + } + } else { + } + I2C_ClearITPendingBit(BSTx, I2C_IT_TXIS); + } else if(I2C_GetITStatus(BSTx, I2C_IT_NACKF)) { + if(receiverAddress) { + receiverAddress = false; + I2C_ITConfig(BSTx, I2C_IT_TXI, DISABLE); + } + I2C_ClearITPendingBit(BSTx, I2C_IT_NACKF); + } else if(I2C_GetITStatus(BSTx, I2C_IT_STOPF)) { + if(bstWriteDataLen && dataBufferPointer == bstWriteDataLen) { + dataBufferPointer = 0; + bstWriteDataLen = 0; + } + I2C_ClearITPendingBit(BSTx, I2C_IT_STOPF); + } else if(I2C_GetITStatus(BSTx, I2C_IT_BERR) + || I2C_GetITStatus(BSTx, I2C_IT_ARLO) + || I2C_GetITStatus(BSTx, I2C_IT_OVR)) { + bstTimeoutUserCallback(); + I2C_ClearITPendingBit(BSTx, I2C_IT_BERR | I2C_IT_ARLO | I2C_IT_OVR); + } } void I2C1_EV_IRQHandler() { - I2C_EV_IRQHandler(); + I2C_EV_IRQHandler(); } void I2C2_EV_IRQHandler() { - I2C_EV_IRQHandler(); + I2C_EV_IRQHandler(); } uint32_t bstTimeoutUserCallback() { - if (BSTx == I2C1) { - bst1ErrorCount++; - } else { - bst2ErrorCount++; - } - I2C_GenerateSTOP(BSTx, ENABLE); - receiverAddress = false; - dataBufferPointer = 0; - bstWriteDataLen = 0; - I2C_ITConfig(BSTx, I2C_IT_TXI, DISABLE); - I2C_SoftwareResetCmd(BSTx); - return false; + if (BSTx == I2C1) { + bst1ErrorCount++; + } else { + bst2ErrorCount++; + } + I2C_GenerateSTOP(BSTx, ENABLE); + receiverAddress = false; + dataBufferPointer = 0; + bstWriteDataLen = 0; + I2C_ITConfig(BSTx, I2C_IT_TXI, DISABLE); + I2C_SoftwareResetCmd(BSTx); + return false; } void bstInitPort(I2C_TypeDef *BSTx/*, uint8_t Address*/) { - NVIC_InitTypeDef nvic; - GPIO_InitTypeDef GPIO_InitStructure; - I2C_InitTypeDef BST_InitStructure; + NVIC_InitTypeDef nvic; + GPIO_InitTypeDef GPIO_InitStructure; + I2C_InitTypeDef BST_InitStructure; - if(BSTx == I2C1) { - RCC_AHBPeriphClockCmd(BST1_SCL_CLK_SOURCE | BST1_SDA_CLK_SOURCE, ENABLE); - RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1, ENABLE); - RCC_I2CCLKConfig(RCC_I2C1CLK_SYSCLK); + if(BSTx == I2C1) { + RCC_AHBPeriphClockCmd(BST1_SCL_CLK_SOURCE | BST1_SDA_CLK_SOURCE, ENABLE); + RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1, ENABLE); + RCC_I2CCLKConfig(RCC_I2C1CLK_SYSCLK); - GPIO_PinAFConfig(BST1_SCL_GPIO, BST1_SCL_PIN_SOURCE, BST1_SCL_GPIO_AF); - GPIO_PinAFConfig(BST1_SDA_GPIO, BST1_SDA_PIN_SOURCE, BST1_SDA_GPIO_AF); + GPIO_PinAFConfig(BST1_SCL_GPIO, BST1_SCL_PIN_SOURCE, BST1_SCL_GPIO_AF); + GPIO_PinAFConfig(BST1_SDA_GPIO, BST1_SDA_PIN_SOURCE, BST1_SDA_GPIO_AF); - GPIO_StructInit(&GPIO_InitStructure); - I2C_StructInit(&BST_InitStructure); + GPIO_StructInit(&GPIO_InitStructure); + I2C_StructInit(&BST_InitStructure); - // Init pins - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; + // Init pins + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; - GPIO_InitStructure.GPIO_Pin = BST1_SCL_PIN; - GPIO_Init(BST1_SCL_GPIO, &GPIO_InitStructure); + GPIO_InitStructure.GPIO_Pin = BST1_SCL_PIN; + GPIO_Init(BST1_SCL_GPIO, &GPIO_InitStructure); - GPIO_InitStructure.GPIO_Pin = BST1_SDA_PIN; - GPIO_Init(BST1_SDA_GPIO, &GPIO_InitStructure); + GPIO_InitStructure.GPIO_Pin = BST1_SDA_PIN; + GPIO_Init(BST1_SDA_GPIO, &GPIO_InitStructure); - I2C_StructInit(&BST_InitStructure); + I2C_StructInit(&BST_InitStructure); - BST_InitStructure.I2C_Mode = I2C_Mode_I2C; - BST_InitStructure.I2C_AnalogFilter = I2C_AnalogFilter_Enable; - BST_InitStructure.I2C_DigitalFilter = 0x00; - BST_InitStructure.I2C_OwnAddress1 = CLEANFLIGHT_FC; - BST_InitStructure.I2C_Ack = I2C_Ack_Enable; - BST_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit; - BST_InitStructure.I2C_Timing = 0x30E0257A; // 100 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10. + BST_InitStructure.I2C_Mode = I2C_Mode_I2C; + BST_InitStructure.I2C_AnalogFilter = I2C_AnalogFilter_Enable; + BST_InitStructure.I2C_DigitalFilter = 0x00; + BST_InitStructure.I2C_OwnAddress1 = CLEANFLIGHT_FC; + BST_InitStructure.I2C_Ack = I2C_Ack_Enable; + BST_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit; + BST_InitStructure.I2C_Timing = 0x30E0257A; // 100 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10. - I2C_Init(I2C1, &BST_InitStructure); + I2C_Init(I2C1, &BST_InitStructure); - I2C_GeneralCallCmd(I2C1, ENABLE); + I2C_GeneralCallCmd(I2C1, ENABLE); - nvic.NVIC_IRQChannel = I2C1_EV_IRQn; - nvic.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_BST_READ_DATA); - nvic.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_BST_READ_DATA); - nvic.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&nvic); + nvic.NVIC_IRQChannel = I2C1_EV_IRQn; + nvic.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_BST_READ_DATA); + nvic.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_BST_READ_DATA); + nvic.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&nvic); - I2C_ITConfig(I2C1, I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_ERRI, ENABLE); + I2C_ITConfig(I2C1, I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_ERRI, ENABLE); - I2C_Cmd(I2C1, ENABLE); - } + I2C_Cmd(I2C1, ENABLE); + } - if(BSTx == I2C2) { - RCC_AHBPeriphClockCmd(BST2_SCL_CLK_SOURCE | BST2_SDA_CLK_SOURCE, ENABLE); - RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C2, ENABLE); - RCC_I2CCLKConfig(RCC_I2C2CLK_SYSCLK); + if(BSTx == I2C2) { + RCC_AHBPeriphClockCmd(BST2_SCL_CLK_SOURCE | BST2_SDA_CLK_SOURCE, ENABLE); + RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C2, ENABLE); + RCC_I2CCLKConfig(RCC_I2C2CLK_SYSCLK); - GPIO_PinAFConfig(BST2_SCL_GPIO, BST2_SCL_PIN_SOURCE, BST2_SCL_GPIO_AF); - GPIO_PinAFConfig(BST2_SDA_GPIO, BST2_SDA_PIN_SOURCE, BST2_SDA_GPIO_AF); + GPIO_PinAFConfig(BST2_SCL_GPIO, BST2_SCL_PIN_SOURCE, BST2_SCL_GPIO_AF); + GPIO_PinAFConfig(BST2_SDA_GPIO, BST2_SDA_PIN_SOURCE, BST2_SDA_GPIO_AF); - GPIO_StructInit(&GPIO_InitStructure); - I2C_StructInit(&BST_InitStructure); + GPIO_StructInit(&GPIO_InitStructure); + I2C_StructInit(&BST_InitStructure); - // Init pins - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; + // Init pins + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; - GPIO_InitStructure.GPIO_Pin = BST2_SCL_PIN; - GPIO_Init(BST2_SCL_GPIO, &GPIO_InitStructure); + GPIO_InitStructure.GPIO_Pin = BST2_SCL_PIN; + GPIO_Init(BST2_SCL_GPIO, &GPIO_InitStructure); - GPIO_InitStructure.GPIO_Pin = BST2_SDA_PIN; - GPIO_Init(BST2_SDA_GPIO, &GPIO_InitStructure); + GPIO_InitStructure.GPIO_Pin = BST2_SDA_PIN; + GPIO_Init(BST2_SDA_GPIO, &GPIO_InitStructure); - I2C_StructInit(&BST_InitStructure); + I2C_StructInit(&BST_InitStructure); - BST_InitStructure.I2C_Mode = I2C_Mode_I2C; - BST_InitStructure.I2C_AnalogFilter = I2C_AnalogFilter_Enable; - BST_InitStructure.I2C_DigitalFilter = 0x00; - BST_InitStructure.I2C_OwnAddress1 = CLEANFLIGHT_FC; - BST_InitStructure.I2C_Ack = I2C_Ack_Enable; - BST_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit; - BST_InitStructure.I2C_Timing = 0x30E0257A; // 100 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10. + BST_InitStructure.I2C_Mode = I2C_Mode_I2C; + BST_InitStructure.I2C_AnalogFilter = I2C_AnalogFilter_Enable; + BST_InitStructure.I2C_DigitalFilter = 0x00; + BST_InitStructure.I2C_OwnAddress1 = CLEANFLIGHT_FC; + BST_InitStructure.I2C_Ack = I2C_Ack_Enable; + BST_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit; + BST_InitStructure.I2C_Timing = 0x30E0257A; // 100 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10. - I2C_Init(I2C2, &BST_InitStructure); + I2C_Init(I2C2, &BST_InitStructure); - I2C_GeneralCallCmd(I2C2, ENABLE); + I2C_GeneralCallCmd(I2C2, ENABLE); - nvic.NVIC_IRQChannel = I2C2_EV_IRQn; - nvic.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_BST_READ_DATA); - nvic.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_BST_READ_DATA); - nvic.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&nvic); + nvic.NVIC_IRQChannel = I2C2_EV_IRQn; + nvic.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_BST_READ_DATA); + nvic.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_BST_READ_DATA); + nvic.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&nvic); - I2C_ITConfig(I2C2, I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_ERRI, ENABLE); + I2C_ITConfig(I2C2, I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_ERRI, ENABLE); - I2C_Cmd(I2C2, ENABLE); - } + I2C_Cmd(I2C2, ENABLE); + } } void bstInit(BSTDevice index) @@ -297,83 +314,83 @@ uint16_t bstGetErrorCounter(void) bool bstWriteBusy(void) { - if(bstWriteDataLen) - return true; - else - return false; + if(bstWriteDataLen) + return true; + else + return false; } bool bstMasterWrite(uint8_t* data) { - if(bstWriteDataLen==0) { - CRC8 = 0; - dataBufferPointer = 0; - dataBuffer[0] = *data; - dataBuffer[1] = *(data+1); - bstWriteDataLen = dataBuffer[1] + 2; - for(uint8_t i=2; iIDR&BST1_SCL_PIN; - else - scl_set = BST2_SCL_GPIO->IDR&BST2_SCL_PIN; - if(I2C_GetFlagStatus(BSTx, I2C_FLAG_BUSY)==RESET && scl_set) { - I2C_TransferHandling(BSTx, dataBuffer[dataBufferPointer], dataBuffer[dataBufferPointer+1]+1, I2C_AutoEnd_Mode, I2C_Generate_Start_Write); - I2C_ITConfig(BSTx, I2C_IT_TXI, ENABLE); - dataBufferPointer = 1; - bstMasterWriteTimeout = micros(); - } - } else if(currentTime>bstMasterWriteTimeout+BST_SHORT_TIMEOUT) { - bstTimeoutUserCallback(); - } + static uint32_t bstMasterWriteTimeout = 0; + uint32_t currentTime = micros(); + if(bstWriteDataLen && dataBufferPointer==0) { + bool scl_set = false; + if(BSTx == I2C1) + scl_set = BST1_SCL_GPIO->IDR&BST1_SCL_PIN; + else + scl_set = BST2_SCL_GPIO->IDR&BST2_SCL_PIN; + if(I2C_GetFlagStatus(BSTx, I2C_FLAG_BUSY)==RESET && scl_set) { + I2C_TransferHandling(BSTx, dataBuffer[dataBufferPointer], dataBuffer[dataBufferPointer+1]+1, I2C_AutoEnd_Mode, I2C_Generate_Start_Write); + I2C_ITConfig(BSTx, I2C_IT_TXI, ENABLE); + dataBufferPointer = 1; + bstMasterWriteTimeout = micros(); + } + } else if(currentTime>bstMasterWriteTimeout+BST_SHORT_TIMEOUT) { + bstTimeoutUserCallback(); + } } /*************************************************************************************************/ void crc8Cal(uint8_t data_in) { - /* Polynom = x^8+x^7+x^6+x^4+x^2+1 = x^8+x^7+x^6+x^4+x^2+X^0 */ - uint8_t Polynom = BST_CRC_POLYNOM; - bool MSB_Flag; + /* Polynom = x^8+x^7+x^6+x^4+x^2+1 = x^8+x^7+x^6+x^4+x^2+X^0 */ + uint8_t Polynom = BST_CRC_POLYNOM; + bool MSB_Flag; - /* Step through each bit of the BYTE (8-bits) */ - for (uint8_t i = 0; i < 8; i++) { - /* Clear the Flag */ - MSB_Flag = false; + /* Step through each bit of the BYTE (8-bits) */ + for (uint8_t i = 0; i < 8; i++) { + /* Clear the Flag */ + MSB_Flag = false; - /* MSB_Set = 80; */ - if (CRC8 & 0x80) { - MSB_Flag = true; - } - - CRC8 <<= 1; + /* MSB_Set = 80; */ + if (CRC8 & 0x80) { + MSB_Flag = true; + } - /* MSB_Set = 80; */ - if (data_in & 0x80) { - CRC8++; - } - data_in <<= 1; - - if (MSB_Flag == true) { - CRC8 ^= Polynom; - } - } + CRC8 <<= 1; + + /* MSB_Set = 80; */ + if (data_in & 0x80) { + CRC8++; + } + data_in <<= 1; + + if (MSB_Flag == true) { + CRC8 ^= Polynom; + } + } } #endif diff --git a/src/main/target/COLIBRI_RACE/i2c_bst.c b/src/main/target/COLIBRI_RACE/i2c_bst.c index ec7122ddea..10c99ccc01 100644 --- a/src/main/target/COLIBRI_RACE/i2c_bst.c +++ b/src/main/target/COLIBRI_RACE/i2c_bst.c @@ -193,14 +193,14 @@ static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER; // DEPRECATED - Use BST_BUILD_INFO instead #define BST_BF_BUILD_INFO 69 //out message build date as well as some space for future expansion -#define BST_DISARM 70 //in message to disarm -#define BST_ENABLE_ARM 71 //in message to enable arm +#define BST_DISARM 70 //in message to disarm +#define BST_ENABLE_ARM 71 //in message to enable arm -#define BST_DEADBAND 72 //out message -#define BST_SET_DEADBAND 73 //in message +#define BST_DEADBAND 72 //out message +#define BST_SET_DEADBAND 73 //in message -#define BST_FC_FILTERS 74 //out message -#define BST_SET_FC_FILTERS 75 //in message +#define BST_FC_FILTERS 74 //out message +#define BST_SET_FC_FILTERS 75 //in message // // Multwii original MSP commands @@ -291,12 +291,12 @@ static const char pidnames[] = "MAG;" "VEL;"; -#define BOARD_IDENTIFIER_LENGTH 4 +#define BOARD_IDENTIFIER_LENGTH 4 typedef struct box_e { - const uint8_t boxId; // see boxId_e - const char *boxName; // GUI-readable box name - const uint8_t permanentId; // + const uint8_t boxId; // see boxId_e + const char *boxName; // GUI-readable box name + const uint8_t permanentId; // } box_t; // FIXME remove ;'s @@ -338,26 +338,26 @@ extern uint8_t writeData[DATA_BUFFER_SIZE]; /*************************************************************************************************/ uint8_t writeBufferPointer = 1; static void bstWrite8(uint8_t data) { - writeData[writeBufferPointer++] = data; - writeData[0] = writeBufferPointer; + writeData[writeBufferPointer++] = data; + writeData[0] = writeBufferPointer; } static void bstWrite16(uint16_t data) { - bstWrite8((uint8_t)(data >> 0)); - bstWrite8((uint8_t)(data >> 8)); + bstWrite8((uint8_t)(data >> 0)); + bstWrite8((uint8_t)(data >> 8)); } static void bstWrite32(uint32_t data) { - bstWrite16((uint16_t)(data >> 0)); - bstWrite16((uint16_t)(data >> 16)); + bstWrite16((uint16_t)(data >> 0)); + bstWrite16((uint16_t)(data >> 16)); } uint8_t readBufferPointer = 4; static uint8_t bstCurrentAddress(void) { - return readData[0]; + return readData[0]; } static uint8_t bstRead8(void) @@ -381,25 +381,25 @@ static uint32_t bstRead32(void) static uint8_t bstReadDataSize(void) { - return readData[1]-5; + return readData[1]-5; } static uint8_t bstReadCRC(void) { - return readData[readData[1]+1]; + return readData[readData[1]+1]; } static void s_struct(uint8_t *cb, uint8_t siz) { while (siz--) - bstWrite8(*cb++); + bstWrite8(*cb++); } static void bstWriteNames(const char *s) { const char *c; for (c = s; *c; c++) - bstWrite8(*c); + bstWrite8(*c); } static const box_t *findBoxByActiveBoxId(uint8_t activeBoxId) @@ -449,7 +449,7 @@ reset: count += len; } else { for (j = 0; j < len; j++) - bstWrite8(box->boxName[j]); + bstWrite8(box->boxName[j]); } } @@ -462,1050 +462,1053 @@ reset: static void bstWriteDataflashSummaryReply(void) { #ifdef USE_FLASHFS - const flashGeometry_t *geometry = flashfsGetGeometry(); - bstWrite8(flashfsIsReady() ? 1 : 0); - bstWrite32(geometry->sectors); - bstWrite32(geometry->totalSize); - bstWrite32(flashfsGetOffset()); // Effectively the current number of bytes stored on the volume + const flashGeometry_t *geometry = flashfsGetGeometry(); + bstWrite8(flashfsIsReady() ? 1 : 0); + bstWrite32(geometry->sectors); + bstWrite32(geometry->totalSize); + bstWrite32(flashfsGetOffset()); // Effectively the current number of bytes stored on the volume #else - bstWrite8(0); - bstWrite32(0); - bstWrite32(0); - bstWrite32(0); + bstWrite8(0); + bstWrite32(0); + bstWrite32(0); + bstWrite32(0); #endif } #ifdef USE_FLASHFS static void bstWriteDataflashReadReply(uint32_t address, uint8_t size) { - uint8_t buffer[128]; - int bytesRead; + uint8_t buffer[128]; + int bytesRead; - if (size > sizeof(buffer)) { - size = sizeof(buffer); - } + if (size > sizeof(buffer)) { + size = sizeof(buffer); + } - bstWrite32(address); + bstWrite32(address); - // bytesRead will be lower than that requested if we reach end of volume - bytesRead = flashfsReadAbs(address, buffer, size); + // bytesRead will be lower than that requested if we reach end of volume + bytesRead = flashfsReadAbs(address, buffer, size); - for (int i = 0; i < bytesRead; i++) { - bstWrite8(buffer[i]); - } + for (int i = 0; i < bytesRead; i++) { + bstWrite8(buffer[i]); + } } #endif #define IS_ENABLED(mask) (mask == 0 ? 0 : 1) /*************************************************************************************************/ -#define BST_USB_COMMANDS 0x0A -#define BST_GENERAL_HEARTBEAT 0x0B -#define BST_USB_DEVICE_INFO_REQUEST 0x04 //Handshake -#define BST_USB_DEVICE_INFO_FRAME 0x05 //Handshake -#define BST_READ_COMMANDS 0x26 -#define BST_WRITE_COMMANDS 0x25 -#define BST_PASSED 0x01 -#define BST_FAILED 0x00 +#define BST_USB_COMMANDS 0x0A +#define BST_GENERAL_HEARTBEAT 0x0B +#define BST_USB_DEVICE_INFO_REQUEST 0x04 //Handshake +#define BST_USB_DEVICE_INFO_FRAME 0x05 //Handshake +#define BST_READ_COMMANDS 0x26 +#define BST_WRITE_COMMANDS 0x25 +#define BST_PASSED 0x01 +#define BST_FAILED 0x00 static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest) { - uint32_t i, tmp, junk; + uint32_t i, tmp, junk; #ifdef GPS - uint8_t wp_no; - int32_t lat = 0, lon = 0; + uint8_t wp_no; + int32_t lat = 0, lon = 0; #endif - switch(bstRequest) { - case BST_API_VERSION: - bstWrite8(BST_PROTOCOL_VERSION); + switch(bstRequest) { + case BST_API_VERSION: + bstWrite8(BST_PROTOCOL_VERSION); - bstWrite8(API_VERSION_MAJOR); - bstWrite8(API_VERSION_MINOR); - break; - case BST_FC_VARIANT: - for (i = 0; i < FLIGHT_CONTROLLER_IDENTIFIER_LENGTH; i++) { - bstWrite8(flightControllerIdentifier[i]); - } - break; - case BST_FC_VERSION: - bstWrite8(FC_VERSION_MAJOR); - bstWrite8(FC_VERSION_MINOR); - bstWrite8(FC_VERSION_PATCH_LEVEL); - break; - case BST_BOARD_INFO: - for (i = 0; i < BOARD_IDENTIFIER_LENGTH; i++) { - bstWrite8(boardIdentifier[i]); - } - break; - case BST_BUILD_INFO: - for (i = 0; i < BUILD_DATE_LENGTH; i++) { - bstWrite8(buildDate[i]); - } - for (i = 0; i < BUILD_TIME_LENGTH; i++) { - bstWrite8(buildTime[i]); - } + bstWrite8(API_VERSION_MAJOR); + bstWrite8(API_VERSION_MINOR); + break; + case BST_FC_VARIANT: + for (i = 0; i < FLIGHT_CONTROLLER_IDENTIFIER_LENGTH; i++) { + bstWrite8(flightControllerIdentifier[i]); + } + break; + case BST_FC_VERSION: + bstWrite8(FC_VERSION_MAJOR); + bstWrite8(FC_VERSION_MINOR); + bstWrite8(FC_VERSION_PATCH_LEVEL); + break; + case BST_BOARD_INFO: + for (i = 0; i < BOARD_IDENTIFIER_LENGTH; i++) { + bstWrite8(boardIdentifier[i]); + } + break; + case BST_BUILD_INFO: + for (i = 0; i < BUILD_DATE_LENGTH; i++) { + bstWrite8(buildDate[i]); + } + for (i = 0; i < BUILD_TIME_LENGTH; i++) { + bstWrite8(buildTime[i]); + } - for (i = 0; i < GIT_SHORT_REVISION_LENGTH; i++) { - bstWrite8(shortGitRevision[i]); - } - break; - // DEPRECATED - Use MSP_API_VERSION - case BST_IDENT: - bstWrite8(MW_VERSION); - bstWrite8(masterConfig.mixerMode); - bstWrite8(BST_PROTOCOL_VERSION); - bstWrite32(CAP_DYNBALANCE); // "capability" - break; + for (i = 0; i < GIT_SHORT_REVISION_LENGTH; i++) { + bstWrite8(shortGitRevision[i]); + } + break; + // DEPRECATED - Use MSP_API_VERSION + case BST_IDENT: + bstWrite8(MW_VERSION); + bstWrite8(masterConfig.mixerMode); + bstWrite8(BST_PROTOCOL_VERSION); + bstWrite32(CAP_DYNBALANCE); // "capability" + break; - case BST_STATUS: - bstWrite16(cycleTime); + case BST_STATUS: + bstWrite16(cycleTime); #ifdef USE_I2C - bstWrite16(i2cGetErrorCounter()); + bstWrite16(i2cGetErrorCounter()); #else - bstWrite16(0); + bstWrite16(0); #endif - bstWrite16(sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_SONAR) << 4); - // BST the flags in the order we delivered them, ignoring BOXNAMES and BOXINDEXES - // Requires new Multiwii protocol version to fix - // It would be preferable to setting the enabled bits based on BOXINDEX. - junk = 0; - tmp = IS_ENABLED(FLIGHT_MODE(ANGLE_MODE)) << BOXANGLE | - IS_ENABLED(FLIGHT_MODE(HORIZON_MODE)) << BOXHORIZON | - IS_ENABLED(FLIGHT_MODE(BARO_MODE)) << BOXBARO | - IS_ENABLED(FLIGHT_MODE(MAG_MODE)) << BOXMAG | - IS_ENABLED(FLIGHT_MODE(HEADFREE_MODE)) << BOXHEADFREE | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXHEADADJ)) << BOXHEADADJ | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXCAMSTAB)) << BOXCAMSTAB | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXCAMTRIG)) << BOXCAMTRIG | - IS_ENABLED(FLIGHT_MODE(GPS_HOME_MODE)) << BOXGPSHOME | - IS_ENABLED(FLIGHT_MODE(GPS_HOLD_MODE)) << BOXGPSHOLD | - IS_ENABLED(FLIGHT_MODE(PASSTHRU_MODE)) << BOXPASSTHRU | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXBEEPERON)) << BOXBEEPERON | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXLEDMAX)) << BOXLEDMAX | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXLEDLOW)) << BOXLEDLOW | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXLLIGHTS)) << BOXLLIGHTS | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXCALIB)) << BOXCALIB | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXGOV)) << BOXGOV | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXOSD)) << BOXOSD | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXTELEMETRY)) << BOXTELEMETRY | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXGTUNE)) << BOXGTUNE | - IS_ENABLED(FLIGHT_MODE(SONAR_MODE)) << BOXSONAR | - IS_ENABLED(ARMING_FLAG(ARMED)) << BOXARM | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXBLACKBOX)) << BOXBLACKBOX | - IS_ENABLED(FLIGHT_MODE(FAILSAFE_MODE)) << BOXFAILSAFE; - for (i = 0; i < activeBoxIdCount; i++) { - int flag = (tmp & (1 << activeBoxIds[i])); - if (flag) - junk |= 1 << i; - } - bstWrite32(junk); - bstWrite8(masterConfig.current_profile_index); - break; - case BST_RAW_IMU: - { - // Hack scale due to choice of units for sensor data in multiwii - uint8_t scale = (acc.acc_1G > 1024) ? 8 : 1; + bstWrite16(sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_SONAR) << 4); + // BST the flags in the order we delivered them, ignoring BOXNAMES and BOXINDEXES + // Requires new Multiwii protocol version to fix + // It would be preferable to setting the enabled bits based on BOXINDEX. + junk = 0; + tmp = IS_ENABLED(FLIGHT_MODE(ANGLE_MODE)) << BOXANGLE | + IS_ENABLED(FLIGHT_MODE(HORIZON_MODE)) << BOXHORIZON | + IS_ENABLED(FLIGHT_MODE(BARO_MODE)) << BOXBARO | + IS_ENABLED(FLIGHT_MODE(MAG_MODE)) << BOXMAG | + IS_ENABLED(FLIGHT_MODE(HEADFREE_MODE)) << BOXHEADFREE | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXHEADADJ)) << BOXHEADADJ | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXCAMSTAB)) << BOXCAMSTAB | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXCAMTRIG)) << BOXCAMTRIG | + IS_ENABLED(FLIGHT_MODE(GPS_HOME_MODE)) << BOXGPSHOME | + IS_ENABLED(FLIGHT_MODE(GPS_HOLD_MODE)) << BOXGPSHOLD | + IS_ENABLED(FLIGHT_MODE(PASSTHRU_MODE)) << BOXPASSTHRU | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXBEEPERON)) << BOXBEEPERON | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXLEDMAX)) << BOXLEDMAX | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXLEDLOW)) << BOXLEDLOW | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXLLIGHTS)) << BOXLLIGHTS | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXCALIB)) << BOXCALIB | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXGOV)) << BOXGOV | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXOSD)) << BOXOSD | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXTELEMETRY)) << BOXTELEMETRY | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXGTUNE)) << BOXGTUNE | + IS_ENABLED(FLIGHT_MODE(SONAR_MODE)) << BOXSONAR | + IS_ENABLED(ARMING_FLAG(ARMED)) << BOXARM | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXBLACKBOX)) << BOXBLACKBOX | + IS_ENABLED(FLIGHT_MODE(FAILSAFE_MODE)) << BOXFAILSAFE; + for (i = 0; i < activeBoxIdCount; i++) { + int flag = (tmp & (1 << activeBoxIds[i])); + if (flag) + junk |= 1 << i; + } + bstWrite32(junk); + bstWrite8(masterConfig.current_profile_index); + break; + case BST_RAW_IMU: + { + // Hack scale due to choice of units for sensor data in multiwii + uint8_t scale = (acc.acc_1G > 1024) ? 8 : 1; - for (i = 0; i < 3; i++) - bstWrite16(accSmooth[i] / scale); - for (i = 0; i < 3; i++) - bstWrite16(gyroADC[i]); - for (i = 0; i < 3; i++) - bstWrite16(magADC[i]); - } - break; + for (i = 0; i < 3; i++) + bstWrite16(accSmooth[i] / scale); + for (i = 0; i < 3; i++) + bstWrite16(gyroADC[i]); + for (i = 0; i < 3; i++) + bstWrite16(magADC[i]); + } + break; #ifdef USE_SERVOS - case BST_SERVO: - s_struct((uint8_t *)&servo, MAX_SUPPORTED_SERVOS * 2); - break; - case BST_SERVO_CONFIGURATIONS: - for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) { - bstWrite16(masterConfig.servoConf[i].min); - bstWrite16(masterConfig.servoConf[i].max); - bstWrite16(masterConfig.servoConf[i].middle); - bstWrite8(masterConfig.servoConf[i].rate); - bstWrite8(masterConfig.servoConf[i].angleAtMin); - bstWrite8(masterConfig.servoConf[i].angleAtMax); - bstWrite8(masterConfig.servoConf[i].forwardFromChannel); - bstWrite32(masterConfig.servoConf[i].reversedSources); - } - break; - case BST_SERVO_MIX_RULES: - for (i = 0; i < MAX_SERVO_RULES; i++) { - bstWrite8(masterConfig.customServoMixer[i].targetChannel); - bstWrite8(masterConfig.customServoMixer[i].inputSource); - bstWrite8(masterConfig.customServoMixer[i].rate); - bstWrite8(masterConfig.customServoMixer[i].speed); - bstWrite8(masterConfig.customServoMixer[i].min); - bstWrite8(masterConfig.customServoMixer[i].max); - bstWrite8(masterConfig.customServoMixer[i].box); - } - break; + case BST_SERVO: + s_struct((uint8_t *)&servo, MAX_SUPPORTED_SERVOS * 2); + break; + case BST_SERVO_CONFIGURATIONS: + for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) { + bstWrite16(masterConfig.servoConf[i].min); + bstWrite16(masterConfig.servoConf[i].max); + bstWrite16(masterConfig.servoConf[i].middle); + bstWrite8(masterConfig.servoConf[i].rate); + bstWrite8(masterConfig.servoConf[i].angleAtMin); + bstWrite8(masterConfig.servoConf[i].angleAtMax); + bstWrite8(masterConfig.servoConf[i].forwardFromChannel); + bstWrite32(masterConfig.servoConf[i].reversedSources); + } + break; + case BST_SERVO_MIX_RULES: + for (i = 0; i < MAX_SERVO_RULES; i++) { + bstWrite8(masterConfig.customServoMixer[i].targetChannel); + bstWrite8(masterConfig.customServoMixer[i].inputSource); + bstWrite8(masterConfig.customServoMixer[i].rate); + bstWrite8(masterConfig.customServoMixer[i].speed); + bstWrite8(masterConfig.customServoMixer[i].min); + bstWrite8(masterConfig.customServoMixer[i].max); + bstWrite8(masterConfig.customServoMixer[i].box); + } + break; #endif - case BST_MOTOR: - s_struct((uint8_t *)motor, 16); - break; - case BST_RC: - for (i = 0; i < rxRuntimeConfig.channelCount; i++) - bstWrite16(rcData[i]); - break; - case BST_ATTITUDE: - for (i = 0; i < 2; i++) - bstWrite16(attitude.raw[i]); - //bstWrite16(heading); - break; - case BST_ALTITUDE: + case BST_MOTOR: + s_struct((uint8_t *)motor, 16); + break; + case BST_RC: + for (i = 0; i < rxRuntimeConfig.channelCount; i++) + bstWrite16(rcData[i]); + break; + case BST_ATTITUDE: + for (i = 0; i < 2; i++) + bstWrite16(attitude.raw[i]); + //bstWrite16(heading); + break; + case BST_ALTITUDE: #if defined(BARO) || defined(SONAR) - bstWrite32(altitudeHoldGetEstimatedAltitude()); + bstWrite32(altitudeHoldGetEstimatedAltitude()); #else - bstWrite32(0); + bstWrite32(0); #endif - bstWrite16(vario); - break; - case BST_SONAR_ALTITUDE: + bstWrite16(vario); + break; + case BST_SONAR_ALTITUDE: #if defined(SONAR) - bstWrite32(sonarGetLatestAltitude()); + bstWrite32(sonarGetLatestAltitude()); #else - bstWrite32(0); + bstWrite32(0); #endif - break; - case BST_ANALOG: - bstWrite8((uint8_t)constrain(vbat, 0, 255)); - bstWrite16((uint16_t)constrain(mAhDrawn, 0, 0xFFFF)); // milliamp hours drawn from battery - bstWrite16(rssi); - if(masterConfig.batteryConfig.multiwiiCurrentMeterOutput) { - bstWrite16((uint16_t)constrain(amperage * 10, 0, 0xFFFF)); // send amperage in 0.001 A steps. Negative range is truncated to zero - } else - bstWrite16((int16_t)constrain(amperage, -0x8000, 0x7FFF)); // send amperage in 0.01 A steps, range is -320A to 320A - break; - case BST_ARMING_CONFIG: - bstWrite8(masterConfig.auto_disarm_delay); - bstWrite8(masterConfig.disarm_kill_switch); - break; - case BST_LOOP_TIME: - //bstWrite16(masterConfig.looptime); - bstWrite16(cycleTime); - break; - case BST_RC_TUNING: - bstWrite8(currentControlRateProfile->rcRate8); - bstWrite8(currentControlRateProfile->rcExpo8); - for (i = 0 ; i < 3; i++) { - bstWrite8(currentControlRateProfile->rates[i]); // R,P,Y see flight_dynamics_index_t - } - bstWrite8(currentControlRateProfile->dynThrPID); - bstWrite8(currentControlRateProfile->thrMid8); - bstWrite8(currentControlRateProfile->thrExpo8); - bstWrite16(currentControlRateProfile->tpa_breakpoint); - bstWrite8(currentControlRateProfile->rcYawExpo8); - break; - case BST_PID: - for (i = 0; i < PID_ITEM_COUNT; i++) { - bstWrite8(currentProfile->pidProfile.P8[i]); - bstWrite8(currentProfile->pidProfile.I8[i]); - bstWrite8(currentProfile->pidProfile.D8[i]); - } - break; - case BST_PIDNAMES: - bstWriteNames(pidnames); - break; - case BST_PID_CONTROLLER: - bstWrite8(currentProfile->pidProfile.pidController); - break; - case BST_MODE_RANGES: - for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) { - modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i]; - const box_t *box = &boxes[mac->modeId]; - bstWrite8(box->permanentId); - bstWrite8(mac->auxChannelIndex); - bstWrite8(mac->range.startStep); - bstWrite8(mac->range.endStep); - } - break; - case BST_ADJUSTMENT_RANGES: - for (i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) { - adjustmentRange_t *adjRange = &masterConfig.adjustmentRanges[i]; - bstWrite8(adjRange->adjustmentIndex); - bstWrite8(adjRange->auxChannelIndex); - bstWrite8(adjRange->range.startStep); - bstWrite8(adjRange->range.endStep); - bstWrite8(adjRange->adjustmentFunction); - bstWrite8(adjRange->auxSwitchChannelIndex); - } - break; - case BST_BOXNAMES: - bstWriteBoxNamesReply(); - break; - case BST_BOXIDS: - for (i = 0; i < activeBoxIdCount; i++) { - const box_t *box = findBoxByActiveBoxId(activeBoxIds[i]); - if (!box) { - continue; - } - bstWrite8(box->permanentId); - } - break; - case BST_MISC: - bstWrite16(masterConfig.rxConfig.midrc); + break; + case BST_ANALOG: + bstWrite8((uint8_t)constrain(vbat, 0, 255)); + bstWrite16((uint16_t)constrain(mAhDrawn, 0, 0xFFFF)); // milliamp hours drawn from battery + bstWrite16(rssi); + if(masterConfig.batteryConfig.multiwiiCurrentMeterOutput) { + bstWrite16((uint16_t)constrain(amperage * 10, 0, 0xFFFF)); // send amperage in 0.001 A steps. Negative range is truncated to zero + } else + bstWrite16((int16_t)constrain(amperage, -0x8000, 0x7FFF)); // send amperage in 0.01 A steps, range is -320A to 320A + break; + case BST_ARMING_CONFIG: + bstWrite8(masterConfig.auto_disarm_delay); + bstWrite8(masterConfig.disarm_kill_switch); + break; + case BST_LOOP_TIME: + //bstWrite16(masterConfig.looptime); + bstWrite16(cycleTime); + break; + case BST_RC_TUNING: + bstWrite8(currentControlRateProfile->rcRate8); + bstWrite8(currentControlRateProfile->rcExpo8); + for (i = 0 ; i < 3; i++) { + bstWrite8(currentControlRateProfile->rates[i]); // R,P,Y see flight_dynamics_index_t + } + bstWrite8(currentControlRateProfile->dynThrPID); + bstWrite8(currentControlRateProfile->thrMid8); + bstWrite8(currentControlRateProfile->thrExpo8); + bstWrite16(currentControlRateProfile->tpa_breakpoint); + bstWrite8(currentControlRateProfile->rcYawExpo8); + break; + case BST_PID: + for (i = 0; i < PID_ITEM_COUNT; i++) { + bstWrite8(currentProfile->pidProfile.P8[i]); + bstWrite8(currentProfile->pidProfile.I8[i]); + bstWrite8(currentProfile->pidProfile.D8[i]); + } + break; + case BST_PIDNAMES: + bstWriteNames(pidnames); + break; + case BST_PID_CONTROLLER: + bstWrite8(currentProfile->pidProfile.pidController); + break; + case BST_MODE_RANGES: + for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) { + modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i]; + const box_t *box = &boxes[mac->modeId]; + bstWrite8(box->permanentId); + bstWrite8(mac->auxChannelIndex); + bstWrite8(mac->range.startStep); + bstWrite8(mac->range.endStep); + } + break; + case BST_ADJUSTMENT_RANGES: + for (i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) { + adjustmentRange_t *adjRange = &masterConfig.adjustmentRanges[i]; + bstWrite8(adjRange->adjustmentIndex); + bstWrite8(adjRange->auxChannelIndex); + bstWrite8(adjRange->range.startStep); + bstWrite8(adjRange->range.endStep); + bstWrite8(adjRange->adjustmentFunction); + bstWrite8(adjRange->auxSwitchChannelIndex); + } + break; + case BST_BOXNAMES: + bstWriteBoxNamesReply(); + break; + case BST_BOXIDS: + for (i = 0; i < activeBoxIdCount; i++) { + const box_t *box = findBoxByActiveBoxId(activeBoxIds[i]); + if (!box) { + continue; + } + bstWrite8(box->permanentId); + } + break; + case BST_MISC: + bstWrite16(masterConfig.rxConfig.midrc); - bstWrite16(masterConfig.escAndServoConfig.minthrottle); - bstWrite16(masterConfig.escAndServoConfig.maxthrottle); - bstWrite16(masterConfig.escAndServoConfig.mincommand); + bstWrite16(masterConfig.escAndServoConfig.minthrottle); + bstWrite16(masterConfig.escAndServoConfig.maxthrottle); + bstWrite16(masterConfig.escAndServoConfig.mincommand); - bstWrite16(masterConfig.failsafeConfig.failsafe_throttle); + bstWrite16(masterConfig.failsafeConfig.failsafe_throttle); #ifdef GPS - bstWrite8(masterConfig.gpsConfig.provider); // gps_type - bstWrite8(0); // TODO gps_baudrate (an index, cleanflight uses a uint32_t - bstWrite8(masterConfig.gpsConfig.sbasMode); // gps_ubx_sbas + bstWrite8(masterConfig.gpsConfig.provider); // gps_type + bstWrite8(0); // TODO gps_baudrate (an index, cleanflight uses a uint32_t + bstWrite8(masterConfig.gpsConfig.sbasMode); // gps_ubx_sbas #else - bstWrite8(0); // gps_type - bstWrite8(0); // TODO gps_baudrate (an index, cleanflight uses a uint32_t - bstWrite8(0); // gps_ubx_sbas + bstWrite8(0); // gps_type + bstWrite8(0); // TODO gps_baudrate (an index, cleanflight uses a uint32_t + bstWrite8(0); // gps_ubx_sbas #endif - bstWrite8(masterConfig.batteryConfig.multiwiiCurrentMeterOutput); - bstWrite8(masterConfig.rxConfig.rssi_channel); - bstWrite8(0); + bstWrite8(masterConfig.batteryConfig.multiwiiCurrentMeterOutput); + bstWrite8(masterConfig.rxConfig.rssi_channel); + bstWrite8(0); - bstWrite16(masterConfig.mag_declination / 10); + bstWrite16(masterConfig.mag_declination / 10); - bstWrite8(masterConfig.batteryConfig.vbatscale); - bstWrite8(masterConfig.batteryConfig.vbatmincellvoltage); - bstWrite8(masterConfig.batteryConfig.vbatmaxcellvoltage); - bstWrite8(masterConfig.batteryConfig.vbatwarningcellvoltage); - break; - case BST_MOTOR_PINS: - // FIXME This is hardcoded and should not be. - for (i = 0; i < 8; i++) - bstWrite8(i + 1); - break; + bstWrite8(masterConfig.batteryConfig.vbatscale); + bstWrite8(masterConfig.batteryConfig.vbatmincellvoltage); + bstWrite8(masterConfig.batteryConfig.vbatmaxcellvoltage); + bstWrite8(masterConfig.batteryConfig.vbatwarningcellvoltage); + break; + case BST_MOTOR_PINS: + // FIXME This is hardcoded and should not be. + for (i = 0; i < 8; i++) + bstWrite8(i + 1); + break; #ifdef GPS - case BST_RAW_GPS: - bstWrite8(STATE(GPS_FIX)); - bstWrite8(GPS_numSat); - bstWrite32(GPS_coord[LAT]); - bstWrite32(GPS_coord[LON]); - bstWrite16(GPS_altitude); - bstWrite16(GPS_speed); - bstWrite16(GPS_ground_course); - break; - case BST_COMP_GPS: - bstWrite16(GPS_distanceToHome); - bstWrite16(GPS_directionToHome); - bstWrite8(GPS_update & 1); - break; - case BST_WP: - wp_no = bstRead8(); // get the wp number - if (wp_no == 0) { - lat = GPS_home[LAT]; - lon = GPS_home[LON]; - } else if (wp_no == 16) { - lat = GPS_hold[LAT]; - lon = GPS_hold[LON]; - } - bstWrite8(wp_no); - bstWrite32(lat); - bstWrite32(lon); - bstWrite32(AltHold); // altitude (cm) will come here -- temporary implementation to test feature with apps - bstWrite16(0); // heading will come here (deg) - bstWrite16(0); // time to stay (ms) will come here - bstWrite8(0); // nav flag will come here - break; - case BST_GPSSVINFO: - bstWrite8(GPS_numCh); - for (i = 0; i < GPS_numCh; i++){ - bstWrite8(GPS_svinfo_chn[i]); - bstWrite8(GPS_svinfo_svid[i]); - bstWrite8(GPS_svinfo_quality[i]); - bstWrite8(GPS_svinfo_cno[i]); - } - break; + case BST_RAW_GPS: + bstWrite8(STATE(GPS_FIX)); + bstWrite8(GPS_numSat); + bstWrite32(GPS_coord[LAT]); + bstWrite32(GPS_coord[LON]); + bstWrite16(GPS_altitude); + bstWrite16(GPS_speed); + bstWrite16(GPS_ground_course); + break; + case BST_COMP_GPS: + bstWrite16(GPS_distanceToHome); + bstWrite16(GPS_directionToHome); + bstWrite8(GPS_update & 1); + break; + case BST_WP: + wp_no = bstRead8(); // get the wp number + if (wp_no == 0) { + lat = GPS_home[LAT]; + lon = GPS_home[LON]; + } else if (wp_no == 16) { + lat = GPS_hold[LAT]; + lon = GPS_hold[LON]; + } + bstWrite8(wp_no); + bstWrite32(lat); + bstWrite32(lon); + bstWrite32(AltHold); // altitude (cm) will come here -- temporary implementation to test feature with apps + bstWrite16(0); // heading will come here (deg) + bstWrite16(0); // time to stay (ms) will come here + bstWrite8(0); // nav flag will come here + break; + case BST_GPSSVINFO: + bstWrite8(GPS_numCh); + for (i = 0; i < GPS_numCh; i++){ + bstWrite8(GPS_svinfo_chn[i]); + bstWrite8(GPS_svinfo_svid[i]); + bstWrite8(GPS_svinfo_quality[i]); + bstWrite8(GPS_svinfo_cno[i]); + } + break; #endif - case BST_DEBUG: - // output some useful QA statistics - // debug[x] = ((hse_value / 1000000) * 1000) + (SystemCoreClock / 1000000); // XX0YY [crystal clock : core clock] + case BST_DEBUG: + // output some useful QA statistics + // debug[x] = ((hse_value / 1000000) * 1000) + (SystemCoreClock / 1000000); // XX0YY [crystal clock : core clock] - for (i = 0; i < DEBUG16_VALUE_COUNT; i++) - bstWrite16(debug[i]); // 4 variables are here for general monitoring purpose - break; + for (i = 0; i < DEBUG16_VALUE_COUNT; i++) + bstWrite16(debug[i]); // 4 variables are here for general monitoring purpose + break; - // Additional commands that are not compatible with MultiWii - case BST_ACC_TRIM: - bstWrite16(masterConfig.accelerometerTrims.values.pitch); - bstWrite16(masterConfig.accelerometerTrims.values.roll); - break; + // Additional commands that are not compatible with MultiWii + case BST_ACC_TRIM: + bstWrite16(masterConfig.accelerometerTrims.values.pitch); + bstWrite16(masterConfig.accelerometerTrims.values.roll); + break; - case BST_UID: - bstWrite32(U_ID_0); - bstWrite32(U_ID_1); - bstWrite32(U_ID_2); - break; + case BST_UID: + bstWrite32(U_ID_0); + bstWrite32(U_ID_1); + bstWrite32(U_ID_2); + break; - case BST_FEATURE: - bstWrite32(featureMask()); - break; + case BST_FEATURE: + bstWrite32(featureMask()); + break; - case BST_BOARD_ALIGNMENT: - bstWrite16(masterConfig.boardAlignment.rollDegrees); - bstWrite16(masterConfig.boardAlignment.pitchDegrees); - bstWrite16(masterConfig.boardAlignment.yawDegrees); - break; + case BST_BOARD_ALIGNMENT: + bstWrite16(masterConfig.boardAlignment.rollDegrees); + bstWrite16(masterConfig.boardAlignment.pitchDegrees); + bstWrite16(masterConfig.boardAlignment.yawDegrees); + break; - case BST_VOLTAGE_METER_CONFIG: - bstWrite8(masterConfig.batteryConfig.vbatscale); - bstWrite8(masterConfig.batteryConfig.vbatmincellvoltage); - bstWrite8(masterConfig.batteryConfig.vbatmaxcellvoltage); - bstWrite8(masterConfig.batteryConfig.vbatwarningcellvoltage); - break; + case BST_VOLTAGE_METER_CONFIG: + bstWrite8(masterConfig.batteryConfig.vbatscale); + bstWrite8(masterConfig.batteryConfig.vbatmincellvoltage); + bstWrite8(masterConfig.batteryConfig.vbatmaxcellvoltage); + bstWrite8(masterConfig.batteryConfig.vbatwarningcellvoltage); + break; - case BST_CURRENT_METER_CONFIG: - bstWrite16(masterConfig.batteryConfig.currentMeterScale); - bstWrite16(masterConfig.batteryConfig.currentMeterOffset); - bstWrite8(masterConfig.batteryConfig.currentMeterType); - bstWrite16(masterConfig.batteryConfig.batteryCapacity); - break; + case BST_CURRENT_METER_CONFIG: + bstWrite16(masterConfig.batteryConfig.currentMeterScale); + bstWrite16(masterConfig.batteryConfig.currentMeterOffset); + bstWrite8(masterConfig.batteryConfig.currentMeterType); + bstWrite16(masterConfig.batteryConfig.batteryCapacity); + break; - case BST_MIXER: - bstWrite8(masterConfig.mixerMode); - break; + case BST_MIXER: + bstWrite8(masterConfig.mixerMode); + break; - case BST_RX_CONFIG: - bstWrite8(masterConfig.rxConfig.serialrx_provider); - bstWrite16(masterConfig.rxConfig.maxcheck); - bstWrite16(masterConfig.rxConfig.midrc); - bstWrite16(masterConfig.rxConfig.mincheck); - bstWrite8(masterConfig.rxConfig.spektrum_sat_bind); - bstWrite16(masterConfig.rxConfig.rx_min_usec); - bstWrite16(masterConfig.rxConfig.rx_max_usec); - break; + case BST_RX_CONFIG: + bstWrite8(masterConfig.rxConfig.serialrx_provider); + bstWrite16(masterConfig.rxConfig.maxcheck); + bstWrite16(masterConfig.rxConfig.midrc); + bstWrite16(masterConfig.rxConfig.mincheck); + bstWrite8(masterConfig.rxConfig.spektrum_sat_bind); + bstWrite16(masterConfig.rxConfig.rx_min_usec); + bstWrite16(masterConfig.rxConfig.rx_max_usec); + break; - case BST_FAILSAFE_CONFIG: - bstWrite8(masterConfig.failsafeConfig.failsafe_delay); - bstWrite8(masterConfig.failsafeConfig.failsafe_off_delay); - bstWrite16(masterConfig.failsafeConfig.failsafe_throttle); - break; + case BST_FAILSAFE_CONFIG: + bstWrite8(masterConfig.failsafeConfig.failsafe_delay); + bstWrite8(masterConfig.failsafeConfig.failsafe_off_delay); + bstWrite16(masterConfig.failsafeConfig.failsafe_throttle); + break; - case BST_RXFAIL_CONFIG: - for (i = NON_AUX_CHANNEL_COUNT; i < rxRuntimeConfig.channelCount; i++) { - bstWrite8(masterConfig.rxConfig.failsafe_channel_configurations[i].mode); - bstWrite16(RXFAIL_STEP_TO_CHANNEL_VALUE(masterConfig.rxConfig.failsafe_channel_configurations[i].step)); - } - break; + case BST_RXFAIL_CONFIG: + for (i = NON_AUX_CHANNEL_COUNT; i < rxRuntimeConfig.channelCount; i++) { + bstWrite8(masterConfig.rxConfig.failsafe_channel_configurations[i].mode); + bstWrite16(RXFAIL_STEP_TO_CHANNEL_VALUE(masterConfig.rxConfig.failsafe_channel_configurations[i].step)); + } + break; - case BST_RSSI_CONFIG: - bstWrite8(masterConfig.rxConfig.rssi_channel); - break; + case BST_RSSI_CONFIG: + bstWrite8(masterConfig.rxConfig.rssi_channel); + break; - case BST_RX_MAP: - for (i = 0; i < MAX_MAPPABLE_RX_INPUTS; i++) - bstWrite8(masterConfig.rxConfig.rcmap[i]); - break; + case BST_RX_MAP: + for (i = 0; i < MAX_MAPPABLE_RX_INPUTS; i++) + bstWrite8(masterConfig.rxConfig.rcmap[i]); + break; - case BST_BF_CONFIG: - bstWrite8(masterConfig.mixerMode); + case BST_BF_CONFIG: + bstWrite8(masterConfig.mixerMode); - bstWrite32(featureMask()); + bstWrite32(featureMask()); - bstWrite8(masterConfig.rxConfig.serialrx_provider); + bstWrite8(masterConfig.rxConfig.serialrx_provider); - bstWrite16(masterConfig.boardAlignment.rollDegrees); - bstWrite16(masterConfig.boardAlignment.pitchDegrees); - bstWrite16(masterConfig.boardAlignment.yawDegrees); + bstWrite16(masterConfig.boardAlignment.rollDegrees); + bstWrite16(masterConfig.boardAlignment.pitchDegrees); + bstWrite16(masterConfig.boardAlignment.yawDegrees); - bstWrite16(masterConfig.batteryConfig.currentMeterScale); - bstWrite16(masterConfig.batteryConfig.currentMeterOffset); - break; + bstWrite16(masterConfig.batteryConfig.currentMeterScale); + bstWrite16(masterConfig.batteryConfig.currentMeterOffset); + break; - case BST_CF_SERIAL_CONFIG: - for (i = 0; i < SERIAL_PORT_COUNT; i++) { - if (!serialIsPortAvailable(masterConfig.serialConfig.portConfigs[i].identifier)) { - continue; - }; - bstWrite8(masterConfig.serialConfig.portConfigs[i].identifier); - bstWrite16(masterConfig.serialConfig.portConfigs[i].functionMask); - bstWrite8(masterConfig.serialConfig.portConfigs[i].msp_baudrateIndex); - bstWrite8(masterConfig.serialConfig.portConfigs[i].gps_baudrateIndex); - bstWrite8(masterConfig.serialConfig.portConfigs[i].telemetry_baudrateIndex); - bstWrite8(masterConfig.serialConfig.portConfigs[i].blackbox_baudrateIndex); - } - break; + case BST_CF_SERIAL_CONFIG: + for (i = 0; i < SERIAL_PORT_COUNT; i++) { + if (!serialIsPortAvailable(masterConfig.serialConfig.portConfigs[i].identifier)) { + continue; + }; + bstWrite8(masterConfig.serialConfig.portConfigs[i].identifier); + bstWrite16(masterConfig.serialConfig.portConfigs[i].functionMask); + bstWrite8(masterConfig.serialConfig.portConfigs[i].msp_baudrateIndex); + bstWrite8(masterConfig.serialConfig.portConfigs[i].gps_baudrateIndex); + bstWrite8(masterConfig.serialConfig.portConfigs[i].telemetry_baudrateIndex); + bstWrite8(masterConfig.serialConfig.portConfigs[i].blackbox_baudrateIndex); + } + break; #ifdef LED_STRIP - case BST_LED_COLORS: - for (i = 0; i < CONFIGURABLE_COLOR_COUNT; i++) { - hsvColor_t *color = &masterConfig.colors[i]; - bstWrite16(color->h); - bstWrite8(color->s); - bstWrite8(color->v); - } - break; + case BST_LED_COLORS: + for (i = 0; i < CONFIGURABLE_COLOR_COUNT; i++) { + hsvColor_t *color = &masterConfig.colors[i]; + bstWrite16(color->h); + bstWrite8(color->s); + bstWrite8(color->v); + } + break; - case BST_LED_STRIP_CONFIG: - for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) { - ledConfig_t *ledConfig = &masterConfig.ledConfigs[i]; - bstWrite16((ledConfig->flags & LED_DIRECTION_MASK) >> LED_DIRECTION_BIT_OFFSET); - bstWrite16((ledConfig->flags & LED_FUNCTION_MASK) >> LED_FUNCTION_BIT_OFFSET); - bstWrite8(GET_LED_X(ledConfig)); - bstWrite8(GET_LED_Y(ledConfig)); - bstWrite8(ledConfig->color); - } - break; + case BST_LED_STRIP_CONFIG: + for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) { + ledConfig_t *ledConfig = &masterConfig.ledConfigs[i]; + bstWrite16((ledConfig->flags & LED_DIRECTION_MASK) >> LED_DIRECTION_BIT_OFFSET); + bstWrite16((ledConfig->flags & LED_FUNCTION_MASK) >> LED_FUNCTION_BIT_OFFSET); + bstWrite8(GET_LED_X(ledConfig)); + bstWrite8(GET_LED_Y(ledConfig)); + bstWrite8(ledConfig->color); + } + break; #endif - case BST_DATAFLASH_SUMMARY: - bstWriteDataflashSummaryReply(); - break; + case BST_DATAFLASH_SUMMARY: + bstWriteDataflashSummaryReply(); + break; #ifdef USE_FLASHFS - case BST_DATAFLASH_READ: - { - uint32_t readAddress = read32(); + case BST_DATAFLASH_READ: + { + uint32_t readAddress = bstRead32(); - bstWriteDataflashReadReply(readAddress, 128); - } - break; + bstWriteDataflashReadReply(readAddress, 128); + } + break; #endif - case BST_BF_BUILD_INFO: - for (i = 0; i < 11; i++) - bstWrite8(buildDate[i]); // MMM DD YYYY as ascii, MMM = Jan/Feb... etc - bstWrite32(0); // future exp - bstWrite32(0); // future exp - break; - case BST_DEADBAND: - bstWrite8(masterConfig.rcControlsConfig.alt_hold_deadband); - bstWrite8(masterConfig.rcControlsConfig.alt_hold_fast_change); - bstWrite8(masterConfig.rcControlsConfig.deadband); - bstWrite8(masterConfig.rcControlsConfig.yaw_deadband); - break; - case BST_FC_FILTERS: - bstWrite16(constrain(masterConfig.gyro_lpf, 0, 1)); // Extra safety to prevent OSD setting corrupt values - break; - default: - // we do not know how to handle the (valid) message, indicate error BST - return false; - } - //bstSlaveWrite(writeData); - return true; + case BST_BF_BUILD_INFO: + for (i = 0; i < 11; i++) + bstWrite8(buildDate[i]); // MMM DD YYYY as ascii, MMM = Jan/Feb... etc + bstWrite32(0); // future exp + bstWrite32(0); // future exp + break; + case BST_DEADBAND: + bstWrite8(masterConfig.rcControlsConfig.alt_hold_deadband); + bstWrite8(masterConfig.rcControlsConfig.alt_hold_fast_change); + bstWrite8(masterConfig.rcControlsConfig.deadband); + bstWrite8(masterConfig.rcControlsConfig.yaw_deadband); + break; + case BST_FC_FILTERS: + bstWrite16(constrain(masterConfig.gyro_lpf, 0, 1)); // Extra safety to prevent OSD setting corrupt values + break; + default: + // we do not know how to handle the (valid) message, indicate error BST + return false; + } + //bstSlaveWrite(writeData); + return true; } static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand) { - uint32_t i; - uint16_t tmp; - uint8_t rate; + uint32_t i; + uint16_t tmp; + uint8_t rate; #ifdef GPS - uint8_t wp_no; - int32_t lat = 0, lon = 0, alt = 0; + uint8_t wp_no; + int32_t lat = 0, lon = 0, alt = 0; #endif - bool ret = BST_PASSED; - switch(bstWriteCommand) { - case BST_SELECT_SETTING: - if (!ARMING_FLAG(ARMED)) { - masterConfig.current_profile_index = bstRead8(); - if (masterConfig.current_profile_index > 2) { - masterConfig.current_profile_index = 0; - } - writeEEPROM(); - readEEPROM(); - } - break; - case BST_SET_HEAD: - magHold = bstRead16(); - break; - case BST_SET_RAW_RC: - { - uint8_t channelCount = bstReadDataSize() / sizeof(uint16_t); - if (channelCount > MAX_SUPPORTED_RC_CHANNEL_COUNT) { - ret = BST_FAILED; - } else { - uint16_t frame[MAX_SUPPORTED_RC_CHANNEL_COUNT]; + bool ret = BST_PASSED; + switch(bstWriteCommand) { + case BST_SELECT_SETTING: + if (!ARMING_FLAG(ARMED)) { + masterConfig.current_profile_index = bstRead8(); + if (masterConfig.current_profile_index > 2) { + masterConfig.current_profile_index = 0; + } + writeEEPROM(); + readEEPROM(); + } + break; + case BST_SET_HEAD: + magHold = bstRead16(); + break; + case BST_SET_RAW_RC: + { + uint8_t channelCount = bstReadDataSize() / sizeof(uint16_t); + if (channelCount > MAX_SUPPORTED_RC_CHANNEL_COUNT) { + ret = BST_FAILED; + } else { + uint16_t frame[MAX_SUPPORTED_RC_CHANNEL_COUNT]; - for (i = 0; i < channelCount; i++) { - frame[i] = bstRead16(); - } + for (i = 0; i < channelCount; i++) { + frame[i] = bstRead16(); + } - rxMspFrameReceive(frame, channelCount); - } - } - case BST_SET_ACC_TRIM: - masterConfig.accelerometerTrims.values.pitch = bstRead16(); - masterConfig.accelerometerTrims.values.roll = bstRead16(); - break; - case BST_SET_ARMING_CONFIG: - masterConfig.auto_disarm_delay = bstRead8(); - masterConfig.disarm_kill_switch = bstRead8(); - break; - case BST_SET_LOOP_TIME: - //masterConfig.looptime = bstRead16(); - cycleTime = bstRead16(); - break; - case BST_SET_PID_CONTROLLER: - currentProfile->pidProfile.pidController = bstRead8(); - pidSetController(currentProfile->pidProfile.pidController); - break; - case BST_SET_PID: - for (i = 0; i < PID_ITEM_COUNT; i++) { - currentProfile->pidProfile.P8[i] = bstRead8(); - currentProfile->pidProfile.I8[i] = bstRead8(); - currentProfile->pidProfile.D8[i] = bstRead8(); - } - break; - case BST_SET_MODE_RANGE: - i = bstRead8(); - if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) { - modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i]; - i = bstRead8(); - const box_t *box = findBoxByPermenantId(i); - if (box) { - mac->modeId = box->boxId; - mac->auxChannelIndex = bstRead8(); - mac->range.startStep = bstRead8(); - mac->range.endStep = bstRead8(); + rxMspFrameReceive(frame, channelCount); + } + } + case BST_SET_ACC_TRIM: + masterConfig.accelerometerTrims.values.pitch = bstRead16(); + masterConfig.accelerometerTrims.values.roll = bstRead16(); + break; + case BST_SET_ARMING_CONFIG: + masterConfig.auto_disarm_delay = bstRead8(); + masterConfig.disarm_kill_switch = bstRead8(); + break; + case BST_SET_LOOP_TIME: + //masterConfig.looptime = bstRead16(); + cycleTime = bstRead16(); + break; + case BST_SET_PID_CONTROLLER: + currentProfile->pidProfile.pidController = bstRead8(); + pidSetController(currentProfile->pidProfile.pidController); + break; + case BST_SET_PID: + for (i = 0; i < PID_ITEM_COUNT; i++) { + currentProfile->pidProfile.P8[i] = bstRead8(); + currentProfile->pidProfile.I8[i] = bstRead8(); + currentProfile->pidProfile.D8[i] = bstRead8(); + } + break; + case BST_SET_MODE_RANGE: + i = bstRead8(); + if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) { + modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i]; + i = bstRead8(); + const box_t *box = findBoxByPermenantId(i); + if (box) { + mac->modeId = box->boxId; + mac->auxChannelIndex = bstRead8(); + mac->range.startStep = bstRead8(); + mac->range.endStep = bstRead8(); - useRcControlsConfig(masterConfig.modeActivationConditions, &masterConfig.escAndServoConfig, ¤tProfile->pidProfile); - } else { - ret = BST_FAILED; - } - } else { - ret = BST_FAILED; - } - break; - case BST_SET_ADJUSTMENT_RANGE: - i = bstRead8(); - if (i < MAX_ADJUSTMENT_RANGE_COUNT) { - adjustmentRange_t *adjRange = &masterConfig.adjustmentRanges[i]; - i = bstRead8(); - if (i < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) { - adjRange->adjustmentIndex = i; - adjRange->auxChannelIndex = bstRead8(); - adjRange->range.startStep = bstRead8(); - adjRange->range.endStep = bstRead8(); - adjRange->adjustmentFunction = bstRead8(); - adjRange->auxSwitchChannelIndex = bstRead8(); - } else { - ret = BST_FAILED; - } - } else { - ret = BST_FAILED; - } - break; - case BST_SET_RC_TUNING: - if (bstReadDataSize() >= 10) { - currentControlRateProfile->rcRate8 = bstRead8(); - currentControlRateProfile->rcExpo8 = bstRead8(); - for (i = 0; i < 3; i++) { - rate = bstRead8(); - currentControlRateProfile->rates[i] = MIN(rate, i == FD_YAW ? CONTROL_RATE_CONFIG_YAW_RATE_MAX : CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX); - } - rate = bstRead8(); - currentControlRateProfile->dynThrPID = MIN(rate, CONTROL_RATE_CONFIG_TPA_MAX); - currentControlRateProfile->thrMid8 = bstRead8(); - currentControlRateProfile->thrExpo8 = bstRead8(); - currentControlRateProfile->tpa_breakpoint = bstRead16(); - if (bstReadDataSize() >= 11) { - currentControlRateProfile->rcYawExpo8 = bstRead8(); - } - } else { - ret = BST_FAILED; - } - break; - case BST_SET_MISC: - tmp = bstRead16(); - if (tmp < 1600 && tmp > 1400) - masterConfig.rxConfig.midrc = tmp; + useRcControlsConfig(masterConfig.modeActivationConditions, &masterConfig.escAndServoConfig, ¤tProfile->pidProfile); + } else { + ret = BST_FAILED; + } + } else { + ret = BST_FAILED; + } + break; + case BST_SET_ADJUSTMENT_RANGE: + i = bstRead8(); + if (i < MAX_ADJUSTMENT_RANGE_COUNT) { + adjustmentRange_t *adjRange = &masterConfig.adjustmentRanges[i]; + i = bstRead8(); + if (i < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) { + adjRange->adjustmentIndex = i; + adjRange->auxChannelIndex = bstRead8(); + adjRange->range.startStep = bstRead8(); + adjRange->range.endStep = bstRead8(); + adjRange->adjustmentFunction = bstRead8(); + adjRange->auxSwitchChannelIndex = bstRead8(); + } else { + ret = BST_FAILED; + } + } else { + ret = BST_FAILED; + } + break; + case BST_SET_RC_TUNING: + if (bstReadDataSize() >= 10) { + currentControlRateProfile->rcRate8 = bstRead8(); + currentControlRateProfile->rcExpo8 = bstRead8(); + for (i = 0; i < 3; i++) { + rate = bstRead8(); + currentControlRateProfile->rates[i] = MIN(rate, i == FD_YAW ? CONTROL_RATE_CONFIG_YAW_RATE_MAX : CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX); + } + rate = bstRead8(); + currentControlRateProfile->dynThrPID = MIN(rate, CONTROL_RATE_CONFIG_TPA_MAX); + currentControlRateProfile->thrMid8 = bstRead8(); + currentControlRateProfile->thrExpo8 = bstRead8(); + currentControlRateProfile->tpa_breakpoint = bstRead16(); + if (bstReadDataSize() >= 11) { + currentControlRateProfile->rcYawExpo8 = bstRead8(); + } + } else { + ret = BST_FAILED; + } + break; + case BST_SET_MISC: + tmp = bstRead16(); + if (tmp < 1600 && tmp > 1400) + masterConfig.rxConfig.midrc = tmp; - masterConfig.escAndServoConfig.minthrottle = bstRead16(); - masterConfig.escAndServoConfig.maxthrottle = bstRead16(); - masterConfig.escAndServoConfig.mincommand = bstRead16(); + masterConfig.escAndServoConfig.minthrottle = bstRead16(); + masterConfig.escAndServoConfig.maxthrottle = bstRead16(); + masterConfig.escAndServoConfig.mincommand = bstRead16(); - masterConfig.failsafeConfig.failsafe_throttle = bstRead16(); + masterConfig.failsafeConfig.failsafe_throttle = bstRead16(); - #ifdef GPS - masterConfig.gpsConfig.provider = bstRead8(); // gps_type - bstRead8(); // gps_baudrate - masterConfig.gpsConfig.sbasMode = bstRead8(); // gps_ubx_sbas - #else - bstRead8(); // gps_type - bstRead8(); // gps_baudrate - bstRead8(); // gps_ubx_sbas - #endif - masterConfig.batteryConfig.multiwiiCurrentMeterOutput = bstRead8(); - masterConfig.rxConfig.rssi_channel = bstRead8(); - bstRead8(); + #ifdef GPS + masterConfig.gpsConfig.provider = bstRead8(); // gps_type + bstRead8(); // gps_baudrate + masterConfig.gpsConfig.sbasMode = bstRead8(); // gps_ubx_sbas + #else + bstRead8(); // gps_type + bstRead8(); // gps_baudrate + bstRead8(); // gps_ubx_sbas + #endif + masterConfig.batteryConfig.multiwiiCurrentMeterOutput = bstRead8(); + masterConfig.rxConfig.rssi_channel = bstRead8(); + bstRead8(); - masterConfig.mag_declination = bstRead16() * 10; + masterConfig.mag_declination = bstRead16() * 10; - masterConfig.batteryConfig.vbatscale = bstRead8(); // actual vbatscale as intended - masterConfig.batteryConfig.vbatmincellvoltage = bstRead8(); // vbatlevel_warn1 in MWC2.3 GUI - masterConfig.batteryConfig.vbatmaxcellvoltage = bstRead8(); // vbatlevel_warn2 in MWC2.3 GUI - masterConfig.batteryConfig.vbatwarningcellvoltage = bstRead8(); // vbatlevel when buzzer starts to alert - break; - case BST_SET_MOTOR: - for (i = 0; i < 8; i++) // FIXME should this use MAX_MOTORS or MAX_SUPPORTED_MOTORS instead of 8 - motor_disarmed[i] = bstRead16(); - break; - case BST_SET_SERVO_CONFIGURATION: + masterConfig.batteryConfig.vbatscale = bstRead8(); // actual vbatscale as intended + masterConfig.batteryConfig.vbatmincellvoltage = bstRead8(); // vbatlevel_warn1 in MWC2.3 GUI + masterConfig.batteryConfig.vbatmaxcellvoltage = bstRead8(); // vbatlevel_warn2 in MWC2.3 GUI + masterConfig.batteryConfig.vbatwarningcellvoltage = bstRead8(); // vbatlevel when buzzer starts to alert + break; + case BST_SET_MOTOR: + for (i = 0; i < 8; i++) // FIXME should this use MAX_MOTORS or MAX_SUPPORTED_MOTORS instead of 8 + motor_disarmed[i] = bstRead16(); + break; + case BST_SET_SERVO_CONFIGURATION: #ifdef USE_SERVOS - if (bstReadDataSize() != 1 + sizeof(servoParam_t)) { - ret = BST_FAILED; - break; - } - i = bstRead8(); - if (i >= MAX_SUPPORTED_SERVOS) { - ret = BST_FAILED; - } else { - masterConfig.servoConf[i].min = bstRead16(); - masterConfig.servoConf[i].max = bstRead16(); - masterConfig.servoConf[i].middle = bstRead16(); - masterConfig.servoConf[i].rate = bstRead8(); - masterConfig.servoConf[i].angleAtMin = bstRead8(); - masterConfig.servoConf[i].angleAtMax = bstRead8(); - masterConfig.servoConf[i].forwardFromChannel = bstRead8(); - masterConfig.servoConf[i].reversedSources = bstRead32(); - } + if (bstReadDataSize() != 1 + sizeof(servoParam_t)) { + ret = BST_FAILED; + break; + } + i = bstRead8(); + if (i >= MAX_SUPPORTED_SERVOS) { + ret = BST_FAILED; + } else { + masterConfig.servoConf[i].min = bstRead16(); + masterConfig.servoConf[i].max = bstRead16(); + masterConfig.servoConf[i].middle = bstRead16(); + masterConfig.servoConf[i].rate = bstRead8(); + masterConfig.servoConf[i].angleAtMin = bstRead8(); + masterConfig.servoConf[i].angleAtMax = bstRead8(); + masterConfig.servoConf[i].forwardFromChannel = bstRead8(); + masterConfig.servoConf[i].reversedSources = bstRead32(); + } #endif - break; - case BST_SET_SERVO_MIX_RULE: + break; + case BST_SET_SERVO_MIX_RULE: #ifdef USE_SERVOS - i = bstRead8(); - if (i >= MAX_SERVO_RULES) { - ret = BST_FAILED; - } else { - masterConfig.customServoMixer[i].targetChannel = bstRead8(); - masterConfig.customServoMixer[i].inputSource = bstRead8(); - masterConfig.customServoMixer[i].rate = bstRead8(); - masterConfig.customServoMixer[i].speed = bstRead8(); - masterConfig.customServoMixer[i].min = bstRead8(); - masterConfig.customServoMixer[i].max = bstRead8(); - masterConfig.customServoMixer[i].box = bstRead8(); - loadCustomServoMixer(); - } + i = bstRead8(); + if (i >= MAX_SERVO_RULES) { + ret = BST_FAILED; + } else { + masterConfig.customServoMixer[i].targetChannel = bstRead8(); + masterConfig.customServoMixer[i].inputSource = bstRead8(); + masterConfig.customServoMixer[i].rate = bstRead8(); + masterConfig.customServoMixer[i].speed = bstRead8(); + masterConfig.customServoMixer[i].min = bstRead8(); + masterConfig.customServoMixer[i].max = bstRead8(); + masterConfig.customServoMixer[i].box = bstRead8(); + loadCustomServoMixer(); + } #endif - break; - case BST_RESET_CONF: - if (!ARMING_FLAG(ARMED)) { - resetEEPROM(); - readEEPROM(); - } - break; - case BST_ACC_CALIBRATION: - if (!ARMING_FLAG(ARMED)) - accSetCalibrationCycles(CALIBRATING_ACC_CYCLES); - break; - case BST_MAG_CALIBRATION: - if (!ARMING_FLAG(ARMED)) - ENABLE_STATE(CALIBRATE_MAG); - break; - case BST_EEPROM_WRITE: - if (ARMING_FLAG(ARMED)) { - ret = BST_FAILED; - bstWrite8(ret); - //bstSlaveWrite(writeData); - return ret; - } - writeEEPROM(); - readEEPROM(); - break; + break; + case BST_RESET_CONF: + if (!ARMING_FLAG(ARMED)) { + resetEEPROM(); + readEEPROM(); + } + break; + case BST_ACC_CALIBRATION: + if (!ARMING_FLAG(ARMED)) + accSetCalibrationCycles(CALIBRATING_ACC_CYCLES); + break; + case BST_MAG_CALIBRATION: + if (!ARMING_FLAG(ARMED)) + ENABLE_STATE(CALIBRATE_MAG); + break; + case BST_EEPROM_WRITE: + if (ARMING_FLAG(ARMED)) { + ret = BST_FAILED; + bstWrite8(ret); + //bstSlaveWrite(writeData); + return ret; + } + writeEEPROM(); + readEEPROM(); + break; #ifdef USE_FLASHFS - case BST_DATAFLASH_ERASE: - flashfsEraseCompletely(); - break; + case BST_DATAFLASH_ERASE: + flashfsEraseCompletely(); + break; #endif #ifdef GPS - case BST_SET_RAW_GPS: - if (bstRead8()) { - ENABLE_STATE(GPS_FIX); - } else { - DISABLE_STATE(GPS_FIX); - } - GPS_numSat = bstRead8(); - GPS_coord[LAT] = bstRead32(); - GPS_coord[LON] = bstRead32(); - GPS_altitude = bstRead16(); - GPS_speed = bstRead16(); - GPS_update |= 2; // New data signalisation to GPS functions // FIXME Magic Numbers - break; - case BST_SET_WP: - wp_no = bstRead8(); //get the wp number - lat = bstRead32(); - lon = bstRead32(); - alt = bstRead32(); // to set altitude (cm) - bstRead16(); // future: to set heading (deg) - bstRead16(); // future: to set time to stay (ms) - bstRead8(); // future: to set nav flag - if (wp_no == 0) { - GPS_home[LAT] = lat; - GPS_home[LON] = lon; - DISABLE_FLIGHT_MODE(GPS_HOME_MODE); // with this flag, GPS_set_next_wp will be called in the next loop -- OK with SERIAL GPS / OK with I2C GPS - ENABLE_STATE(GPS_FIX_HOME); - if (alt != 0) - AltHold = alt; // temporary implementation to test feature with apps - } else if (wp_no == 16) { // OK with SERIAL GPS -- NOK for I2C GPS / needs more code dev in order to inject GPS coord inside I2C GPS - GPS_hold[LAT] = lat; - GPS_hold[LON] = lon; - if (alt != 0) - AltHold = alt; // temporary implementation to test feature with apps - nav_mode = NAV_MODE_WP; - GPS_set_next_wp(&GPS_hold[LAT], &GPS_hold[LON]); - } - break; + case BST_SET_RAW_GPS: + if (bstRead8()) { + ENABLE_STATE(GPS_FIX); + } else { + DISABLE_STATE(GPS_FIX); + } + GPS_numSat = bstRead8(); + GPS_coord[LAT] = bstRead32(); + GPS_coord[LON] = bstRead32(); + GPS_altitude = bstRead16(); + GPS_speed = bstRead16(); + GPS_update |= 2; // New data signalisation to GPS functions // FIXME Magic Numbers + break; + case BST_SET_WP: + wp_no = bstRead8(); //get the wp number + lat = bstRead32(); + lon = bstRead32(); + alt = bstRead32(); // to set altitude (cm) + bstRead16(); // future: to set heading (deg) + bstRead16(); // future: to set time to stay (ms) + bstRead8(); // future: to set nav flag + if (wp_no == 0) { + GPS_home[LAT] = lat; + GPS_home[LON] = lon; + DISABLE_FLIGHT_MODE(GPS_HOME_MODE); // with this flag, GPS_set_next_wp will be called in the next loop -- OK with SERIAL GPS / OK with I2C GPS + ENABLE_STATE(GPS_FIX_HOME); + if (alt != 0) + AltHold = alt; // temporary implementation to test feature with apps + } else if (wp_no == 16) { // OK with SERIAL GPS -- NOK for I2C GPS / needs more code dev in order to inject GPS coord inside I2C GPS + GPS_hold[LAT] = lat; + GPS_hold[LON] = lon; + if (alt != 0) + AltHold = alt; // temporary implementation to test feature with apps + nav_mode = NAV_MODE_WP; + GPS_set_next_wp(&GPS_hold[LAT], &GPS_hold[LON]); + } + break; #endif - case BST_SET_FEATURE: - featureClearAll(); - featureSet(bstRead32()); // features bitmap - break; - case BST_SET_BOARD_ALIGNMENT: - masterConfig.boardAlignment.rollDegrees = bstRead16(); - masterConfig.boardAlignment.pitchDegrees = bstRead16(); - masterConfig.boardAlignment.yawDegrees = bstRead16(); - break; - case BST_SET_VOLTAGE_METER_CONFIG: - masterConfig.batteryConfig.vbatscale = bstRead8(); // actual vbatscale as intended - masterConfig.batteryConfig.vbatmincellvoltage = bstRead8(); // vbatlevel_warn1 in MWC2.3 GUI - masterConfig.batteryConfig.vbatmaxcellvoltage = bstRead8(); // vbatlevel_warn2 in MWC2.3 GUI - masterConfig.batteryConfig.vbatwarningcellvoltage = bstRead8(); // vbatlevel when buzzer starts to alert - break; - case BST_SET_CURRENT_METER_CONFIG: - masterConfig.batteryConfig.currentMeterScale = bstRead16(); - masterConfig.batteryConfig.currentMeterOffset = bstRead16(); - masterConfig.batteryConfig.currentMeterType = bstRead8(); - masterConfig.batteryConfig.batteryCapacity = bstRead16(); - break; + case BST_SET_FEATURE: + featureClearAll(); + featureSet(bstRead32()); // features bitmap + break; + case BST_SET_BOARD_ALIGNMENT: + masterConfig.boardAlignment.rollDegrees = bstRead16(); + masterConfig.boardAlignment.pitchDegrees = bstRead16(); + masterConfig.boardAlignment.yawDegrees = bstRead16(); + break; + case BST_SET_VOLTAGE_METER_CONFIG: + masterConfig.batteryConfig.vbatscale = bstRead8(); // actual vbatscale as intended + masterConfig.batteryConfig.vbatmincellvoltage = bstRead8(); // vbatlevel_warn1 in MWC2.3 GUI + masterConfig.batteryConfig.vbatmaxcellvoltage = bstRead8(); // vbatlevel_warn2 in MWC2.3 GUI + masterConfig.batteryConfig.vbatwarningcellvoltage = bstRead8(); // vbatlevel when buzzer starts to alert + break; + case BST_SET_CURRENT_METER_CONFIG: + masterConfig.batteryConfig.currentMeterScale = bstRead16(); + masterConfig.batteryConfig.currentMeterOffset = bstRead16(); + masterConfig.batteryConfig.currentMeterType = bstRead8(); + masterConfig.batteryConfig.batteryCapacity = bstRead16(); + break; #ifndef USE_QUAD_MIXER_ONLY - case BST_SET_MIXER: - masterConfig.mixerMode = bstRead8(); - break; + case BST_SET_MIXER: + masterConfig.mixerMode = bstRead8(); + break; #endif - case BST_SET_RX_CONFIG: - masterConfig.rxConfig.serialrx_provider = bstRead8(); - masterConfig.rxConfig.maxcheck = bstRead16(); - masterConfig.rxConfig.midrc = bstRead16(); - masterConfig.rxConfig.mincheck = bstRead16(); - masterConfig.rxConfig.spektrum_sat_bind = bstRead8(); - if (bstReadDataSize() > 8) { - masterConfig.rxConfig.rx_min_usec = bstRead16(); - masterConfig.rxConfig.rx_max_usec = bstRead16(); - } - break; - case BST_SET_FAILSAFE_CONFIG: - masterConfig.failsafeConfig.failsafe_delay = bstRead8(); - masterConfig.failsafeConfig.failsafe_off_delay = bstRead8(); - masterConfig.failsafeConfig.failsafe_throttle = bstRead16(); - break; - case BST_SET_RXFAIL_CONFIG: - { - uint8_t channelCount = bstReadDataSize() / 3; - if (channelCount > MAX_AUX_CHANNEL_COUNT) { - ret = BST_FAILED; - } else { - for (i = NON_AUX_CHANNEL_COUNT; i < channelCount; i++) { - masterConfig.rxConfig.failsafe_channel_configurations[i].mode = bstRead8(); - masterConfig.rxConfig.failsafe_channel_configurations[i].step = CHANNEL_VALUE_TO_RXFAIL_STEP(bstRead16()); - } - } - } - break; - case BST_SET_RSSI_CONFIG: - masterConfig.rxConfig.rssi_channel = bstRead8(); - break; - case BST_SET_RX_MAP: - for (i = 0; i < MAX_MAPPABLE_RX_INPUTS; i++) { - masterConfig.rxConfig.rcmap[i] = bstRead8(); - } - break; - case BST_SET_BF_CONFIG: + case BST_SET_RX_CONFIG: + masterConfig.rxConfig.serialrx_provider = bstRead8(); + masterConfig.rxConfig.maxcheck = bstRead16(); + masterConfig.rxConfig.midrc = bstRead16(); + masterConfig.rxConfig.mincheck = bstRead16(); + masterConfig.rxConfig.spektrum_sat_bind = bstRead8(); + if (bstReadDataSize() > 8) { + masterConfig.rxConfig.rx_min_usec = bstRead16(); + masterConfig.rxConfig.rx_max_usec = bstRead16(); + } + break; + case BST_SET_FAILSAFE_CONFIG: + masterConfig.failsafeConfig.failsafe_delay = bstRead8(); + masterConfig.failsafeConfig.failsafe_off_delay = bstRead8(); + masterConfig.failsafeConfig.failsafe_throttle = bstRead16(); + break; + case BST_SET_RXFAIL_CONFIG: + { + uint8_t channelCount = bstReadDataSize() / 3; + if (channelCount > MAX_AUX_CHANNEL_COUNT) { + ret = BST_FAILED; + } else { + for (i = NON_AUX_CHANNEL_COUNT; i < channelCount; i++) { + masterConfig.rxConfig.failsafe_channel_configurations[i].mode = bstRead8(); + masterConfig.rxConfig.failsafe_channel_configurations[i].step = CHANNEL_VALUE_TO_RXFAIL_STEP(bstRead16()); + } + } + } + break; + case BST_SET_RSSI_CONFIG: + masterConfig.rxConfig.rssi_channel = bstRead8(); + break; + case BST_SET_RX_MAP: + for (i = 0; i < MAX_MAPPABLE_RX_INPUTS; i++) { + masterConfig.rxConfig.rcmap[i] = bstRead8(); + } + break; + case BST_SET_BF_CONFIG: #ifdef USE_QUAD_MIXER_ONLY - bstRead8(); // mixerMode ignored + bstRead8(); // mixerMode ignored #else - masterConfig.mixerMode = bstRead8(); // mixerMode + masterConfig.mixerMode = bstRead8(); // mixerMode #endif - featureClearAll(); - featureSet(bstRead32()); // features bitmap + featureClearAll(); + featureSet(bstRead32()); // features bitmap - masterConfig.rxConfig.serialrx_provider = bstRead8(); // serialrx_type + masterConfig.rxConfig.serialrx_provider = bstRead8(); // serialrx_type - masterConfig.boardAlignment.rollDegrees = bstRead16(); // board_align_roll - masterConfig.boardAlignment.pitchDegrees = bstRead16(); // board_align_pitch - masterConfig.boardAlignment.yawDegrees = bstRead16(); // board_align_yaw + masterConfig.boardAlignment.rollDegrees = bstRead16(); // board_align_roll + masterConfig.boardAlignment.pitchDegrees = bstRead16(); // board_align_pitch + masterConfig.boardAlignment.yawDegrees = bstRead16(); // board_align_yaw - masterConfig.batteryConfig.currentMeterScale = bstRead16(); - masterConfig.batteryConfig.currentMeterOffset = bstRead16(); - break; - case BST_SET_CF_SERIAL_CONFIG: - { - uint8_t portConfigSize = sizeof(uint8_t) + sizeof(uint16_t) + (sizeof(uint8_t) * 4); - if (bstReadDataSize() % portConfigSize != 0) { - ret = BST_FAILED; - break; - } + masterConfig.batteryConfig.currentMeterScale = bstRead16(); + masterConfig.batteryConfig.currentMeterOffset = bstRead16(); + break; + case BST_SET_CF_SERIAL_CONFIG: + { + uint8_t portConfigSize = sizeof(uint8_t) + sizeof(uint16_t) + (sizeof(uint8_t) * 4); + if (bstReadDataSize() % portConfigSize != 0) { + ret = BST_FAILED; + break; + } - uint8_t remainingPortsInPacket = bstReadDataSize() / portConfigSize; + uint8_t remainingPortsInPacket = bstReadDataSize() / portConfigSize; - while (remainingPortsInPacket--) { - uint8_t identifier = bstRead8(); + while (remainingPortsInPacket--) { + uint8_t identifier = bstRead8(); - serialPortConfig_t *portConfig = serialFindPortConfiguration(identifier); - if (!portConfig) { - ret = BST_FAILED; - break; - } + serialPortConfig_t *portConfig = serialFindPortConfiguration(identifier); + if (!portConfig) { + ret = BST_FAILED; + break; + } - portConfig->identifier = identifier; - portConfig->functionMask = bstRead16(); - portConfig->msp_baudrateIndex = bstRead8(); - portConfig->gps_baudrateIndex = bstRead8(); - portConfig->telemetry_baudrateIndex = bstRead8(); - portConfig->blackbox_baudrateIndex = bstRead8(); - } - } - break; + portConfig->identifier = identifier; + portConfig->functionMask = bstRead16(); + portConfig->msp_baudrateIndex = bstRead8(); + portConfig->gps_baudrateIndex = bstRead8(); + portConfig->telemetry_baudrateIndex = bstRead8(); + portConfig->blackbox_baudrateIndex = bstRead8(); + } + } + break; #ifdef LED_STRIP - case BST_SET_LED_COLORS: - //for (i = 0; i < CONFIGURABLE_COLOR_COUNT; i++) { - { - i = bstRead8(); - hsvColor_t *color = &masterConfig.colors[i]; - color->h = bstRead16(); - color->s = bstRead8(); - color->v = bstRead8(); - } - break; - case BST_SET_LED_STRIP_CONFIG: - { - i = bstRead8(); - if (i >= MAX_LED_STRIP_LENGTH || bstReadDataSize() != (1 + 7)) { - ret = BST_FAILED; - break; - } - ledConfig_t *ledConfig = &masterConfig.ledConfigs[i]; - uint16_t mask; - // currently we're storing directions and functions in a uint16 (flags) - // the msp uses 2 x uint16_t to cater for future expansion - mask = bstRead16(); - ledConfig->flags = (mask << LED_DIRECTION_BIT_OFFSET) & LED_DIRECTION_MASK; + case BST_SET_LED_COLORS: + //for (i = 0; i < CONFIGURABLE_COLOR_COUNT; i++) { + { + i = bstRead8(); + hsvColor_t *color = &masterConfig.colors[i]; + color->h = bstRead16(); + color->s = bstRead8(); + color->v = bstRead8(); + } + break; + case BST_SET_LED_STRIP_CONFIG: + { + i = bstRead8(); + if (i >= MAX_LED_STRIP_LENGTH || bstReadDataSize() != (1 + 7)) { + ret = BST_FAILED; + break; + } + ledConfig_t *ledConfig = &masterConfig.ledConfigs[i]; + uint16_t mask; + // currently we're storing directions and functions in a uint16 (flags) + // the msp uses 2 x uint16_t to cater for future expansion + mask = bstRead16(); + ledConfig->flags = (mask << LED_DIRECTION_BIT_OFFSET) & LED_DIRECTION_MASK; - mask = bstRead16(); - ledConfig->flags |= (mask << LED_FUNCTION_BIT_OFFSET) & LED_FUNCTION_MASK; + mask = bstRead16(); + ledConfig->flags |= (mask << LED_FUNCTION_BIT_OFFSET) & LED_FUNCTION_MASK; - mask = bstRead8(); - ledConfig->xy = CALCULATE_LED_X(mask); + mask = bstRead8(); + ledConfig->xy = CALCULATE_LED_X(mask); - mask = bstRead8(); - ledConfig->xy |= CALCULATE_LED_Y(mask); + mask = bstRead8(); + ledConfig->xy |= CALCULATE_LED_Y(mask); - ledConfig->color = bstRead8(); + ledConfig->color = bstRead8(); - reevalulateLedConfig(); - } - break; + reevalulateLedConfig(); + } + break; #endif - case BST_REBOOT: - isRebootScheduled = true; - break; - case BST_DISARM: - if (ARMING_FLAG(ARMED)) - mwDisarm(); - ENABLE_ARMING_FLAG(PREVENT_ARMING); - break; - case BST_ENABLE_ARM: - DISABLE_ARMING_FLAG(PREVENT_ARMING); - break; - case BST_SET_DEADBAND: - masterConfig.rcControlsConfig.alt_hold_deadband = bstRead8(); - masterConfig.rcControlsConfig.alt_hold_fast_change = bstRead8(); - masterConfig.rcControlsConfig.deadband = bstRead8(); - masterConfig.rcControlsConfig.yaw_deadband = bstRead8(); - break; - case BST_SET_FC_FILTERS: - masterConfig.gyro_lpf = bstRead16(); - break; + case BST_REBOOT: + isRebootScheduled = true; + break; + case BST_DISARM: + if (ARMING_FLAG(ARMED)) + mwDisarm(); + ENABLE_ARMING_FLAG(PREVENT_ARMING); + break; + case BST_ENABLE_ARM: + DISABLE_ARMING_FLAG(PREVENT_ARMING); + break; + case BST_SET_DEADBAND: + masterConfig.rcControlsConfig.alt_hold_deadband = bstRead8(); + masterConfig.rcControlsConfig.alt_hold_fast_change = bstRead8(); + masterConfig.rcControlsConfig.deadband = bstRead8(); + masterConfig.rcControlsConfig.yaw_deadband = bstRead8(); + break; + case BST_SET_FC_FILTERS: + masterConfig.gyro_lpf = bstRead16(); + break; - default: - // we do not know how to handle the (valid) message, indicate error BST - ret = BST_FAILED; - } - bstWrite8(ret); - //bstSlaveWrite(writeData); - if(ret == BST_FAILED) - return false; - return true; + default: + // we do not know how to handle the (valid) message, indicate error BST + ret = BST_FAILED; + } + bstWrite8(ret); + //bstSlaveWrite(writeData); + if(ret == BST_FAILED) + return false; + return true; } static bool bstSlaveUSBCommandFeedback(/*uint8_t bstFeedback*/) { - bstWrite8(BST_USB_DEVICE_INFO_FRAME); //Sub CPU Device Info FRAME - bstWrite8(sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_SONAR) << 4); - bstWrite8(0x00); - bstWrite8(0x00); - bstWrite8(0x00); - bstWrite8(FC_VERSION_MAJOR); //Firmware ID - bstWrite8(FC_VERSION_MINOR); //Firmware ID - bstWrite8(0x00); - bstWrite8(0x00); - //bstSlaveWrite(writeData); - return true; + bstWrite8(BST_USB_DEVICE_INFO_FRAME); //Sub CPU Device Info FRAME + bstWrite8(sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_SONAR) << 4); + bstWrite8(0x00); + bstWrite8(0x00); + bstWrite8(0x00); + bstWrite8(FC_VERSION_MAJOR); //Firmware ID + bstWrite8(FC_VERSION_MINOR); //Firmware ID + bstWrite8(0x00); + bstWrite8(0x00); + //bstSlaveWrite(writeData); + return true; } /*************************************************************************************************/ -#define BST_RESET_TIME 1.2*1000*1000 //micro-seconds +#define BST_RESET_TIME 1.2*1000*1000 //micro-seconds uint32_t resetBstTimer = 0; bool needResetCheck = true; +extern bool cleanflight_data_ready; void bstProcessInCommand(void) { - readBufferPointer = 2; - if(bstCurrentAddress() == CLEANFLIGHT_FC) { - if(bstReadCRC() == CRC8 && bstRead8()==BST_USB_COMMANDS) { - uint8_t i; - writeBufferPointer = 1; - for(i = 0; i < DATA_BUFFER_SIZE; i++) { - writeData[i] = 0; - } - switch (bstRead8()) { - case BST_USB_DEVICE_INFO_REQUEST: - bstRead8(); - if(bstSlaveUSBCommandFeedback(/*bstRead8()*/)) - coreProReady = true; - break; - case BST_READ_COMMANDS: - bstWrite8(BST_READ_COMMANDS); - bstSlaveProcessFeedbackCommand(bstRead8()); - break; - case BST_WRITE_COMMANDS: - bstWrite8(BST_WRITE_COMMANDS); - bstSlaveProcessWriteCommand(bstRead8()); - break; - default: - // we do not know how to handle the (valid) message, indicate error BST - break; - } - } - } else if(bstCurrentAddress() == 0x00) { - if(bstReadCRC() == CRC8 && bstRead8()==BST_GENERAL_HEARTBEAT) { - resetBstTimer = micros(); - needResetCheck = true; - } - } + readBufferPointer = 2; + if(bstCurrentAddress() == CLEANFLIGHT_FC) { + if(bstReadCRC() == CRC8 && bstRead8()==BST_USB_COMMANDS) { + uint8_t i; + writeBufferPointer = 1; + cleanflight_data_ready = false; + for(i = 0; i < DATA_BUFFER_SIZE; i++) { + writeData[i] = 0; + } + switch (bstRead8()) { + case BST_USB_DEVICE_INFO_REQUEST: + bstRead8(); + if(bstSlaveUSBCommandFeedback(/*bstRead8()*/)) + coreProReady = true; + break; + case BST_READ_COMMANDS: + bstWrite8(BST_READ_COMMANDS); + bstSlaveProcessFeedbackCommand(bstRead8()); + break; + case BST_WRITE_COMMANDS: + bstWrite8(BST_WRITE_COMMANDS); + bstSlaveProcessWriteCommand(bstRead8()); + break; + default: + // we do not know how to handle the (valid) message, indicate error BST + break; + } + cleanflight_data_ready = true; + } + } else if(bstCurrentAddress() == 0x00) { + if(bstReadCRC() == CRC8 && bstRead8()==BST_GENERAL_HEARTBEAT) { + resetBstTimer = micros(); + needResetCheck = true; + } + } } void resetBstChecker(void) { - if(needResetCheck) { - uint32_t currentTimer = micros(); - if(currentTimer >= (resetBstTimer + BST_RESET_TIME)) - { - bstTimeoutUserCallback(); - needResetCheck = false; - } - } + if(needResetCheck) { + uint32_t currentTimer = micros(); + if(currentTimer >= (resetBstTimer + BST_RESET_TIME)) + { + bstTimeoutUserCallback(); + needResetCheck = false; + } + } } /*************************************************************************************************/ @@ -1519,63 +1522,64 @@ static uint8_t sendCounter = 0; void taskBstMasterProcess(void) { - if(coreProReady) { - uint32_t now = micros(); - if(now >= next02hzUpdateAt_1 && !bstWriteBusy()) { - writeFCModeToBST(); - next02hzUpdateAt_1 = now + UPDATE_AT_02HZ; - } - if(now >= next20hzUpdateAt_1 && !bstWriteBusy()) { - if(sendCounter == 0) - writeRCChannelToBST(); - else if(sendCounter == 1) - writeRollPitchYawToBST(); - sendCounter++; - if(sendCounter > 1) - sendCounter = 0; - next20hzUpdateAt_1 = now + UPDATE_AT_20HZ; - } + if(coreProReady) { + uint32_t now = micros(); + if(now >= next02hzUpdateAt_1 && !bstWriteBusy()) { + writeFCModeToBST(); + next02hzUpdateAt_1 = now + UPDATE_AT_02HZ; + } + if(now >= next20hzUpdateAt_1 && !bstWriteBusy()) { + if(sendCounter == 0) + writeRCChannelToBST(); + else if(sendCounter == 1) + writeRollPitchYawToBST(); + sendCounter++; + if(sendCounter > 1) + sendCounter = 0; + next20hzUpdateAt_1 = now + UPDATE_AT_20HZ; + } - if(sensors(SENSOR_GPS) && !bstWriteBusy()) - writeGpsPositionPrameToBST(); - } - bstMasterWriteLoop(); - if (isRebootScheduled) { - stopMotors(); - handleOneshotFeatureChangeOnRestart(); - systemReset(); - } - resetBstChecker(); + if(sensors(SENSOR_GPS) && !bstWriteBusy()) + writeGpsPositionPrameToBST(); + } + bstMasterWriteLoop(); + if (isRebootScheduled) { + stopMotors(); + systemReset(); + } + resetBstChecker(); } /*************************************************************************************************/ static uint8_t masterWriteBufferPointer; static uint8_t masterWriteData[DATA_BUFFER_SIZE]; -static void bstMasterStartBuffer(uint8_t address) { - masterWriteData[0] = address; - masterWriteBufferPointer = 2; +static void bstMasterStartBuffer(uint8_t address) +{ + masterWriteData[0] = address; + masterWriteBufferPointer = 2; } -static void bstMasterWrite8(uint8_t data) { - masterWriteData[masterWriteBufferPointer++] = data; - masterWriteData[1] = masterWriteBufferPointer; +static void bstMasterWrite8(uint8_t data) +{ + masterWriteData[masterWriteBufferPointer++] = data; + masterWriteData[1] = masterWriteBufferPointer; } static void bstMasterWrite16(uint16_t data) { - bstMasterWrite8((uint8_t)(data >> 8)); - bstMasterWrite8((uint8_t)(data >> 0)); + bstMasterWrite8((uint8_t)(data >> 8)); + bstMasterWrite8((uint8_t)(data >> 0)); } static void bstMasterWrite32(uint32_t data) { - bstMasterWrite16((uint8_t)(data >> 16)); - bstMasterWrite16((uint8_t)(data >> 0)); + bstMasterWrite16((uint8_t)(data >> 16)); + bstMasterWrite16((uint8_t)(data >> 0)); } /*************************************************************************************************/ -#define PUBLIC_ADDRESS 0x00 +#define PUBLIC_ADDRESS 0x00 static int32_t lat = 0; static int32_t lon = 0; @@ -1584,108 +1588,108 @@ static uint8_t numOfSat = 0; bool writeGpsPositionPrameToBST(void) { - if((lat != GPS_coord[LAT]) || (lon != GPS_coord[LON]) || (alt != GPS_altitude) || (numOfSat != GPS_numSat)) { - lat = GPS_coord[LAT]; - lon = GPS_coord[LON]; - alt = GPS_altitude; - numOfSat = GPS_numSat; - uint16_t speed = (GPS_speed * 9 / 25); - uint16_t gpsHeading = 0; - uint16_t altitude = 0; - gpsHeading = GPS_ground_course * 10; - altitude = alt * 10 + 1000; + if((lat != GPS_coord[LAT]) || (lon != GPS_coord[LON]) || (alt != GPS_altitude) || (numOfSat != GPS_numSat)) { + lat = GPS_coord[LAT]; + lon = GPS_coord[LON]; + alt = GPS_altitude; + numOfSat = GPS_numSat; + uint16_t speed = (GPS_speed * 9 / 25); + uint16_t gpsHeading = 0; + uint16_t altitude = 0; + gpsHeading = GPS_ground_course * 10; + altitude = alt * 10 + 1000; - bstMasterStartBuffer(PUBLIC_ADDRESS); - bstMasterWrite8(GPS_POSITION_FRAME_ID); - bstMasterWrite32(lat); - bstMasterWrite32(lon); - bstMasterWrite16(speed); - bstMasterWrite16(gpsHeading); - bstMasterWrite16(altitude); - bstMasterWrite8(numOfSat); - bstMasterWrite8(0x00); + bstMasterStartBuffer(PUBLIC_ADDRESS); + bstMasterWrite8(GPS_POSITION_FRAME_ID); + bstMasterWrite32(lat); + bstMasterWrite32(lon); + bstMasterWrite16(speed); + bstMasterWrite16(gpsHeading); + bstMasterWrite16(altitude); + bstMasterWrite8(numOfSat); + bstMasterWrite8(0x00); - return bstMasterWrite(masterWriteData); - } else - return false; + return bstMasterWrite(masterWriteData); + } else + return false; } bool writeRollPitchYawToBST(void) { - int16_t X = -attitude.values.pitch * (M_PIf / 1800.0f) * 10000; - int16_t Y = attitude.values.roll * (M_PIf / 1800.0f) * 10000; - int16_t Z = 0;//radiusHeading * 10000; + int16_t X = -attitude.values.pitch * (M_PIf / 1800.0f) * 10000; + int16_t Y = attitude.values.roll * (M_PIf / 1800.0f) * 10000; + int16_t Z = 0;//radiusHeading * 10000; - bstMasterStartBuffer(PUBLIC_ADDRESS); - bstMasterWrite8(FC_ATTITUDE_FRAME_ID); - bstMasterWrite16(X); - bstMasterWrite16(Y); - bstMasterWrite16(Z); + bstMasterStartBuffer(PUBLIC_ADDRESS); + bstMasterWrite8(FC_ATTITUDE_FRAME_ID); + bstMasterWrite16(X); + bstMasterWrite16(Y); + bstMasterWrite16(Z); - return bstMasterWrite(masterWriteData); + return bstMasterWrite(masterWriteData); } bool writeRCChannelToBST(void) { - uint8_t i = 0; - bstMasterStartBuffer(PUBLIC_ADDRESS); - bstMasterWrite8(RC_CHANNEL_FRAME_ID); - for(i = 0; i < (USABLE_TIMER_CHANNEL_COUNT-1); i++) { - bstMasterWrite16(rcData[i]); - } + uint8_t i = 0; + bstMasterStartBuffer(PUBLIC_ADDRESS); + bstMasterWrite8(RC_CHANNEL_FRAME_ID); + for(i = 0; i < (USABLE_TIMER_CHANNEL_COUNT-1); i++) { + bstMasterWrite16(rcData[i]); + } - return bstMasterWrite(masterWriteData); + return bstMasterWrite(masterWriteData); } bool writeFCModeToBST(void) { #ifdef CLEANFLIGHT_FULL_STATUS_SET - uint32_t tmp = 0; + uint32_t tmp = 0; tmp = IS_ENABLED(FLIGHT_MODE(ANGLE_MODE)) << BOXANGLE | IS_ENABLED(FLIGHT_MODE(HORIZON_MODE)) << BOXHORIZON | IS_ENABLED(FLIGHT_MODE(BARO_MODE)) << BOXBARO | IS_ENABLED(FLIGHT_MODE(MAG_MODE)) << BOXMAG | IS_ENABLED(FLIGHT_MODE(HEADFREE_MODE)) << BOXHEADFREE | IS_ENABLED(IS_RC_MODE_ACTIVE(BOXHEADADJ)) << BOXHEADADJ | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXCAMSTAB)) << BOXCAMSTAB | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXCAMTRIG)) << BOXCAMTRIG | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXCAMSTAB)) << BOXCAMSTAB | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXCAMTRIG)) << BOXCAMTRIG | IS_ENABLED(FLIGHT_MODE(GPS_HOME_MODE)) << BOXGPSHOME | IS_ENABLED(FLIGHT_MODE(GPS_HOLD_MODE)) << BOXGPSHOLD | IS_ENABLED(FLIGHT_MODE(PASSTHRU_MODE)) << BOXPASSTHRU | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXBEEPERON)) << BOXBEEPERON | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXLEDMAX)) << BOXLEDMAX | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXLEDLOW)) << BOXLEDLOW | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXLLIGHTS)) << BOXLLIGHTS | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXCALIB)) << BOXCALIB | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXGOV)) << BOXGOV | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXOSD)) << BOXOSD | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXTELEMETRY)) << BOXTELEMETRY | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXGTUNE)) << BOXGTUNE | - IS_ENABLED(FLIGHT_MODE(SONAR_MODE)) << BOXSONAR | - IS_ENABLED(ARMING_FLAG(ARMED)) << BOXARM | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXBLACKBOX)) << BOXBLACKBOX | - IS_ENABLED(FLIGHT_MODE(FAILSAFE_MODE)) << BOXFAILSAFE; - bstMasterStartBuffer(PUBLIC_ADDRESS); - bstMasterWrite8(CLEANFLIGHT_MODE_FRAME_ID); - bstMasterWrite32(tmp); - bstMasterWrite16(sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_SONAR) << 4); + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXBEEPERON)) << BOXBEEPERON | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXLEDMAX)) << BOXLEDMAX | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXLEDLOW)) << BOXLEDLOW | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXLLIGHTS)) << BOXLLIGHTS | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXCALIB)) << BOXCALIB | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXGOV)) << BOXGOV | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXOSD)) << BOXOSD | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXTELEMETRY)) << BOXTELEMETRY | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXGTUNE)) << BOXGTUNE | + IS_ENABLED(FLIGHT_MODE(SONAR_MODE)) << BOXSONAR | + IS_ENABLED(ARMING_FLAG(ARMED)) << BOXARM | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXBLACKBOX)) << BOXBLACKBOX | + IS_ENABLED(FLIGHT_MODE(FAILSAFE_MODE)) << BOXFAILSAFE; + bstMasterStartBuffer(PUBLIC_ADDRESS); + bstMasterWrite8(CLEANFLIGHT_MODE_FRAME_ID); + bstMasterWrite32(tmp); + bstMasterWrite16(sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_SONAR) << 4); #else - uint8_t tmp = 0; - tmp = IS_ENABLED(ARMING_FLAG(ARMED)) | - IS_ENABLED(FLIGHT_MODE(ANGLE_MODE)) << 1 | - IS_ENABLED(FLIGHT_MODE(HORIZON_MODE)) << 2 | - IS_ENABLED(FLIGHT_MODE(BARO_MODE)) << 3 | - IS_ENABLED(FLIGHT_MODE(MAG_MODE)) << 4 | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXAIRMODE)) << 5 | - IS_ENABLED(FLIGHT_MODE(SONAR_MODE)) << 6 | - IS_ENABLED(FLIGHT_MODE(FAILSAFE_MODE)) << 7; + uint8_t tmp = 0; + tmp = IS_ENABLED(ARMING_FLAG(ARMED)) | + IS_ENABLED(FLIGHT_MODE(ANGLE_MODE)) << 1 | + IS_ENABLED(FLIGHT_MODE(HORIZON_MODE)) << 2 | + IS_ENABLED(FLIGHT_MODE(BARO_MODE)) << 3 | + IS_ENABLED(FLIGHT_MODE(MAG_MODE)) << 4 | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXAIRMODE)) << 5 | + IS_ENABLED(FLIGHT_MODE(SONAR_MODE)) << 6 | + IS_ENABLED(FLIGHT_MODE(FAILSAFE_MODE)) << 7; - bstMasterStartBuffer(PUBLIC_ADDRESS); - bstMasterWrite8(CLEANFLIGHT_MODE_FRAME_ID); - bstMasterWrite8(tmp); - bstMasterWrite8(sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_SONAR) << 4); + bstMasterStartBuffer(PUBLIC_ADDRESS); + bstMasterWrite8(CLEANFLIGHT_MODE_FRAME_ID); + bstMasterWrite8(tmp); + bstMasterWrite8(sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_SONAR) << 4); #endif - return bstMasterWrite(masterWriteData); + return bstMasterWrite(masterWriteData); } /*************************************************************************************************/ diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h index 527ffbbfbf..68bf284483 100755 --- a/src/main/target/COLIBRI_RACE/target.h +++ b/src/main/target/COLIBRI_RACE/target.h @@ -103,16 +103,8 @@ #define USE_I2C #define I2C_DEVICE (I2CDEV_2) -#define I2C2_SCL_GPIO GPIOA -#define I2C2_SCL_GPIO_AF GPIO_AF_4 -#define I2C2_SCL_PIN GPIO_Pin_9 -#define I2C2_SCL_PIN_SOURCE GPIO_PinSource9 -#define I2C2_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOA -#define I2C2_SDA_GPIO GPIOA -#define I2C2_SDA_GPIO_AF GPIO_AF_4 -#define I2C2_SDA_PIN GPIO_Pin_10 -#define I2C2_SDA_PIN_SOURCE GPIO_PinSource10 -#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA +#define I2C2_SCL_PIN PA9 +#define I2C2_SDA_PIN PA10 #define USE_BST #define BST_DEVICE (BSTDEV_1) @@ -120,32 +112,17 @@ #define BST_CRC_POLYNOM 0xD5 #define USE_ADC - #define ADC_INSTANCE ADC1 -#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1 -#define ADC_DMA_CHANNEL DMA1_Channel1 - #define BOARD_HAS_VOLTAGE_DIVIDER -#define VBAT_ADC_GPIO GPIOC -#define VBAT_ADC_GPIO_PIN GPIO_Pin_0 -#define VBAT_ADC_CHANNEL ADC_Channel_6 - -#define CURRENT_METER_ADC_GPIO GPIOC -#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_7 - -#define RSSI_ADC_GPIO GPIOC -#define RSSI_ADC_GPIO_PIN GPIO_Pin_2 -#define RSSI_ADC_CHANNEL ADC_Channel_8 - -#define EXTERNAL1_ADC_GPIO GPIOC -#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_3 -#define EXTERNAL1_ADC_CHANNEL ADC_Channel_9 +#define VBAT_ADC_PIN PC0 +#define CURRENT_METER_ADC_PIN PC1 +#define RSSI_ADC_PIN PC2 +#define EXTERNAL1_ADC_PIN PC3 #define LED_STRIP #define USE_COLIBTI_RACE_LED_DEFAULT_CONFIG -#define LED_STRIP_TIMER TIM16 +#define LED_STRIP_TIMER TIM16 #define WS2811_GPIO GPIOA #define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA diff --git a/src/main/target/DOGE/target.h b/src/main/target/DOGE/target.h index b5ed0ec599..44a16782b1 100644 --- a/src/main/target/DOGE/target.h +++ b/src/main/target/DOGE/target.h @@ -34,44 +34,29 @@ #define BEEPER_INVERTED // tqfp48 pin 3 -#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOC -#define MPU6500_CS_GPIO GPIOC #define MPU6500_CS_PIN PC14 #define MPU6500_SPI_INSTANCE SPI1 // tqfp48 pin 25 -#define BMP280_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOB -#define BMP280_CS_GPIO GPIOB -#define BMP280_CS_PIN GPIO_Pin_12 +#define BMP280_CS_PIN PB12 #define BMP280_SPI_INSTANCE SPI2 #define USE_SPI #define USE_SPI_DEVICE_1 #define USE_SPI_DEVICE_2 -#define SPI1_GPIO GPIOB -#define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB // tqfp48 pin 39 #define SPI1_SCK_PIN PB3 -#define SPI1_SCK_PIN_SOURCE GPIO_PinSource3 // tqfp48 pin 40 #define SPI1_MISO_PIN PB4 -#define SPI1_MISO_PIN_SOURCE GPIO_PinSource4 // tqfp48 pin 41 #define SPI1_MOSI_PIN PB5 -#define SPI1_MOSI_PIN_SOURCE GPIO_PinSource5 - -#define SPI2_GPIO GPIOB -#define SPI2_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB // tqfp48 pin 26 #define SPI2_SCK_PIN PB13 -#define SPI2_SCK_PIN_SOURCE GPIO_PinSource13 // tqfp48 pin 27 #define SPI2_MISO_PIN PB14 -#define SPI2_MISO_PIN_SOURCE GPIO_PinSource14 // tqfp48 pin 28 #define SPI2_MOSI_PIN PB15 -#define SPI2_MOSI_PIN_SOURCE GPIO_PinSource15 #define USE_FLASHFS #define USE_FLASH_M25P16 @@ -139,20 +124,9 @@ #define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER - #define ADC_INSTANCE ADC2 -#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2 -#define ADC_DMA_CHANNEL DMA2_Channel1 - -// tqfp48 pin 14 -#define VBAT_ADC_GPIO GPIOA -#define VBAT_ADC_GPIO_PIN GPIO_Pin_4 -#define VBAT_ADC_CHANNEL ADC_Channel_1 - -// tqfp48 pin 15 -#define CURRENT_METER_ADC_GPIO GPIOA -#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 // mpu_int definition in sensors/initialisation.c #define USE_EXTI diff --git a/src/main/target/EUSTM32F103RC/sonar_config.c b/src/main/target/EUSTM32F103RC/sonar_config.c deleted file mode 100644 index e2f4fb7b19..0000000000 --- a/src/main/target/EUSTM32F103RC/sonar_config.c +++ /dev/null @@ -1,28 +0,0 @@ - -#include "drivers/sonar_hcsr04.h" -#include "drivers/io.h" -#include "config/runtime_config.h" -#include "config/config.h" - -#include "sensors/battery.h" -#include "sensors/sonar.h" - -const sonarHardware_t *sonarGetTargetHardwareConfiguration(batteryConfig_t *batteryConfig) -{ - static const sonarHardware_t const sonarPWM56 = { - .triggerIO = IO_TAG(PB8), - .echoIO = IO_TAG(PB9), - }; - static const sonarHardware_t sonarRC78 = { - .triggerIO = IO_TAG(PB0), - .echoIO = IO_TAG(PB1), - }; - // If we are using softserial, parallel PWM or ADC current sensor, then use motor pins 5 and 6 for sonar, otherwise use rc pins 7 and 8 - if (feature(FEATURE_SOFTSERIAL) - || feature(FEATURE_RX_PARALLEL_PWM ) - || (feature(FEATURE_CURRENT_METER) && batteryConfig->currentMeterType == CURRENT_SENSOR_ADC)) { - return &sonarPWM56; - } else { - return &sonarRC78; - } -} \ No newline at end of file diff --git a/src/main/target/EUSTM32F103RC/target.h b/src/main/target/EUSTM32F103RC/target.h index 2545ff49f6..d6d916bb28 100644 --- a/src/main/target/EUSTM32F103RC/target.h +++ b/src/main/target/EUSTM32F103RC/target.h @@ -69,7 +69,10 @@ #define MAG_AK8975_ALIGN CW180_DEG_FLIP #define SONAR -#define SONAR_CUSTOM_CONFIG +#define SONAR_TRIGGER_PIN PB0 +#define SONAR_ECHO_PIN PB1 +#define SONAR_TRIGGER_PIN_PWM PB8 +#define SONAR_ECHO_PIN_PWM PB9 #define DISPLAY @@ -94,22 +97,10 @@ // #define SOFT_I2C_PB67 #define USE_ADC - -#define CURRENT_METER_ADC_GPIO GPIOB -#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_9 - -#define VBAT_ADC_GPIO GPIOA -#define VBAT_ADC_GPIO_PIN GPIO_Pin_4 -#define VBAT_ADC_CHANNEL ADC_Channel_4 - -#define RSSI_ADC_GPIO GPIOA -#define RSSI_ADC_GPIO_PIN GPIO_Pin_1 -#define RSSI_ADC_CHANNEL ADC_Channel_1 - -#define EXTERNAL1_ADC_GPIO GPIOA -#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_5 -#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5 +#define CURRENT_METER_ADC_PIN PB1 +#define VBAT_ADC_PIN PA4 +#define RSSI_ADC_PIN PA1 +#define EXTERNAL1_ADC_PIN PA5 //#define LED_STRIP #define LED_STRIP_TIMER TIM3 diff --git a/src/main/target/EUSTM32F103RC/target.mk b/src/main/target/EUSTM32F103RC/target.mk index c12a9fa269..b315c0aacb 100644 --- a/src/main/target/EUSTM32F103RC/target.mk +++ b/src/main/target/EUSTM32F103RC/target.mk @@ -11,6 +11,7 @@ TARGET_SRC = \ drivers/accgyro_mpu.c \ drivers/accgyro_mpu3050.c \ drivers/accgyro_mpu6050.c \ + drivers/accgyro_mpu6500.c \ drivers/accgyro_spi_mpu6000.c \ drivers/accgyro_spi_mpu6500.c \ drivers/barometer_bmp085.c \ diff --git a/src/main/target/FURYF3/target.h b/src/main/target/FURYF3/target.h index afba1e344e..6201b8b3f0 100644 --- a/src/main/target/FURYF3/target.h +++ b/src/main/target/FURYF3/target.h @@ -150,25 +150,13 @@ #define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER - #define ADC_INSTANCE ADC1 -#define ADC_DMA_CHANNEL DMA1_Channel1 -#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1 - -#define VBAT_ADC_GPIO GPIOA -#define VBAT_ADC_GPIO_PIN GPIO_Pin_0 -#define VBAT_ADC_CHANNEL ADC_Channel_1 - -#define RSSI_ADC_GPIO GPIOA -#define RSSI_ADC_GPIO_PIN GPIO_Pin_1 -#define RSSI_ADC_CHANNEL ADC_Channel_2 - -#define CURRENT_METER_ADC_GPIO GPIOA -#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_2 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_3 +#define VBAT_ADC_PIN PA0 +#define RSSI_ADC_PIN PA1 +#define CURRENT_METER_ADC_PIN PA2 #define LED_STRIP -#define LED_STRIP_TIMER TIM1 +#define LED_STRIP_TIMER TIM1 #define USE_LED_STRIP_ON_DMA1_CHANNEL2 #define WS2811_GPIO GPIOA diff --git a/src/main/target/FURYF4/target.h b/src/main/target/FURYF4/target.h index 0c524c3e6e..a6586c95cd 100644 --- a/src/main/target/FURYF4/target.h +++ b/src/main/target/FURYF4/target.h @@ -144,15 +144,9 @@ #define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER - -#define VBAT_ADC_PIN PC1 -#define VBAT_ADC_CHANNEL ADC_Channel_11 - -#define RSSI_ADC_GPIO_PIN PC2 -#define RSSI_ADC_CHANNEL ADC_Channel_12 - +#define VBAT_ADC_PIN PC1 +#define RSSI_ADC_GPIO_PIN PC2 #define CURRENT_METER_ADC_PIN PC3 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_13 #define DEFAULT_RX_FEATURE FEATURE_RX_PPM diff --git a/src/main/target/IRCFUSIONF3/target.h b/src/main/target/IRCFUSIONF3/target.h index 963fc0e6bf..9588159722 100644 --- a/src/main/target/IRCFUSIONF3/target.h +++ b/src/main/target/IRCFUSIONF3/target.h @@ -80,33 +80,19 @@ #define USE_SPI #define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 -#define M25P16_CS_GPIO GPIOB #define M25P16_CS_PIN PB12 #define M25P16_SPI_INSTANCE SPI2 #define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER - - #define ADC_INSTANCE ADC2 -#define ADC_DMA_CHANNEL DMA2_Channel1 -#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2 - -#define VBAT_ADC_GPIO GPIOA -#define VBAT_ADC_GPIO_PIN GPIO_Pin_4 -#define VBAT_ADC_CHANNEL ADC_Channel_1 - -#define CURRENT_METER_ADC_GPIO GPIOA -#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2 - -#define RSSI_ADC_GPIO GPIOB -#define RSSI_ADC_GPIO_PIN GPIO_Pin_2 -#define RSSI_ADC_CHANNEL ADC_Channel_12 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 #define SPEKTRUM_BIND // USART3, -#define BIND_PIN PB11 +#define BIND_PIN PB11 #define USE_SERIAL_4WAY_BLHELI_INTERFACE /* diff --git a/src/main/target/KISSFC/target.h b/src/main/target/KISSFC/target.h index 211b0ea211..03c3cf31f6 100644 --- a/src/main/target/KISSFC/target.h +++ b/src/main/target/KISSFC/target.h @@ -72,23 +72,11 @@ #define USE_I2C #define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA - +//#define USE_ADC #define ADC_INSTANCE ADC2 -#define ADC_DMA_CHANNEL DMA2_Channel1 -#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2 - -#define VBAT_ADC_GPIO GPIOA -#define VBAT_ADC_GPIO_PIN GPIO_Pin_4 -#define VBAT_ADC_CHANNEL ADC_Channel_1 - -#define CURRENT_METER_ADC_GPIO GPIOA -#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2 - -#define RSSI_ADC_GPIO GPIOB -#define RSSI_ADC_GPIO_PIN GPIO_Pin_2 -#define RSSI_ADC_CHANNEL ADC_Channel_12 - +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 #define SPEKTRUM_BIND diff --git a/src/main/target/LUX_RACE/target.h b/src/main/target/LUX_RACE/target.h index 44ef0818c2..6292d2435f 100644 --- a/src/main/target/LUX_RACE/target.h +++ b/src/main/target/LUX_RACE/target.h @@ -88,30 +88,14 @@ #define I2C_DEVICE (I2CDEV_2) #define USE_ADC - #define ADC_INSTANCE ADC1 -#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1 -#define ADC_DMA_CHANNEL DMA1_Channel1 - -#define VBAT_ADC_GPIO GPIOC -#define VBAT_ADC_GPIO_PIN GPIO_Pin_0 -#define VBAT_ADC_CHANNEL ADC_Channel_6 - -#define CURRENT_METER_ADC_GPIO GPIOC -#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_7 - -#define RSSI_ADC_GPIO GPIOC -#define RSSI_ADC_GPIO_PIN GPIO_Pin_2 -#define RSSI_ADC_CHANNEL ADC_Channel_8 - -#define EXTERNAL1_ADC_GPIO GPIOC -#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_3 -#define EXTERNAL1_ADC_CHANNEL ADC_Channel_9 +#define VBAT_ADC_PIN PC0 +#define CURRENT_METER_ADC_PIN PC1 +#define RSSI_ADC_PIN PC2 +#define EXTERNAL1_ADC_PIN PC3 #define LED_STRIP - -#define LED_STRIP_TIMER TIM16 +#define LED_STRIP_TIMER TIM16 #define WS2811_GPIO GPIOA #define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA diff --git a/src/main/target/MOTOLAB/target.h b/src/main/target/MOTOLAB/target.h index d4f03bfec8..27bf98691b 100644 --- a/src/main/target/MOTOLAB/target.h +++ b/src/main/target/MOTOLAB/target.h @@ -119,22 +119,10 @@ #define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER - #define ADC_INSTANCE ADC2 -#define ADC_DMA_CHANNEL DMA2_Channel1 -#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2 - -#define VBAT_ADC_GPIO GPIOA -#define VBAT_ADC_GPIO_PIN GPIO_Pin_5 -#define VBAT_ADC_CHANNEL ADC_Channel_2 - -//#define CURRENT_METER_ADC_GPIO GPIOA -//#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5 -//#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2 - -#define RSSI_ADC_GPIO GPIOB -#define RSSI_ADC_GPIO_PIN GPIO_Pin_2 -#define RSSI_ADC_CHANNEL ADC_Channel_12 +#define VBAT_ADC_PIN PA5 +//#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 #define LED_STRIP #if 1 diff --git a/src/main/target/NAZE/hardware_revision.c b/src/main/target/NAZE/hardware_revision.c index d9f540eb9f..d71edde627 100755 --- a/src/main/target/NAZE/hardware_revision.c +++ b/src/main/target/NAZE/hardware_revision.c @@ -113,18 +113,19 @@ void updateHardwareRevision(void) const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void) { - // MPU_INT output on rev4 PB13 - static const extiConfig_t nazeRev4MPUIntExtiConfig = { - .io = IO_TAG(PB13) - }; // MPU_INT output on rev5 hardware PC13 static const extiConfig_t nazeRev5MPUIntExtiConfig = { - .io = IO_TAG(PC13) + .tag = IO_TAG(PC13) }; #ifdef AFROMINI return &nazeRev5MPUIntExtiConfig; #else + // MPU_INT output on rev4 PB13 + static const extiConfig_t nazeRev4MPUIntExtiConfig = { + .tag = IO_TAG(PB13) + }; + if (hardwareRevision < NAZE32_REV5) { return &nazeRev4MPUIntExtiConfig; } diff --git a/src/main/target/NAZE/sonar_config.c b/src/main/target/NAZE/sonar_config.c deleted file mode 100644 index 3362146c0d..0000000000 --- a/src/main/target/NAZE/sonar_config.c +++ /dev/null @@ -1,28 +0,0 @@ - -#include "drivers/sonar_hcsr04.h" -#include "drivers/io.h" -#include "config/runtime_config.h" -#include "config/config.h" - -#include "sensors/battery.h" -#include "sensors/sonar.h" - -const sonarHardware_t *sonarGetTargetHardwareConfiguration(batteryConfig_t *batteryConfig) -{ - static const sonarHardware_t const sonarPWM56 = { - .triggerIO = IO_TAG(PB8), - .echoIO = IO_TAG(PB9), - }; - static const sonarHardware_t sonarRC78 = { - .triggerIO = IO_TAG(PB0), - .echoIO = IO_TAG(PB1), - }; - // If we are using softserial, parallel PWM or ADC current sensor, then use motor pins 5 and 6 for sonar, otherwise use rc pins 7 and 8 - if (feature(FEATURE_SOFTSERIAL) - || feature(FEATURE_RX_PARALLEL_PWM ) - || (feature(FEATURE_CURRENT_METER) && batteryConfig->currentMeterType == CURRENT_SENSOR_ADC)) { - return &sonarPWM56; - } else { - return &sonarRC78; - } -} diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index a99c0040ef..9f6e3d2b22 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -33,8 +33,8 @@ #define BARO_XCLR_PIN PC13 #define BARO_EOC_PIN PC14 -#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO -#define INVERTER_USART USART2 +#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO +#define INVERTER_USART USART2 #define USE_EXTI @@ -111,7 +111,11 @@ #define MAG_HMC5883_ALIGN CW180_DEG #define SONAR -#define SONAR_CUSTOM_CONFIG +#define SONAR_TRIGGER_PIN PB0 +#define SONAR_ECHO_PIN PB1 +#define SONAR_TRIGGER_PIN_PWM PB8 +#define SONAR_ECHO_PIN_PWM PB9 + #define DISPLAY #define USE_USART1 @@ -143,26 +147,14 @@ // #define SOFT_I2C_PB67 #define USE_ADC - -#define CURRENT_METER_ADC_GPIO GPIOB -#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_9 - -#define VBAT_ADC_GPIO GPIOA -#define VBAT_ADC_GPIO_PIN GPIO_Pin_4 -#define VBAT_ADC_CHANNEL ADC_Channel_4 - -#define RSSI_ADC_GPIO GPIOA -#define RSSI_ADC_GPIO_PIN GPIO_Pin_1 -#define RSSI_ADC_CHANNEL ADC_Channel_1 - -#define EXTERNAL1_ADC_GPIO GPIOA -#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_5 -#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5 +#define CURRENT_METER_ADC_PIN PB1 +#define VBAT_ADC_PIN PA4 +#define RSSI_ADC_PIN PA1 +#define EXTERNAL1_ADC_PIN PA5 #define LED_STRIP -#define LED_STRIP_TIMER TIM3 +#define LED_STRIP_TIMER TIM3 #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6 #define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER diff --git a/src/main/target/OLIMEXINO/target.h b/src/main/target/OLIMEXINO/target.h index 8a0b35cf2c..b7972ad777 100644 --- a/src/main/target/OLIMEXINO/target.h +++ b/src/main/target/OLIMEXINO/target.h @@ -83,22 +83,10 @@ // #define SOFT_I2C_PB67 #define USE_ADC - -#define CURRENT_METER_ADC_GPIO GPIOB -#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_9 - -#define VBAT_ADC_GPIO GPIOA -#define VBAT_ADC_GPIO_PIN GPIO_Pin_4 -#define VBAT_ADC_CHANNEL ADC_Channel_4 - -#define RSSI_ADC_GPIO GPIOA -#define RSSI_ADC_GPIO_PIN GPIO_Pin_1 -#define RSSI_ADC_CHANNEL ADC_Channel_1 - -#define EXTERNAL1_ADC_GPIO GPIOA -#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_5 -#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5 +#define CURRENT_METER_ADC_PIN PB1 +#define VBAT_ADC_PIN PA4 +#define RSSI_ADC_PIN PA1 +#define EXTERNAL1_ADC_PIN PA5 //#define LED_STRIP //#define LED_STRIP_TIMER TIM3 diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h index 9eb39d6dbf..c9eb4a59da 100644 --- a/src/main/target/OMNIBUS/target.h +++ b/src/main/target/OMNIBUS/target.h @@ -159,26 +159,14 @@ #define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER - - #define ADC_INSTANCE ADC2 -#define ADC_DMA_CHANNEL DMA2_Channel1 -#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 -#define VBAT_ADC_GPIO GPIOA -#define VBAT_ADC_GPIO_PIN GPIO_Pin_4 -#define VBAT_ADC_CHANNEL ADC_Channel_1 - -#define CURRENT_METER_ADC_GPIO GPIOA -#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2 - -#define RSSI_ADC_GPIO GPIOB -#define RSSI_ADC_GPIO_PIN GPIO_Pin_2 -#define RSSI_ADC_CHANNEL ADC_Channel_12 #define LED_STRIP -#define LED_STRIP_TIMER TIM1 +#define LED_STRIP_TIMER TIM1 #define WS2811_GPIO GPIOA #define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA @@ -210,6 +198,7 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT #define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES FEATURE_BLACKBOX #define BUTTONS #define BUTTON_A_PORT GPIOB diff --git a/src/main/target/PIKOBLX/target.h b/src/main/target/PIKOBLX/target.h index 8a25943114..8b14570c91 100644 --- a/src/main/target/PIKOBLX/target.h +++ b/src/main/target/PIKOBLX/target.h @@ -87,26 +87,14 @@ #define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER - #define ADC_INSTANCE ADC2 -#define ADC_DMA_CHANNEL DMA2_Channel1 -#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2 - -#define CURRENT_METER_ADC_GPIO GPIOA -#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_2 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_3 - -#define VBAT_ADC_GPIO GPIOA -#define VBAT_ADC_GPIO_PIN GPIO_Pin_5 -#define VBAT_ADC_CHANNEL ADC_Channel_2 - -#define RSSI_ADC_GPIO GPIOB -#define RSSI_ADC_GPIO_PIN GPIO_Pin_2 -#define RSSI_ADC_CHANNEL ADC_Channel_12 +#define CURRENT_METER_ADC_PIN PA2 +#define VBAT_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 #define LED_STRIP #if 1 -#define LED_STRIP_TIMER TIM16 +#define LED_STRIP_TIMER TIM16 #define USE_LED_STRIP_ON_DMA1_CHANNEL3 #define WS2811_GPIO GPIOB diff --git a/src/main/target/PORT103R/sonar_config.c b/src/main/target/PORT103R/sonar_config.c deleted file mode 100644 index e2f4fb7b19..0000000000 --- a/src/main/target/PORT103R/sonar_config.c +++ /dev/null @@ -1,28 +0,0 @@ - -#include "drivers/sonar_hcsr04.h" -#include "drivers/io.h" -#include "config/runtime_config.h" -#include "config/config.h" - -#include "sensors/battery.h" -#include "sensors/sonar.h" - -const sonarHardware_t *sonarGetTargetHardwareConfiguration(batteryConfig_t *batteryConfig) -{ - static const sonarHardware_t const sonarPWM56 = { - .triggerIO = IO_TAG(PB8), - .echoIO = IO_TAG(PB9), - }; - static const sonarHardware_t sonarRC78 = { - .triggerIO = IO_TAG(PB0), - .echoIO = IO_TAG(PB1), - }; - // If we are using softserial, parallel PWM or ADC current sensor, then use motor pins 5 and 6 for sonar, otherwise use rc pins 7 and 8 - if (feature(FEATURE_SOFTSERIAL) - || feature(FEATURE_RX_PARALLEL_PWM ) - || (feature(FEATURE_CURRENT_METER) && batteryConfig->currentMeterType == CURRENT_SENSOR_ADC)) { - return &sonarPWM56; - } else { - return &sonarRC78; - } -} \ No newline at end of file diff --git a/src/main/target/PORT103R/target.h b/src/main/target/PORT103R/target.h index 2e0292bc51..64e0b6455c 100644 --- a/src/main/target/PORT103R/target.h +++ b/src/main/target/PORT103R/target.h @@ -38,22 +38,17 @@ #define USE_SPI_DEVICE_2 #define PORT103R_SPI_INSTANCE SPI2 -#define PORT103R_SPI_CS_GPIO GPIOB #define PORT103R_SPI_CS_PIN PB12 // We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision: -#define M25P16_CS_GPIO PORT103R_SPI_CS_GPIO #define M25P16_CS_PIN PORT103R_SPI_CS_PIN #define M25P16_SPI_INSTANCE PORT103R_SPI_INSTANCE -#define MPU6000_CS_GPIO PORT103R_SPI_CS_GPIO #define MPU6000_CS_PIN PORT103R_SPI_CS_PIN #define MPU6000_SPI_INSTANCE PORT103R_SPI_INSTANCE -#define MPU6500_CS_GPIO PORT103R_SPI_CS_GPIO #define MPU6500_CS_PIN PORT103R_SPI_CS_PIN #define MPU6500_SPI_INSTANCE PORT103R_SPI_INSTANCE -#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOB #define GYRO #define USE_FAKE_GYRO @@ -87,7 +82,10 @@ #define USE_FLASH_M25P16 #define SONAR -#define SONAR_CUSTOM_CONFIG +#define SONAR_TRIGGER_PIN PB0 +#define SONAR_ECHO_PIN PB1 +#define SONAR_TRIGGER_PIN_PWM PB8 +#define SONAR_ECHO_PIN_PWM PB9 #define DISPLAY @@ -112,22 +110,10 @@ // #define SOFT_I2C_PB67 #define USE_ADC - -#define CURRENT_METER_ADC_GPIO GPIOB -#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_9 - -#define VBAT_ADC_GPIO GPIOA -#define VBAT_ADC_GPIO_PIN GPIO_Pin_4 -#define VBAT_ADC_CHANNEL ADC_Channel_4 - -#define RSSI_ADC_GPIO GPIOA -#define RSSI_ADC_GPIO_PIN GPIO_Pin_1 -#define RSSI_ADC_CHANNEL ADC_Channel_1 - -#define EXTERNAL1_ADC_GPIO GPIOA -#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_5 -#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5 +#define CURRENT_METER_ADC_PIN PB1 +#define VBAT_ADC_PIN PA4 +#define RSSI_ADC_PIN PA1 +#define EXTERNAL1_ADC_PIN PA5 //#define LED_STRIP //#define LED_STRIP_TIMER TIM3 diff --git a/src/main/target/PORT103R/target.mk b/src/main/target/PORT103R/target.mk index 507b303bff..411a04e02b 100644 --- a/src/main/target/PORT103R/target.mk +++ b/src/main/target/PORT103R/target.mk @@ -11,6 +11,7 @@ TARGET_SRC = \ drivers/accgyro_mpu.c \ drivers/accgyro_mpu3050.c \ drivers/accgyro_mpu6050.c \ + drivers/accgyro_mpu6500.c \ drivers/accgyro_spi_mpu6000.c \ drivers/accgyro_spi_mpu6500.c \ drivers/barometer_bmp085.c \ diff --git a/src/main/target/REVO/target.h b/src/main/target/REVO/target.h index 4c3972a69a..cda67742e6 100644 --- a/src/main/target/REVO/target.h +++ b/src/main/target/REVO/target.h @@ -20,23 +20,17 @@ #define TARGET_BOARD_IDENTIFIER "REVO" #define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8) -#define CONFIG_SERIALRX_PROVIDER SERIALRX_SBUS -#define CONFIG_BLACKBOX_DEVICE BLACKBOX_DEVICE_FLASH -#define CONFIG_FEATURE_RX_SERIAL -#define CONFIG_FEATURE_ONESHOT125 -#define CONFIG_MSP_PORT 2 -#define CONFIG_RX_SERIAL_PORT 1 #define USBD_PRODUCT_STRING "Revolution" #ifdef OPBL #define USBD_SERIALNUMBER_STRING "0x8020000" #endif -#define LED0 PB5 -#define LED1 PB4 -#define BEEPER PB4 -#define INVERTER PC0 // PC0 used as inverter select GPIO -#define INVERTER_USART USART1 +#define LED0 PB5 +#define LED1 PB4 +#define BEEPER PB4 +#define INVERTER PC0 // PC0 used as inverter select GPIO +#define INVERTER_USART USART1 #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_INSTANCE SPI1 @@ -110,14 +104,10 @@ #define USE_ADC #define CURRENT_METER_ADC_PIN PC1 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_11 - -#define VBAT_ADC_PIN PC2 -#define VBAT_ADC_CHANNEL ADC_Channel_12 - -#define RSSI_ADC_GPIO_PIN PA0 -#define RSSI_ADC_CHANNEL ADC_Channel_0 +#define VBAT_ADC_PIN PC2 +#define RSSI_ADC_GPIO_PIN PA0 + #define SENSORS_SET (SENSOR_ACC) //#define LED_STRIP diff --git a/src/main/target/REVONANO/target.h b/src/main/target/REVONANO/target.h index 3769f0f701..3c0287f2f7 100644 --- a/src/main/target/REVONANO/target.h +++ b/src/main/target/REVONANO/target.h @@ -19,12 +19,6 @@ #define TARGET_BOARD_IDENTIFIER "REVN" #define CONFIG_START_FLASH_ADDRESS (0x08060000) //0x08060000 to 0x08080000 (FLASH_Sector_7) -#define CONFIG_SERIALRX_PROVIDER 2 -#define CONFIG_BLACKBOX_DEVICE 1 -#define CONFIG_FEATURE_RX_SERIAL -#define CONFIG_FEATURE_ONESHOT125 -#define CONFIG_MSP_PORT 1 -#define CONFIG_RX_SERIAL_PORT 2 #define USBD_PRODUCT_STRING "Revo Nano" #ifdef OPBL @@ -87,18 +81,9 @@ #define I2C_DEVICE (I2CDEV_3) #define USE_ADC - -//FLEXI-IO 6 #define CURRENT_METER_ADC_PIN PA7 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_7 - -//FLEXI-IO 7 #define VBAT_ADC_PIN PA6 -#define VBAT_ADC_CHANNEL ADC_Channel_6 - -//FLEXI-IO 8 #define RSSI_ADC_PIN PA5 -#define RSSI_ADC_CHANNEL ADC_Channel_5 //#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG) diff --git a/src/main/target/RMDO/target.h b/src/main/target/RMDO/target.h index 3bf23f6916..779b8ab6ce 100644 --- a/src/main/target/RMDO/target.h +++ b/src/main/target/RMDO/target.h @@ -106,26 +106,13 @@ #define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER - - #define ADC_INSTANCE ADC2 -#define ADC_DMA_CHANNEL DMA2_Channel1 -#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2 - -#define VBAT_ADC_GPIO GPIOA -#define VBAT_ADC_GPIO_PIN GPIO_Pin_4 -#define VBAT_ADC_CHANNEL ADC_Channel_1 - -#define CURRENT_METER_ADC_GPIO GPIOA -#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2 - -#define RSSI_ADC_GPIO GPIOB -#define RSSI_ADC_GPIO_PIN GPIO_Pin_2 -#define RSSI_ADC_CHANNEL ADC_Channel_12 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 #define LED_STRIP -#define LED_STRIP_TIMER TIM1 +#define LED_STRIP_TIMER TIM1 #define USE_LED_STRIP_ON_DMA1_CHANNEL2 #define WS2811_GPIO GPIOA diff --git a/src/main/target/SINGULARITY/target.h b/src/main/target/SINGULARITY/target.h index 298d183b42..192971fd11 100644 --- a/src/main/target/SINGULARITY/target.h +++ b/src/main/target/SINGULARITY/target.h @@ -94,12 +94,7 @@ #define BOARD_HAS_VOLTAGE_DIVIDER #define ADC_INSTANCE ADC2 -#define ADC_DMA_CHANNEL DMA2_Channel1 -#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2 - -#define VBAT_ADC_GPIO GPIOB -#define VBAT_ADC_GPIO_PIN GPIO_Pin_2 -#define VBAT_ADC_CHANNEL ADC_Channel_12 +#define VBAT_ADC_PIN PB2 #define LED_STRIP #define LED_STRIP_TIMER TIM1 @@ -117,8 +112,10 @@ #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 #define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER -#define DEFAULT_RX_FEATURE FEATURE_RX_PPM -#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_RX_SERIAL) +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define DEFAULT_FEATURES FEATURE_BLACKBOX #define SPEKTRUM_BIND // USART2, PA15 diff --git a/src/main/target/SIRINFPV/target.h b/src/main/target/SIRINFPV/target.h index fbbaf6b7b9..cf6eacf4cb 100644 --- a/src/main/target/SIRINFPV/target.h +++ b/src/main/target/SIRINFPV/target.h @@ -142,17 +142,12 @@ // Performance logging for SD card operations: // #define AFATFS_USE_INTROSPECTIVE_LOGGING -#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_RX_SERIAL | FEATURE_OSD | FEATURE_VTX) + #define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER #define ADC_INSTANCE ADC1 -#define ADC_DMA_CHANNEL DMA1_Channel1 -#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1 - -#define VBAT_ADC_GPIO GPIOA -#define VBAT_ADC_GPIO_PIN GPIO_Pin_0 -#define VBAT_ADC_CHANNEL ADC_Channel_1 +#define VBAT_ADC_PIN PA0 //#define USE_QUAD_MIXER_ONLY #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT @@ -162,6 +157,7 @@ #define USE_SERVOS #define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_RX_SERIAL | FEATURE_OSD | FEATURE_VTX) #define USE_SERIAL_4WAY_BLHELI_INTERFACE diff --git a/src/main/target/SPARKY/target.h b/src/main/target/SPARKY/target.h index 29b764d9f8..58101f0b85 100644 --- a/src/main/target/SPARKY/target.h +++ b/src/main/target/SPARKY/target.h @@ -87,37 +87,17 @@ #define USE_I2C #define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4) -#define I2C2_SCL_GPIO GPIOA -#define I2C2_SCL_GPIO_AF GPIO_AF_4 -#define I2C2_SCL_PIN GPIO_Pin_9 -#define I2C2_SCL_PIN_SOURCE GPIO_PinSource9 -#define I2C2_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOA -#define I2C2_SDA_GPIO GPIOA -#define I2C2_SDA_GPIO_AF GPIO_AF_4 -#define I2C2_SDA_PIN GPIO_Pin_10 -#define I2C2_SDA_PIN_SOURCE GPIO_PinSource10 -#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA - #define USE_ADC - #define ADC_INSTANCE ADC2 -#define ADC_DMA_CHANNEL DMA2_Channel1 -#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA7 -#define VBAT_ADC_GPIO GPIOA -#define VBAT_ADC_GPIO_PIN GPIO_Pin_4 -#define VBAT_ADC_CHANNEL ADC_Channel_1 - -#define CURRENT_METER_ADC_GPIO GPIOA -#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_7 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_4 - -#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define LED_STRIP #if 1 // LED strip configuration using PWM motor output pin 5. -#define LED_STRIP_TIMER TIM16 +#define LED_STRIP_TIMER TIM16 #define USE_LED_STRIP_ON_DMA1_CHANNEL3 #define WS2811_GPIO GPIOA diff --git a/src/main/target/SPRACINGF3/target.h b/src/main/target/SPRACINGF3/target.h index 929a5f3fd3..68413bbe0b 100644 --- a/src/main/target/SPRACINGF3/target.h +++ b/src/main/target/SPRACINGF3/target.h @@ -114,26 +114,13 @@ #define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER - - #define ADC_INSTANCE ADC2 -#define ADC_DMA_CHANNEL DMA2_Channel1 -#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2 - -#define VBAT_ADC_GPIO GPIOA -#define VBAT_ADC_GPIO_PIN GPIO_Pin_4 -#define VBAT_ADC_CHANNEL ADC_Channel_1 - -#define CURRENT_METER_ADC_GPIO GPIOA -#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2 - -#define RSSI_ADC_GPIO GPIOB -#define RSSI_ADC_GPIO_PIN GPIO_Pin_2 -#define RSSI_ADC_CHANNEL ADC_Channel_12 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 #define LED_STRIP -#define LED_STRIP_TIMER TIM1 +#define LED_STRIP_TIMER TIM1 #define USE_LED_STRIP_ON_DMA1_CHANNEL2 #define WS2811_GPIO GPIOA @@ -148,6 +135,8 @@ #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 #define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + #define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define DEFAULT_FEATURES FEATURE_BLACKBOX diff --git a/src/main/target/SPRACINGF3/target.mk b/src/main/target/SPRACINGF3/target.mk index 00e15bd25f..ed7391c7a8 100644 --- a/src/main/target/SPRACINGF3/target.mk +++ b/src/main/target/SPRACINGF3/target.mk @@ -1,5 +1,5 @@ F3_TARGETS += $(TARGET) -FEATURES = VCP ONBOARDFLASH +FEATURES = ONBOARDFLASH TARGET_SRC = \ drivers/accgyro_mpu.c \ diff --git a/src/main/target/SPRACINGF3EVO/target.h b/src/main/target/SPRACINGF3EVO/target.h index d71254270c..c4a9a04845 100755 --- a/src/main/target/SPRACINGF3EVO/target.h +++ b/src/main/target/SPRACINGF3EVO/target.h @@ -136,25 +136,13 @@ #define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER - #define ADC_INSTANCE ADC2 -#define ADC_DMA_CHANNEL DMA2_Channel1 -#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2 - -#define VBAT_ADC_GPIO GPIOA -#define VBAT_ADC_GPIO_PIN GPIO_Pin_4 -#define VBAT_ADC_CHANNEL ADC_Channel_1 - -#define CURRENT_METER_ADC_GPIO GPIOA -#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2 - -#define RSSI_ADC_GPIO GPIOB -#define RSSI_ADC_GPIO_PIN GPIO_Pin_2 -#define RSSI_ADC_CHANNEL ADC_Channel_12 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 #define LED_STRIP -#define LED_STRIP_TIMER TIM1 +#define LED_STRIP_TIMER TIM1 #define USE_LED_STRIP_ON_DMA1_CHANNEL2 #define WS2811_GPIO GPIOA @@ -185,7 +173,7 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT #define DEFAULT_RX_FEATURE FEATURE_RX_PPM -#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY) +#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY) #define SPEKTRUM_BIND // USART3, diff --git a/src/main/target/SPRACINGF3MINI/target.h b/src/main/target/SPRACINGF3MINI/target.h index 7c18fb2356..93e2204203 100644 --- a/src/main/target/SPRACINGF3MINI/target.h +++ b/src/main/target/SPRACINGF3MINI/target.h @@ -145,23 +145,12 @@ #define ADC_INSTANCE ADC2 -#define ADC_DMA_CHANNEL DMA2_Channel1 -#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2 - -#define VBAT_ADC_GPIO GPIOA -#define VBAT_ADC_GPIO_PIN GPIO_Pin_4 -#define VBAT_ADC_CHANNEL ADC_Channel_1 - -#define CURRENT_METER_ADC_GPIO GPIOA -#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2 - -#define RSSI_ADC_GPIO GPIOB -#define RSSI_ADC_GPIO_PIN GPIO_Pin_2 -#define RSSI_ADC_CHANNEL ADC_Channel_12 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 #define LED_STRIP -#define LED_STRIP_TIMER TIM1 +#define LED_STRIP_TIMER TIM1 #define WS2811_GPIO GPIOA #define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA @@ -193,6 +182,7 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT #define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES FEATURE_BLACKBOX #define BUTTONS #define BUTTON_A_PORT GPIOB diff --git a/src/main/target/STM32F3DISCOVERY/target.h b/src/main/target/STM32F3DISCOVERY/target.h index 1ddf2de9a1..947ad4913a 100644 --- a/src/main/target/STM32F3DISCOVERY/target.h +++ b/src/main/target/STM32F3DISCOVERY/target.h @@ -139,29 +139,14 @@ #define I2C_DEVICE (I2CDEV_1) #define USE_ADC - #define ADC_INSTANCE ADC1 -#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1 -#define ADC_DMA_CHANNEL DMA1_Channel1 - -#define VBAT_ADC_GPIO GPIOC -#define VBAT_ADC_GPIO_PIN GPIO_Pin_0 -#define VBAT_ADC_CHANNEL ADC_Channel_6 - -#define CURRENT_METER_ADC_GPIO GPIOC -#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_7 - -#define RSSI_ADC_GPIO GPIOC -#define RSSI_ADC_GPIO_PIN GPIO_Pin_2 -#define RSSI_ADC_CHANNEL ADC_Channel_8 - -#define EXTERNAL1_ADC_GPIO GPIOC -#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_3 -#define EXTERNAL1_ADC_CHANNEL ADC_Channel_9 +#define VBAT_ADC_PIN PC0 +#define CURRENT_METER_ADC_PIN PC1 +#define RSSI_ADC_PIN PC2 +#define EXTERNAL1_ADC_PIN PC3 #define LED_STRIP -#define LED_STRIP_TIMER TIM16 +#define LED_STRIP_TIMER TIM16 #define WS2811_GPIO GPIOB #define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOB #define WS2811_GPIO_AF GPIO_AF_1 diff --git a/src/main/target/X_RACERSPI/target.c b/src/main/target/X_RACERSPI/target.c new file mode 100644 index 0000000000..ff9c8044f8 --- /dev/null +++ b/src/main/target/X_RACERSPI/target.c @@ -0,0 +1,106 @@ + +#include +#include + +#include +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" + +const uint16_t multiPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM15 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM16 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + 0xFFFF +}; + +const uint16_t multiPWM[] = { + PWM1 | (MAP_TO_PWM_INPUT << 8), + PWM2 | (MAP_TO_PWM_INPUT << 8), + PWM3 | (MAP_TO_PWM_INPUT << 8), + PWM4 | (MAP_TO_PWM_INPUT << 8), + PWM5 | (MAP_TO_PWM_INPUT << 8), + PWM6 | (MAP_TO_PWM_INPUT << 8), + PWM7 | (MAP_TO_PWM_INPUT << 8), + PWM8 | (MAP_TO_PWM_INPUT << 8), + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM15 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM16 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +const uint16_t airPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 + PWM12 | (MAP_TO_SERVO_OUTPUT << 8), + PWM13 | (MAP_TO_SERVO_OUTPUT << 8), + PWM14 | (MAP_TO_SERVO_OUTPUT << 8), + PWM15 | (MAP_TO_SERVO_OUTPUT << 8), + PWM16 | (MAP_TO_SERVO_OUTPUT << 8), + PWM5 | (MAP_TO_SERVO_OUTPUT << 8), + PWM6 | (MAP_TO_SERVO_OUTPUT << 8), + PWM7 | (MAP_TO_SERVO_OUTPUT << 8), + PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #10 + 0xFFFF +}; + +const uint16_t airPWM[] = { + PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1 + PWM2 | (MAP_TO_PWM_INPUT << 8), + PWM3 | (MAP_TO_PWM_INPUT << 8), + PWM4 | (MAP_TO_PWM_INPUT << 8), + PWM5 | (MAP_TO_PWM_INPUT << 8), + PWM6 | (MAP_TO_PWM_INPUT << 8), + PWM7 | (MAP_TO_PWM_INPUT << 8), + PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8 + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 + PWM12 | (MAP_TO_SERVO_OUTPUT << 8), + PWM13 | (MAP_TO_SERVO_OUTPUT << 8), + PWM14 | (MAP_TO_SERVO_OUTPUT << 8), + PWM15 | (MAP_TO_SERVO_OUTPUT << 8), + PWM16 | (MAP_TO_SERVO_OUTPUT << 8), // server #6 + 0xFFFF +}; + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH1 - PA0 - *TIM2_CH1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N + // Production boards swapped RC_CH3/4 swapped to make it easier to use SerialRX using supplied cables - compared to first prototype. + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH5 - PB4 - *TIM3_CH1 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH6 - PB5 - *TIM3_CH2 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM3 - PA11 + { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM4 - PA12 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM8 - PA3 + + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP +}; + diff --git a/src/main/target/X_RACERSPI/target.h b/src/main/target/X_RACERSPI/target.h new file mode 100644 index 0000000000..a655c93e25 --- /dev/null +++ b/src/main/target/X_RACERSPI/target.h @@ -0,0 +1,161 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "X_RACERSPI" + +#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE + + +#define LED0 PC14 +#define BEEPER PC15 +#define BEEPER_INVERTED + +#define USABLE_TIMER_CHANNEL_COUNT 17 + + + +#define USE_MAG_DATA_READY_SIGNAL +#define ENSURE_MAG_DATA_READY_IS_HIGH + +#define MPU6000_CS_PIN PA15 +#define MPU6000_SPI_INSTANCE SPI1 + + +#define GYRO +#define USE_GYRO_SPI_MPU6000 +#define GYRO_MPU6000_ALIGN CW270_DEG + +#define ACC +#define USE_ACC_SPI_MPU6000 +#define ACC_MPU6000_ALIGN CW270_DEG + +// MPU6000 interrupts +#define USE_MPU_DATA_READY_SIGNAL +#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready (mag disabled) +#define MPU_INT_EXTI PC13 +#define USE_EXTI + + +#define USE_FLASHFS +#define USE_FLASH_M25P16 + +#define USE_USART1 +#define USE_USART2 +#define USE_USART3 +#define USE_SOFTSERIAL1 +#define USE_SOFTSERIAL2 +#define SERIAL_PORT_COUNT 5 + +#ifndef UART1_GPIO +#define UART1_TX_PIN GPIO_Pin_9 // PA9 +#define UART1_RX_PIN GPIO_Pin_10 // PA10 +#define UART1_GPIO GPIOA +#define UART1_GPIO_AF GPIO_AF_7 +#define UART1_TX_PINSOURCE GPIO_PinSource9 +#define UART1_RX_PINSOURCE GPIO_PinSource10 +#endif + +#define UART2_TX_PIN GPIO_Pin_2 // PA14 / SWCLK +#define UART2_RX_PIN GPIO_Pin_3 // PA15 +#define UART2_GPIO GPIOA +#define UART2_GPIO_AF GPIO_AF_7 +#define UART2_TX_PINSOURCE GPIO_PinSource2 +#define UART2_RX_PINSOURCE GPIO_PinSource3 + +#ifndef UART3_GPIO +#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) +#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) +#define UART3_GPIO_AF GPIO_AF_7 +#define UART3_GPIO GPIOB +#define UART3_TX_PINSOURCE GPIO_PinSource10 +#define UART3_RX_PINSOURCE GPIO_PinSource11 +#endif + +#define SOFTSERIAL_1_TIMER TIM3 +#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 +#define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6 +#define SOFTSERIAL_2_TIMER TIM3 +#define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7 +#define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8 + + +#define USE_I2C +#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 +//GPIO_AF_1 + +#define SPI1_NSS_PIN PA15 +#define SPI1_SCK_PIN PB3 +#define SPI1_MISO_PIN PB4 +#define SPI1_MOSI_PIN PB5 + +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define M25P16_CS_PIN PB12 +#define M25P16_SPI_INSTANCE SPI2 + +#define USE_ADC +#define BOARD_HAS_VOLTAGE_DIVIDER +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 + +#define LED_STRIP +#define LED_STRIP_TIMER TIM1 + +#define USE_LED_STRIP_ON_DMA1_CHANNEL2 +#define WS2811_GPIO GPIOA +#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA +#define WS2811_GPIO_AF GPIO_AF_6 +#define WS2811_PIN GPIO_Pin_8 +#define WS2811_PIN_SOURCE GPIO_PinSource8 +#define WS2811_TIMER TIM1 +#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1 +#define WS2811_DMA_CHANNEL DMA1_Channel2 +#define WS2811_IRQ DMA1_Channel2_IRQn +#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 +#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES FEATURE_BLACKBOX + +#define SPEKTRUM_BIND +// USART3, +#define BIND_PIN PB11 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +// IO - stm32f303cc in 48pin package +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) + +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) ) + + diff --git a/src/main/target/X_RACERSPI/target.mk b/src/main/target/X_RACERSPI/target.mk new file mode 100644 index 0000000000..c0c219bd30 --- /dev/null +++ b/src/main/target/X_RACERSPI/target.mk @@ -0,0 +1,16 @@ +F3_TARGETS += $(TARGET) +FEATURES = ONBOARDFLASH +TARGET_FLAGS = -DSPRACINGF3 + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_spi_mpu6000.c \ + drivers/compass_ak8975.c \ + drivers/compass_hmc5883l.c \ + drivers/display_ug2864hsweg01.h \ + drivers/flash_m25p16.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/serial_softserial.c \ + drivers/sonar_hcsr04.c + diff --git a/src/main/target/ZCOREF3/target.c b/src/main/target/ZCOREF3/target.c new file mode 100644 index 0000000000..e3b40ee630 --- /dev/null +++ b/src/main/target/ZCOREF3/target.c @@ -0,0 +1,104 @@ + +#include +#include + +#include +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" + +const uint16_t multiPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM15 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM16 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + 0xFFFF +}; + +const uint16_t multiPWM[] = { + PWM1 | (MAP_TO_PWM_INPUT << 8), + PWM2 | (MAP_TO_PWM_INPUT << 8), + PWM3 | (MAP_TO_PWM_INPUT << 8), + PWM4 | (MAP_TO_PWM_INPUT << 8), + PWM5 | (MAP_TO_PWM_INPUT << 8), + PWM6 | (MAP_TO_PWM_INPUT << 8), + PWM7 | (MAP_TO_PWM_INPUT << 8), + PWM8 | (MAP_TO_PWM_INPUT << 8), + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM15 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM16 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +const uint16_t airPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 + PWM12 | (MAP_TO_SERVO_OUTPUT << 8), + PWM13 | (MAP_TO_SERVO_OUTPUT << 8), + PWM14 | (MAP_TO_SERVO_OUTPUT << 8), + PWM15 | (MAP_TO_SERVO_OUTPUT << 8), + PWM16 | (MAP_TO_SERVO_OUTPUT << 8), + PWM5 | (MAP_TO_SERVO_OUTPUT << 8), + PWM6 | (MAP_TO_SERVO_OUTPUT << 8), + PWM7 | (MAP_TO_SERVO_OUTPUT << 8), + PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #10 + 0xFFFF +}; + +const uint16_t airPWM[] = { + PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1 + PWM2 | (MAP_TO_PWM_INPUT << 8), + PWM3 | (MAP_TO_PWM_INPUT << 8), + PWM4 | (MAP_TO_PWM_INPUT << 8), + PWM5 | (MAP_TO_PWM_INPUT << 8), + PWM6 | (MAP_TO_PWM_INPUT << 8), + PWM7 | (MAP_TO_PWM_INPUT << 8), + PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8 + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 + PWM12 | (MAP_TO_SERVO_OUTPUT << 8), + PWM13 | (MAP_TO_SERVO_OUTPUT << 8), + PWM14 | (MAP_TO_SERVO_OUTPUT << 8), + PWM15 | (MAP_TO_SERVO_OUTPUT << 8), + PWM16 | (MAP_TO_SERVO_OUTPUT << 8), // server #6 + 0xFFFF +}; + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH1 - PA0 - *TIM2_CH1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH5 - PB4 - *TIM3_CH1 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH6 - PB5 - *TIM3_CH2 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM3 - PA11 + { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM4 - PA12 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM8 - PA3 + + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP +}; + diff --git a/src/main/target/ZCOREF3/target.h b/src/main/target/ZCOREF3/target.h new file mode 100644 index 0000000000..c02b4d3ecb --- /dev/null +++ b/src/main/target/ZCOREF3/target.h @@ -0,0 +1,126 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "ZCF3" + +#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT + +#define LED0 PB8 + +#define BEEPER PC15 +#define BEEPER_INVERTED + +#define EXTI15_10_CALLBACK_HANDLER_COUNT 1 + +#define USE_EXTI +#define MPU_INT_EXTI PC13 +#define USE_MPU_DATA_READY_SIGNAL +#define ENSURE_MPU_DATA_READY_IS_LOW + +#define USE_MAG_DATA_READY_SIGNAL +#define ENSURE_MAG_DATA_READY_IS_HIGH + + +#define GYRO +#define USE_GYRO_MPU6500 +#define USE_GYRO_SPI_MPU6500 + +#define ACC +#define USE_ACC_MPU6500 +#define USE_ACC_SPI_MPU6500 + +#define ACC_MPU6500_ALIGN CW180_DEG +#define GYRO_MPU6500_ALIGN CW180_DEG + +#define BARO +#define USE_BARO_BMP280 + +#define USE_USART1 +#define USE_USART2 +#define USE_USART3 +#define SERIAL_PORT_COUNT 3 + +#ifndef UART1_GPIO +#define UART1_TX_PIN GPIO_Pin_9 // PA9 +#define UART1_RX_PIN GPIO_Pin_10 // PA10 +#define UART1_GPIO GPIOA +#define UART1_GPIO_AF GPIO_AF_7 +#define UART1_TX_PINSOURCE GPIO_PinSource9 +#define UART1_RX_PINSOURCE GPIO_PinSource10 +#endif + +#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK +#define UART2_RX_PIN GPIO_Pin_15 // PA15 +#define UART2_GPIO GPIOA +#define UART2_GPIO_AF GPIO_AF_7 +#define UART2_TX_PINSOURCE GPIO_PinSource14 +#define UART2_RX_PINSOURCE GPIO_PinSource15 + +#ifndef UART3_GPIO +#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) +#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) +#define UART3_GPIO_AF GPIO_AF_7 +#define UART3_GPIO GPIOB +#define UART3_TX_PINSOURCE GPIO_PinSource10 +#define UART3_RX_PINSOURCE GPIO_PinSource11 +#endif + +#define USE_I2C +#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA + +#define USE_SPI +#define USE_SPI_DEVICE_1 // PB9,3,4,5 on AF5 SPI1 (MPU) +#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 SPI2 (SDCard) + +#define SPI1_NSS_PIN PB9 +#define SPI1_SCK_PIN PB3 +#define SPI1_MISO_PIN PB4 +#define SPI1_MOSI_PIN PB5 + +#define MPU6500_CS_PIN PB9 +#define MPU6500_SPI_INSTANCE SPI1 + +#define USE_FLASHFS +#define USE_FLASH_M25P16 + +#define M25P16_CS_PIN PB12 +#define M25P16_SPI_INSTANCE SPI2 + +#define USE_ADC +#define BOARD_HAS_VOLTAGE_DIVIDER +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 + +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY) + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +// IO - stm32f303cc in 48pin package +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) + +#define USABLE_TIMER_CHANNEL_COUNT 17 // PPM, 8 PWM, UART3 RX/TX, LED Strip + +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) ) + diff --git a/src/main/target/ZCOREF3/target.mk b/src/main/target/ZCOREF3/target.mk new file mode 100644 index 0000000000..4b232a7870 --- /dev/null +++ b/src/main/target/ZCOREF3/target.mk @@ -0,0 +1,11 @@ +F3_TARGETS += $(TARGET) +FEATURES = ONBOARDFLASH + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6500.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/barometer_bmp280.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c + diff --git a/src/main/target/common.h b/src/main/target/common.h index a9d961e4da..dbe2c3a374 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -17,12 +17,23 @@ #pragma once +#define I2C1_OVERCLOCK true +#define I2C2_OVERCLOCK true + + +/* STM32F4 specific settings that apply to all F4 targets */ #ifdef STM32F4 + #define TASK_GYROPID_DESIRED_PERIOD 125 #define SCHEDULER_DELAY_LIMIT 10 -#else +#define USE_SLOW_SERIAL_CLI +#define I2C3_OVERCLOCK true + +#else /* when not an F4 */ + #define TASK_GYROPID_DESIRED_PERIOD 1000 #define SCHEDULER_DELAY_LIMIT 100 + #endif #define SERIAL_RX diff --git a/src/main/vcpf4/usbd_cdc_vcp.c b/src/main/vcpf4/usbd_cdc_vcp.c index 32258c4d9e..93ac1aaa5c 100644 --- a/src/main/vcpf4/usbd_cdc_vcp.c +++ b/src/main/vcpf4/usbd_cdc_vcp.c @@ -65,8 +65,8 @@ CDC_IF_Prop_TypeDef VCP_fops = {VCP_Init, VCP_DeInit, VCP_Ctrl, VCP_DataTx, VCP_ */ static uint16_t VCP_Init(void) { - bDeviceState = CONFIGURED; - return USBD_OK; + bDeviceState = CONFIGURED; + return USBD_OK; } /** @@ -77,8 +77,8 @@ static uint16_t VCP_Init(void) */ static uint16_t VCP_DeInit(void) { - bDeviceState = UNCONNECTED; - return USBD_OK; + bDeviceState = UNCONNECTED; + return USBD_OK; } void ust_cpy(LINE_CODING* plc2, const LINE_CODING* plc1) @@ -99,12 +99,12 @@ void ust_cpy(LINE_CODING* plc2, const LINE_CODING* plc1) */ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len) { - (void)Len; - LINE_CODING* plc = (LINE_CODING*)Buf; + (void)Len; + LINE_CODING* plc = (LINE_CODING*)Buf; - assert_param(Len>=sizeof(LINE_CODING)); + assert_param(Len>=sizeof(LINE_CODING)); - switch (Cmd) { + switch (Cmd) { /* Not needed for this driver, AT modem commands */ case SEND_ENCAPSULATED_COMMAND: case GET_ENCAPSULATED_RESPONSE: @@ -139,9 +139,9 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len) default: break; - } + } - return USBD_OK; + return USBD_OK; } /******************************************************************************* @@ -153,12 +153,11 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len) *******************************************************************************/ uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength) { - if(USB_Tx_State!=1) - { - VCP_DataTx(ptrBuffer,sendLength); - return sendLength; - } - return 0; + if (USB_Tx_State) + return 0; + + VCP_DataTx(ptrBuffer, sendLength); + return sendLength; } /** @@ -171,20 +170,19 @@ uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength) */ static uint16_t VCP_DataTx(uint8_t* Buf, uint32_t Len) { - uint16_t ptr = APP_Rx_ptr_in; uint32_t i; for (i = 0; i < Len; i++) - APP_Rx_Buffer[ptr++ & (APP_RX_DATA_SIZE-1)] = Buf[i]; + APP_Rx_Buffer[ptr++ & (APP_RX_DATA_SIZE-1)] = Buf[i]; APP_Rx_ptr_in = ptr % APP_RX_DATA_SIZE; - + return USBD_OK; } - -uint8_t usbAvailable(void) { +uint8_t usbAvailable(void) +{ return (usbData.rxBufHead != usbData.rxBufTail); } @@ -197,13 +195,12 @@ uint8_t usbAvailable(void) { *******************************************************************************/ uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len) { - (void)len; - uint8_t ch = 0; + uint32_t ch = 0; - if (usbAvailable()) { - recvBuf[0] = usbData.rxBuf[usbData.rxBufTail]; - usbData.rxBufTail = (usbData.rxBufTail + 1) % USB_RX_BUFSIZE; - ch=1; + while (usbAvailable() && ch < len) { + recvBuf[ch] = usbData.rxBuf[usbData.rxBufTail]; + usbData.rxBufTail = (usbData.rxBufTail + 1) % USB_RX_BUFSIZE; + ch++; receiveLength--; } return ch; @@ -231,13 +228,17 @@ static uint16_t VCP_DataRx(uint8_t* Buf, uint32_t Len) uint32_t i; for (i = 0; i < Len; i++) - usbData.rxBuf[ptr++ & (USB_RX_BUFSIZE-1)] = Buf[i]; + usbData.rxBuf[ptr++ & (USB_RX_BUFSIZE-1)] = Buf[i]; usbData.rxBufHead = ptr % USB_RX_BUFSIZE; - receiveLength = ((usbData.rxBufHead - usbData.rxBufTail)>0?(usbData.rxBufHead - usbData.rxBufTail):(usbData.rxBufHead + USB_RX_BUFSIZE - usbData.rxBufTail)) % USB_RX_BUFSIZE; - if((receiveLength) > (USB_RX_BUFSIZE-1)) - return USBD_FAIL; + receiveLength = ((usbData.rxBufHead - usbData.rxBufTail) > 0 ? + (usbData.rxBufHead - usbData.rxBufTail) : + (usbData.rxBufHead + USB_RX_BUFSIZE - usbData.rxBufTail)) % USB_RX_BUFSIZE; + + if(receiveLength > (USB_RX_BUFSIZE-1)) + return USBD_FAIL; + return USBD_OK; } @@ -274,7 +275,7 @@ uint8_t usbIsConnected(void) *******************************************************************************/ uint32_t CDC_BaudRate(void) { - return g_lc.bitrate; + return g_lc.bitrate; } /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/