diff --git a/RTC/Core/Inc/main.h b/RTC/Core/Inc/main.h
index 63489cf..f033501 100644
--- a/RTC/Core/Inc/main.h
+++ b/RTC/Core/Inc/main.h
@@ -70,14 +70,14 @@ void Error_Handler(void);
#define USART_TX_GPIO_Port GPIOA
#define USART_RX_Pin GPIO_PIN_3
#define USART_RX_GPIO_Port GPIOA
-//#define LD2_Pin GPIO_PIN_5
-//#define LD2_GPIO_Port GPIOA
+#define LD2_Pin GPIO_PIN_5
+#define LD2_GPIO_Port GPIOA
#define TMS_Pin GPIO_PIN_13
#define TMS_GPIO_Port GPIOA
#define TCK_Pin GPIO_PIN_14
#define TCK_GPIO_Port GPIOA
-//#define SWO_Pin GPIO_PIN_3
-//#define SWO_GPIO_Port GPIOB
+#define SWO_Pin GPIO_PIN_3
+#define SWO_GPIO_Port GPIOB
/* USER CODE BEGIN Private defines */
/* USER CODE END Private defines */
diff --git a/RTC/Core/Inc/stm32f4xx_hal_conf.h b/RTC/Core/Inc/stm32f4xx_hal_conf.h
index f5aa67c..e5fa2c6 100644
--- a/RTC/Core/Inc/stm32f4xx_hal_conf.h
+++ b/RTC/Core/Inc/stm32f4xx_hal_conf.h
@@ -36,7 +36,7 @@
*/
#define HAL_MODULE_ENABLED
- /* #define HAL_ADC_MODULE_ENABLED */
+#define HAL_ADC_MODULE_ENABLED */
/* #define HAL_CRYP_MODULE_ENABLED */
/* #define HAL_CAN_MODULE_ENABLED */
/* #define HAL_CRC_MODULE_ENABLED */
@@ -61,7 +61,7 @@
/* #define HAL_SAI_MODULE_ENABLED */
/* #define HAL_SD_MODULE_ENABLED */
/* #define HAL_MMC_MODULE_ENABLED */
-/* #define HAL_SPI_MODULE_ENABLED */
+#define HAL_SPI_MODULE_ENABLED */
#define HAL_TIM_MODULE_ENABLED
#define HAL_UART_MODULE_ENABLED
/* #define HAL_USART_MODULE_ENABLED */
diff --git a/RTC/Core/Inc/stm32f4xx_it.h b/RTC/Core/Inc/stm32f4xx_it.h
index 99e5a03..daccc11 100644
--- a/RTC/Core/Inc/stm32f4xx_it.h
+++ b/RTC/Core/Inc/stm32f4xx_it.h
@@ -57,6 +57,9 @@ void DebugMon_Handler(void);
void PendSV_Handler(void);
void SysTick_Handler(void);
void RTC_Alarm_IRQHandler(void);
+
+void EXTI15_10_IRQHandler(void);
+void TIM4_IRQHandler(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
diff --git a/RTC/Core/Src/stm32f4xx_hal_msp.c b/RTC/Core/Src/stm32f4xx_hal_msp.c
index 43274eb..68b3ca9 100644
--- a/RTC/Core/Src/stm32f4xx_hal_msp.c
+++ b/RTC/Core/Src/stm32f4xx_hal_msp.c
@@ -47,7 +47,9 @@
/* Private function prototypes -----------------------------------------------*/
/* USER CODE BEGIN PFP */
-
+extern void BSP_MotorControl_StepClockHandler(uint8_t deviceId);
+extern void BSP_MotorControl_FlagInterruptHandler(void);
+extern void ButtonHandler(void);
/* USER CODE END PFP */
/* External functions --------------------------------------------------------*/
@@ -194,6 +196,115 @@ void HAL_UART_MspDeInit(UART_HandleTypeDef* huart)
}
+/**
+ * @brief PWM MSP Initialization
+ * @param[in] htim_pwm PWM handle pointer
+ * @retval None
+ */
+void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef* htim_pwm)
+{
+ GPIO_InitTypeDef GPIO_InitStruct;
+ if(htim_pwm->Instance == BSP_MOTOR_CONTROL_BOARD_TIMER_TICK)
+ {
+ /* Peripheral clock enable */
+ __BSP_MOTOR_CONTROL_BOARD_TIMER_TICK_CLCK_ENABLE();
+
+ /* Set Interrupt Group Priority of Timer Interrupt*/
+ HAL_NVIC_SetPriority(BSP_MOTOR_CONTROL_BOARD_TIMER_TICK_IRQn, BSP_MOTOR_CONTROL_BOARD_TIMER_TICK_PRIORITY, 0);
+
+ /* Enable the timer global Interrupt */
+ HAL_NVIC_EnableIRQ(BSP_MOTOR_CONTROL_BOARD_TIMER_TICK_IRQn);
+ }
+ if(htim_pwm->Instance == BSP_MOTOR_CONTROL_BOARD_TIMER_VREFA_PWM)
+ {
+ /* Peripheral clock enable */
+ __BSP_MOTOR_CONTROL_BOARD_TIMER_VREFA_PWM_CLCK_ENABLE();
+
+ /* Configure L6208 - VREFA pin -------------------------------------*/
+ GPIO_InitStruct.Pin = BSP_MOTOR_CONTROL_BOARD_VREFA_PIN;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_MEDIUM;
+ GPIO_InitStruct.Alternate = BSP_MOTOR_CONTROL_BOARD_AFx_TIMx_VREFA_PWM;
+ HAL_GPIO_Init(BSP_MOTOR_CONTROL_BOARD_VREFA_PORT, &GPIO_InitStruct);
+ }
+ if(htim_pwm->Instance == BSP_MOTOR_CONTROL_BOARD_TIMER_VREFB_PWM)
+ {
+ /* Peripheral clock enable */
+ __BSP_MOTOR_CONTROL_BOARD_TIMER_VREFB_PWM_CLCK_ENABLE();
+
+ /* Configure L6208 - VREFB pin -------------------------------------*/
+ GPIO_InitStruct.Pin = BSP_MOTOR_CONTROL_BOARD_VREFB_PIN;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_MEDIUM;
+ GPIO_InitStruct.Alternate = BSP_MOTOR_CONTROL_BOARD_AFx_TIMx_VREFB_PWM;
+ HAL_GPIO_Init(BSP_MOTOR_CONTROL_BOARD_VREFB_PORT, &GPIO_InitStruct);
+ }
+}
+
+/**
+ * @brief PWM MSP De-Initialization
+ * @param[in] htim_pwm PWM handle pointer
+ * @retval None
+ */
+void HAL_TIM_PWM_MspDeInit(TIM_HandleTypeDef* htim_pwm)
+{
+ if(htim_pwm->Instance == BSP_MOTOR_CONTROL_BOARD_TIMER_TICK)
+ {
+ /* Peripheral clock disable */
+ __BSP_MOTOR_CONTROL_BOARD_TIMER_TICK_CLCK_DISABLE();
+ }
+ if(htim_pwm->Instance == BSP_MOTOR_CONTROL_BOARD_TIMER_VREFA_PWM)
+ {
+ /* Peripheral clock disable */
+ __BSP_MOTOR_CONTROL_BOARD_TIMER_VREFA_PWM_CLCK_DISABLE();
+ /* GPIO Deconfiguration */
+ HAL_GPIO_DeInit(BSP_MOTOR_CONTROL_BOARD_VREFA_PORT, BSP_MOTOR_CONTROL_BOARD_VREFA_PIN);
+ }
+ if(htim_pwm->Instance == BSP_MOTOR_CONTROL_BOARD_TIMER_VREFB_PWM)
+ {
+ /* Peripheral clock enable */
+ __BSP_MOTOR_CONTROL_BOARD_TIMER_VREFB_PWM_CLCK_DISABLE();
+ /* GPIO Deconfiguration */
+ HAL_GPIO_DeInit(BSP_MOTOR_CONTROL_BOARD_VREFB_PORT, BSP_MOTOR_CONTROL_BOARD_VREFB_PIN);
+ }
+}
+
+/**
+ * @brief PWM Callback
+ * @param[in] htim PWM handle pointer
+ * @retval None
+ */
+void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim)
+{
+ if ((htim->Instance == BSP_MOTOR_CONTROL_BOARD_TIMER_TICK)&& (htim->Channel == BSP_MOTOR_CONTROL_BOARD_HAL_ACT_CHAN_TIMER_TICK))
+ {
+ if (BSP_MotorControl_GetDeviceState(0) != INACTIVE)
+ {
+ BSP_MotorControl_StepClockHandler(0);
+ }
+ }
+}
+
+/**
+ * @brief External Line Callback
+ * @param[in] GPIO_Pin pin number
+ * @retval None
+ */
+void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin)
+{
+ if (GPIO_Pin == BSP_MOTOR_CONTROL_BOARD_EN_AND_FLAG_PIN)
+ {
+ BSP_MotorControl_FlagInterruptHandler();
+ }
+ if (GPIO_Pin == KEY_BUTTON_PIN)
+ {
+ ButtonHandler();
+ }
+ }
+
+
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */
diff --git a/RTC/Core/Src/stm32f4xx_it.c b/RTC/Core/Src/stm32f4xx_it.c
index 3cafd82..b2f28f7 100644
--- a/RTC/Core/Src/stm32f4xx_it.c
+++ b/RTC/Core/Src/stm32f4xx_it.c
@@ -57,6 +57,7 @@
/* External variables --------------------------------------------------------*/
extern RTC_HandleTypeDef hrtc;
+extern TIM_HandleTypeDef hTimTick;
/* USER CODE BEGIN EV */
/* USER CODE END EV */
@@ -213,6 +214,27 @@ void RTC_Alarm_IRQHandler(void)
/* USER CODE END RTC_Alarm_IRQn 1 */
}
+/**
+ * @brief This function handles interrupt for External lines 10 to 15
+ * @param None
+ * @retval None
+ */
+void EXTI15_10_IRQHandler(void)
+{
+ HAL_GPIO_EXTI_IRQHandler(BSP_MOTOR_CONTROL_BOARD_EN_AND_FLAG_PIN);
+ HAL_GPIO_EXTI_IRQHandler(KEY_BUTTON_PIN);
+}
+
+/**
+ * @brief This function handles TIM4 interrupt request.
+ * @param None
+ * @retval None
+ */
+void TIM4_IRQHandler(void)
+{
+ HAL_TIM_IRQHandler(&hTimTick);
+}
+
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */
diff --git a/RTC/Core/Startup/startup_stm32f401retx.s b/RTC/Core/Startup/startup_stm32f401retx.s
new file mode 100644
index 0000000..cc9a847
--- /dev/null
+++ b/RTC/Core/Startup/startup_stm32f401retx.s
@@ -0,0 +1,432 @@
+/**
+ ******************************************************************************
+ * @file startup_stm32f401xe.s
+ * @author MCD Application Team
+ * @brief STM32F401xExx Devices vector table for GCC based toolchains.
+ * 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 (c) 2017 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under BSD 3-Clause license,
+ * the "License"; You may not use this file except in compliance with the
+ * License. You may obtain a copy of the License at:
+ * opensource.org/licenses/BSD-3-Clause
+ *
+ ******************************************************************************
+ */
+
+ .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 */
+
+/*******************************************************************************
+*
+* 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****/
+