aboutsummaryrefslogtreecommitdiff
path: root/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src
diff options
context:
space:
mode:
Diffstat (limited to 'thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src')
-rw-r--r--thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/hw_config.c406
-rw-r--r--thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/main.c118
-rw-r--r--thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/nor_if.c114
-rw-r--r--thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/stm32_it.c246
-rw-r--r--thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/system_stm32f10x.c917
-rw-r--r--thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/system_stm32l1xx.c533
-rw-r--r--thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/usb_istr.c231
7 files changed, 2565 insertions, 0 deletions
diff --git a/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/hw_config.c b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/hw_config.c
new file mode 100644
index 0000000..a2098f9
--- /dev/null
+++ b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/hw_config.c
@@ -0,0 +1,406 @@
+/**
+ ******************************************************************************
+ * @file hw_config.c
+ * @author MCD Application Team
+ * @version V4.0.0
+ * @date 21-January-2013
+ * @brief Hardware Configuration & Setup
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+ *
+ * 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 "hw_config.h"
+#include "dfu_mal.h"
+#include "usb_lib.h"
+#include "usb_desc.h"
+#include "usb_pwr.h"
+
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+ErrorStatus HSEStartUpStatus;
+EXTI_InitTypeDef EXTI_InitStructure;
+/* Extern variables ----------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+static void IntToUnicode (uint32_t value , uint8_t *pbuf , uint8_t len);
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : Set_System.
+* Description : Configures Main system clocks & power.
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void Set_System(void)
+{
+#if !defined(STM32L1XX_MD) && !defined(STM32L1XX_HD) && !defined (STM32L1XX_MD_PLUS)
+ GPIO_InitTypeDef GPIO_InitStructure;
+#endif /* STM32L1XX_XD*/
+
+#if defined(USB_USE_EXTERNAL_PULLUP)
+ GPIO_InitTypeDef GPIO_InitStructure;
+#endif /* USB_USE_EXTERNAL_PULLUP */
+
+ /*!< At this stage the microcontroller clock setting is already configured,
+ this is done through SystemInit() function which is called from startup
+ file (startup_stm32f10x_xx.s) before to branch to application main.
+ To reconfigure the default setting of SystemInit() function, refer to
+ system_stm32f10x.c file
+ */
+
+#if defined(STM32L1XX_MD) || defined(STM32L1XX_HD)|| defined(STM32L1XX_MD_PLUS) || defined(STM32F37X) || defined(STM32F30X)
+ /* Enable the SYSCFG module clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
+#endif /* STM32L1XX_XD */
+
+FLASH_Unlock();
+
+#ifdef USE_STM3210E_EVAL
+ /* Enable the FSMC Clock */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_FSMC, ENABLE);
+#endif /* USE_STM3210E_EVAL */
+#if defined (USE_STM3210E_EVAL)
+ /* Enable the FSMC Clock */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_FSMC, ENABLE);
+#endif /* USE_STM3210E_EVAL */
+
+#if defined(STM32F37X) || defined(STM32F30X)
+ /* Enable the USB disconnect GPIO clock */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIO_DISCONNECT, ENABLE);
+
+ /*Set PA11,12 as IN - USB_DM,DP*/
+
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOA, ENABLE);
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11 | GPIO_Pin_12;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
+ GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+ GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /*SET PA11,12 for USB: USB_DM,DP*/
+ GPIO_PinAFConfig(GPIOA, GPIO_PinSource11, GPIO_AF_14);
+ GPIO_PinAFConfig(GPIOA, GPIO_PinSource12, GPIO_AF_14);
+
+ /* USB_DISCONNECT used as USB pull-up */
+ GPIO_InitStructure.GPIO_Pin = USB_DISCONNECT_PIN;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
+ GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
+ GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
+ GPIO_Init(USB_DISCONNECT, &GPIO_InitStructure);
+
+ /*Output low level on USB_Disconnect Pin to enable 1.5k ohm pull-up resistor*/
+ GPIO_WriteBit(USB_DISCONNECT, USB_DISCONNECT_PIN, Bit_RESET);
+
+#endif /* STM32F37X && STM32F30X */
+
+#if !defined(STM32L1XX_MD) && !defined(STM32L1XX_HD) && !defined(STM32L1XX_MD_PLUS) && !defined(STM32F37X) && !defined(STM32F30X)
+ /* Enable "DISCONNECT" GPIO clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIO_DISCONNECT, ENABLE);
+
+ /* Configure USB pull-up */
+ GPIO_InitStructure.GPIO_Pin = USB_DISCONNECT_PIN;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_OD;
+ GPIO_Init(USB_DISCONNECT, &GPIO_InitStructure);
+
+ /* Disable the USB connection till initialization phase end */
+ USB_Cable_Config(DISABLE);
+#endif /* STM32L1XX_XD */
+
+#if defined(USB_USE_EXTERNAL_PULLUP)
+ /* Enable the USB disconnect GPIO clock */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIO_DISCONNECT, ENABLE);
+
+ /* USB_DISCONNECT used as USB pull-up */
+ GPIO_InitStructure.GPIO_Pin = USB_DISCONNECT_PIN;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
+ GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+ GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
+ GPIO_Init(USB_DISCONNECT, &GPIO_InitStructure);
+#endif /* USB_USE_EXTERNAL_PULLUP */
+
+ /* Init the media interface */
+ MAL_Init();
+ USB_Cable_Config(ENABLE);
+
+ /* Configure the EXTI line 18 connected internally to the USB IP */
+ EXTI_ClearITPendingBit(EXTI_Line18);
+ EXTI_InitStructure.EXTI_Line = EXTI_Line18;
+ EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
+ EXTI_InitStructure.EXTI_LineCmd = ENABLE;
+ EXTI_Init(&EXTI_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : Set_USBClock.
+* Description : Configures USB Clock input (48MHz).
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void Set_USBClock(void)
+{
+#if defined(STM32L1XX_MD) || defined(STM32L1XX_HD)|| defined(STM32L1XX_MD_PLUS)
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_USB, ENABLE);
+
+#else
+ /* Select USBCLK source */
+ RCC_USBCLKConfig(RCC_USBCLKSource_PLLCLK_1Div5);
+
+ /* Enable the USB clock */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_USB, ENABLE);
+#endif /* STM32L1XX_MD */
+}
+
+/*******************************************************************************
+* Function Name : Enter_LowPowerMode.
+* Description : Power-off system clocks and power while entering suspend mode.
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void Enter_LowPowerMode(void)
+{
+ /* Set the device state to suspend */
+ bDeviceState = SUSPENDED;
+}
+
+/*******************************************************************************
+* Function Name : Leave_LowPowerMode.
+* Description : Restores system clocks and power while exiting suspend mode.
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void Leave_LowPowerMode(void)
+{
+ DEVICE_INFO *pInfo = &Device_Info;
+
+ /* Set the device state to the correct state */
+ if (pInfo->Current_Configuration != 0)
+ {
+ /* Device configured */
+ bDeviceState = CONFIGURED;
+ }
+ else
+ {
+ bDeviceState = ATTACHED;
+ }
+ /*Enable SystemCoreClock*/
+ SystemInit();
+}
+
+/*******************************************************************************
+* Function Name : USB_Cable_Config.
+* Description : Software Connection/Disconnection of USB Cable.
+* Input : NewState: new state.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void USB_Cable_Config (FunctionalState NewState)
+{
+#if defined(STM32L1XX_MD) || defined(STM32L1XX_HD)|| defined(STM32L1XX_MD_PLUS)
+ if (NewState != DISABLE)
+ {
+ STM32L15_USB_CONNECT;
+ }
+ else
+ {
+ STM32L15_USB_DISCONNECT;
+ }
+#else
+ if (NewState != DISABLE)
+ {
+ GPIO_ResetBits(USB_DISCONNECT, USB_DISCONNECT_PIN);
+ }
+ else
+ {
+ GPIO_SetBits(USB_DISCONNECT, USB_DISCONNECT_PIN);
+ }
+#endif /* STM32L1XX_XD */
+}
+
+/*******************************************************************************
+* Function Name : DFU_Button_Config.
+* Description : Configures the DFU selector Button to enter DFU Mode.
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void DFU_Button_Config(void)
+{
+#if defined (USE_STM32L152_EVAL)
+ /* Configure "DFU enter" button */
+ STM_EVAL_PBInit(Button_UP, Mode_GPIO);
+#else
+ /* Configure "DFU enter" button */
+ STM_EVAL_PBInit(Button_KEY, Mode_GPIO);
+#endif /* USE_STM32L152_EVAL */
+}
+
+/*******************************************************************************
+* Function Name : DFU_Button_Read.
+* Description : Reads the DFU selector Button to enter DFU Mode.
+* Input : None.
+* Output : None.
+* Return : Status
+*******************************************************************************/
+uint8_t DFU_Button_Read (void)
+{
+#if defined (USE_STM32L152_EVAL)
+ return STM_EVAL_PBGetState(Button_UP);
+#elif defined (USE_STM32L152D_EVAL)
+ return !STM_EVAL_PBGetState(Button_KEY);
+#else
+ return STM_EVAL_PBGetState(Button_KEY);
+#endif /* USE_STM32L152_EVAL */
+}
+
+/*******************************************************************************
+* Function Name : USB_Interrupts_Config.
+* Description : Configures the USB interrupts.
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void USB_Interrupts_Config(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+ /* 2 bit for pre-emption priority, 2 bits for subpriority */
+ NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
+
+#if defined(STM32L1XX_MD) || defined(STM32L1XX_HD)|| defined(STM32L1XX_MD_PLUS)
+ NVIC_InitStructure.NVIC_IRQChannel = USB_LP_IRQn;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+ /* Enable the USB Wake-up interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = USB_FS_WKUP_IRQn;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+#elif defined(STM32F37X)
+ /* Enable the USB interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = USB_LP_IRQn;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+ /* Enable the USB Wake-up interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = USBWakeUp_IRQn;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+#else
+ /* Enable the USB interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+ /* Enable the USB Wake-up interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = USBWakeUp_IRQn;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+#endif /* STM32L1XX_XD */
+}
+
+/*******************************************************************************
+* Function Name : Reset_Device.
+* Description : Reset the device.
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void Reset_Device(void)
+{
+ USB_Cable_Config(DISABLE);
+ NVIC_SystemReset();
+}
+
+/*******************************************************************************
+* Function Name : Get_SerialNum.
+* Description : Create the serial number string descriptor.
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void Get_SerialNum(void)
+{
+ uint32_t Device_Serial0, Device_Serial1, Device_Serial2;
+
+ Device_Serial0 = *(uint32_t*)ID1;
+ Device_Serial1 = *(uint32_t*)ID2;
+ Device_Serial2 = *(uint32_t*)ID3;
+
+ Device_Serial0 += Device_Serial2;
+
+ if (Device_Serial0 != 0)
+ {
+ IntToUnicode (Device_Serial0, &DFU_StringSerial[2] , 8);
+ IntToUnicode (Device_Serial1, &DFU_StringSerial[18], 4);
+ }
+}
+
+/*******************************************************************************
+* Function Name : HexToChar.
+* Description : Convert Hex 32Bits value into char.
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+static void IntToUnicode (uint32_t value , uint8_t *pbuf , uint8_t len)
+{
+ uint8_t idx = 0;
+
+ for( idx = 0 ; idx < len ; idx ++)
+ {
+ if( ((value >> 28)) < 0xA )
+ {
+ pbuf[ 2* idx] = (value >> 28) + '0';
+ }
+ else
+ {
+ pbuf[2* idx] = (value >> 28) + 'A' - 10;
+ }
+
+ value = value << 4;
+
+ pbuf[ 2* idx + 1] = 0;
+ }
+}
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/main.c b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/main.c
new file mode 100644
index 0000000..f4daeec
--- /dev/null
+++ b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/main.c
@@ -0,0 +1,118 @@
+/**
+ ******************************************************************************
+ * @file main.c
+ * @author MCD Application Team
+ * @version V4.0.0
+ * @date 21-January-2013
+ * @brief Device Firmware Upgrade(DFU) demo main file
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+ *
+ * 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 "hw_config.h"
+#include "usb_lib.h"
+#include "usb_conf.h"
+#include "usb_prop.h"
+#include "usb_pwr.h"
+#include "dfu_mal.h"
+
+/* Private typedef -----------------------------------------------------------*/
+typedef void (*pFunction)(void);
+
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Extern variables ----------------------------------------------------------*/
+uint8_t DeviceState;
+uint8_t DeviceStatus[6];
+pFunction Jump_To_Application;
+uint32_t JumpAddress;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main.
+* Description : main routine.
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+int main(void)
+{
+
+#if defined (USE_STM32L152D_EVAL)
+ FLASH_Unlock();
+ FLASH_ClearFlag(FLASH_FLAG_OPTVERRUSR);
+#endif
+ DFU_Button_Config();
+
+ /* Check if the Key push-button on STM3210x-EVAL Board is pressed */
+ if (DFU_Button_Read() != 0x00)
+ { /* Test if user code is programmed starting from address 0x8003000 */
+ if (((*(__IO uint32_t*)ApplicationAddress) & 0x2FFE0000 ) == 0x20000000)
+ { /* Jump to user application */
+
+ JumpAddress = *(__IO uint32_t*) (ApplicationAddress + 4);
+ Jump_To_Application = (pFunction) JumpAddress;
+ /* Initialize user application's Stack Pointer */
+ __set_MSP(*(__IO uint32_t*) ApplicationAddress);
+ Jump_To_Application();
+ }
+ } /* Otherwise enters DFU mode to allow user to program his application */
+
+ /* Enter DFU mode */
+ DeviceState = STATE_dfuERROR;
+ DeviceStatus[0] = STATUS_ERRFIRMWARE;
+ DeviceStatus[4] = DeviceState;
+
+ Set_System();
+ Set_USBClock();
+ USB_Init();
+
+ /* Main loop */
+ while (1)
+ {}
+}
+
+
+#ifdef USE_FULL_ASSERT
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(uint8_t* file, uint32_t line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {}
+}
+#endif
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/nor_if.c b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/nor_if.c
new file mode 100644
index 0000000..3b7f7a4
--- /dev/null
+++ b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/nor_if.c
@@ -0,0 +1,114 @@
+/**
+ ******************************************************************************
+ * @file nor_if.c
+ * @author MCD Application Team
+ * @version V4.0.0
+ * @date 21-January-2013
+ * @brief specific media access Layer for NOR flash
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+ *
+ * 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.
+ *
+ ******************************************************************************
+ */
+
+#include "platform_config.h"
+
+#ifdef USE_STM3210E_EVAL
+
+/* Includes ------------------------------------------------------------------*/
+#include "fsmc_nor.h"
+#include "nor_if.h"
+#include "dfu_mal.h"
+#include "stm32f10x_fsmc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+extern NOR_IDTypeDef NOR_ID;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NOR_If_Init
+* Description : Initializes the Media on the STM32
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+uint16_t NOR_If_Init(void)
+{
+ /* Configure FSMC Bank1 NOR/SRAM2 */
+ FSMC_NOR_Init();
+
+ /* Enable FSMC Bank1 NOR/SRAM2 */
+ FSMC_NORSRAMCmd(FSMC_Bank1_NORSRAM2, ENABLE);
+
+ return MAL_OK;
+}
+
+/*******************************************************************************
+* Function Name : NOR_If_Erase
+* Description : Erase sector
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+uint16_t NOR_If_Erase(uint32_t Address)
+{
+ /* Erase the destination memory */
+ FSMC_NOR_EraseBlock(Address & 0x00FFFFFF);
+
+ return MAL_OK;
+}
+
+/*******************************************************************************
+* Function Name : NOR_If_Write
+* Description : Write sectors
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+uint16_t NOR_If_Write(uint32_t Address, uint32_t DataLength)
+{
+ if ((DataLength & 1) == 1) /* Not an aligned data */
+ {
+ DataLength += 1;
+ MAL_Buffer[DataLength-1] = 0xFF;
+ }
+
+ FSMC_NOR_WriteBuffer((uint16_t *)MAL_Buffer, (Address&0x00FFFFFF), DataLength >> 1);
+
+ return MAL_OK;
+}
+
+/*******************************************************************************
+* Function Name : NOR_If_Read
+* Description : Read sectors
+* Input : None
+* Output : None
+* Return : buffer address pointer
+*******************************************************************************/
+uint8_t *NOR_If_Read(uint32_t Address, uint32_t DataLength)
+{
+ return (uint8_t*)(Address);
+}
+
+#endif
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/stm32_it.c b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/stm32_it.c
new file mode 100644
index 0000000..eb64264
--- /dev/null
+++ b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/stm32_it.c
@@ -0,0 +1,246 @@
+/**
+ ******************************************************************************
+ * @file stm32_it.c
+ * @author MCD Application Team
+ * @version V4.0.0
+ * @date 21-January-2013
+ * @brief Main Interrupt Service Routines.
+ * This file provides template for all exceptions handler and peripherals
+ * interrupt service routine.
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+ *
+ * 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 "hw_config.h"
+#include "stm32_it.h"
+#include "usb_lib.h"
+#include "usb_istr.h"
+#include "usb_prop.h"
+#include "usb_pwr.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/******************************************************************************/
+/* Cortex-M Processor Exceptions Handlers */
+/******************************************************************************/
+
+/*******************************************************************************
+* Function Name : NMI_Handler
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMI_Handler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFault_Handler
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFault_Handler(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManage_Handler
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManage_Handler(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFault_Handler
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFault_Handler(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFault_Handler
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFault_Handler(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : SVC_Handler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVC_Handler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DebugMon_Handler
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMon_Handler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSV_Handler
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSV_Handler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTick_Handler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTick_Handler(void)
+{
+}
+
+/******************************************************************************/
+/* STM32 Peripherals Interrupt Handlers */
+/*******************************************************************************
+* Function Name : USB_IRQHandler
+* Description : This function handles USB Low Priority interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+#if defined(STM32L1XX_MD) || defined(STM32L1XX_HD)|| defined(STM32L1XX_MD_PLUS)|| defined (STM32F37X)
+void USB_LP_IRQHandler(void)
+#else
+void USB_LP_CAN1_RX0_IRQHandler(void)
+#endif
+{
+ USB_Istr();
+}
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+
+#if defined (USE_STM32L152D_EVAL)
+void EXTI0_IRQHandler(void)
+#elif defined (STM32F37X)
+void EXTI2_TS_IRQHandler(void)
+#else
+void EXTI15_10_IRQHandler(void)
+#endif
+{
+ if (EXTI_GetITStatus(KEY_BUTTON_EXTI_LINE) != RESET)
+ {
+ if (pInformation->Current_Feature & 0x20) //Remote wake-up enabled
+ {
+ Resume(RESUME_INTERNAL);
+ }
+
+ /* Clear the EXTI line 9 pending bit */
+ EXTI_ClearITPendingBit(KEY_BUTTON_EXTI_LINE);
+ }
+}
+
+/*******************************************************************************
+* Function Name : USB_FS_WKUP_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+
+#if defined(STM32L1XX_MD) || defined(STM32L1XX_HD)|| defined(STM32L1XX_MD_PLUS)
+void USB_FS_WKUP_IRQHandler(void)
+#else
+void USBWakeUp_IRQHandler(void)
+#endif
+{
+ EXTI_ClearITPendingBit(EXTI_Line18);
+}
+
+/******************************************************************************/
+/* STM32 Peripherals Interrupt Handlers */
+/* Add here the Interrupt Handler for the used peripheral(s) (PPP), for the */
+/* available peripheral interrupt handler's name please refer to the startup */
+/* file (startup_stm32xxx.s). */
+/******************************************************************************/
+
+/*******************************************************************************
+* Function Name : PPP_IRQHandler
+* Description : This function handles PPP interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+/*void PPP_IRQHandler(void)
+{
+}*/
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/system_stm32f10x.c b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/system_stm32f10x.c
new file mode 100644
index 0000000..3686a2f
--- /dev/null
+++ b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/system_stm32f10x.c
@@ -0,0 +1,917 @@
+/**
+ ******************************************************************************
+ * @file system_stm32f10x.c
+ * @author MCD Application Team
+ * @version V4.0.0
+ * @date 21-January-2013
+ * @brief CMSIS Cortex-M3 Device Peripheral Access Layer System Source File.
+ *
+ * 1. This file provides two functions and one global variable to be called from
+ * user application:
+ * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier
+ * factors, AHB/APBx prescalers and Flash settings).
+ * This function is called at startup just after reset and
+ * before branch to main program. This call is made inside
+ * the "startup_stm32f10x_xx.s" file.
+ *
+ * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
+ * by the user application to setup the SysTick
+ * timer or configure other parameters.
+ *
+ * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
+ * be called whenever the core clock is changed
+ * during program execution.
+ *
+ * 2. After each device reset the HSI (8 MHz) is used as system clock source.
+ * Then SystemInit() function is called, in "startup_stm32f10x_xx.s" file, to
+ * configure the system clock before to branch to main program.
+ *
+ * 3. If the system clock source selected by user fails to startup, the SystemInit()
+ * function will do nothing and HSI still used as system clock source. User can
+ * add some code to deal with this issue inside the SetSysClock() function.
+ *
+ * 4. The default value of HSE crystal is set to 8 MHz (or 25 MHz, depedning on
+ * the product used), refer to "HSE_VALUE" define in "stm32f10x.h" file.
+ * When HSE is used as system clock source, directly or through PLL, and you
+ * are using different crystal you have to adapt the HSE value to your own
+ * configuration.
+ *
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+ *
+ * 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 stm32f10x_system
+ * @{
+ */
+
+/** @addtogroup STM32F10x_System_Private_Includes
+ * @{
+ */
+
+#include "stm32f10x.h"
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F10x_System_Private_TypesDefinitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F10x_System_Private_Defines
+ * @{
+ */
+
+/*!< Uncomment the line corresponding to the desired System clock (SYSCLK)
+ frequency (after reset the HSI is used as SYSCLK source)
+
+ IMPORTANT NOTE:
+ ==============
+ 1. After each device reset the HSI is used as System clock source.
+
+ 2. Please make sure that the selected System clock doesn't exceed your device's
+ maximum frequency.
+
+ 3. If none of the define below is enabled, the HSI is used as System clock
+ source.
+
+ 4. The System clock configuration functions provided within this file assume that:
+ - For Low, Medium and High density Value line devices an external 8MHz
+ crystal is used to drive the System clock.
+ - For Low, Medium and High density devices an external 8MHz crystal is
+ used to drive the System clock.
+ - For Connectivity line devices an external 25MHz crystal is used to drive
+ the System clock.
+ If you are using different crystal you have to adapt those functions accordingly.
+ */
+
+#if defined (STM32F10X_LD_VL) || (defined STM32F10X_MD_VL) || (defined STM32F10X_HD_VL)
+/* #define SYSCLK_FREQ_HSE HSE_VALUE */
+ #define SYSCLK_FREQ_24MHz 24000000
+#else
+/* #define SYSCLK_FREQ_HSE HSE_VALUE */
+/* #define SYSCLK_FREQ_24MHz 24000000 */
+/* #define SYSCLK_FREQ_36MHz 36000000 */
+/* #define SYSCLK_FREQ_48MHz 48000000 */
+/* #define SYSCLK_FREQ_56MHz 56000000 */
+#define SYSCLK_FREQ_72MHz 72000000
+#endif
+
+/*!< Uncomment the following line if you need to use external SRAM mounted
+ on STM3210E-EVAL board (STM32 High density and XL-density devices) or on
+ STM32100E-EVAL board (STM32 High-density value line devices) as data memory */
+#if defined (STM32F10X_HD) || (defined STM32F10X_XL) || (defined STM32F10X_HD_VL)
+/* #define DATA_IN_ExtSRAM */
+#endif
+
+/*!< Uncomment the following line if you need to relocate your vector Table in
+ Internal SRAM. */
+/* #define VECT_TAB_SRAM */
+#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field.
+ This value must be a multiple of 0x200. */
+
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F10x_System_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F10x_System_Private_Variables
+ * @{
+ */
+
+/*******************************************************************************
+* Clock Definitions
+*******************************************************************************/
+#ifdef SYSCLK_FREQ_HSE
+ uint32_t SystemCoreClock = SYSCLK_FREQ_HSE; /*!< System Clock Frequency (Core Clock) */
+#elif defined SYSCLK_FREQ_24MHz
+ uint32_t SystemCoreClock = SYSCLK_FREQ_24MHz; /*!< System Clock Frequency (Core Clock) */
+#elif defined SYSCLK_FREQ_36MHz
+ uint32_t SystemCoreClock = SYSCLK_FREQ_36MHz; /*!< System Clock Frequency (Core Clock) */
+#elif defined SYSCLK_FREQ_48MHz
+ uint32_t SystemCoreClock = SYSCLK_FREQ_48MHz; /*!< System Clock Frequency (Core Clock) */
+#elif defined SYSCLK_FREQ_56MHz
+ uint32_t SystemCoreClock = SYSCLK_FREQ_56MHz; /*!< System Clock Frequency (Core Clock) */
+#elif defined SYSCLK_FREQ_72MHz
+ uint32_t SystemCoreClock = SYSCLK_FREQ_72MHz; /*!< System Clock Frequency (Core Clock) */
+#else /*!< HSI Selected as System Clock source */
+ uint32_t SystemCoreClock = HSI_VALUE; /*!< System Clock Frequency (Core Clock) */
+#endif
+
+__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F10x_System_Private_FunctionPrototypes
+ * @{
+ */
+
+static void SetSysClock(void);
+
+#ifdef SYSCLK_FREQ_HSE
+ static void SetSysClockToHSE(void);
+#elif defined SYSCLK_FREQ_24MHz
+ static void SetSysClockTo24(void);
+#elif defined SYSCLK_FREQ_36MHz
+ static void SetSysClockTo36(void);
+#elif defined SYSCLK_FREQ_48MHz
+ static void SetSysClockTo48(void);
+#elif defined SYSCLK_FREQ_56MHz
+ static void SetSysClockTo56(void);
+#elif defined SYSCLK_FREQ_72MHz
+ static void SetSysClockTo72(void);
+#endif
+
+#ifdef DATA_IN_ExtSRAM
+ static void SystemInit_ExtMemCtl(void);
+#endif /* DATA_IN_ExtSRAM */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F10x_System_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Setup the microcontroller system
+ * Initialize the Embedded Flash Interface, the PLL and update the
+ * SystemCoreClock variable.
+ * @note This function should be used only after reset.
+ * @param None
+ * @retval None
+ */
+void SystemInit (void)
+{
+ /* Reset the RCC clock configuration to the default reset state(for debug purpose) */
+ /* Set HSION bit */
+ RCC->CR |= (uint32_t)0x00000001;
+
+ /* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */
+
+ RCC->CFGR &= (uint32_t)0xF8FF0000;
+
+ /* Reset HSEON, CSSON and PLLON bits */
+ RCC->CR &= (uint32_t)0xFEF6FFFF;
+
+ /* Reset HSEBYP bit */
+ RCC->CR &= (uint32_t)0xFFFBFFFF;
+
+ /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE/OTGFSPRE bits */
+ RCC->CFGR &= (uint32_t)0xFF80FFFF;
+
+#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || (defined STM32F10X_HD_VL)
+ /* Disable all interrupts and clear pending bits */
+ RCC->CIR = 0x009F0000;
+
+ /* Reset CFGR2 register */
+ RCC->CFGR2 = 0x00000000;
+#else
+ /* Disable all interrupts and clear pending bits */
+ RCC->CIR = 0x009F0000;
+#endif /* STM32F10X_XX */
+
+#if defined (STM32F10X_HD) || (defined STM32F10X_XL) || (defined STM32F10X_HD_VL)
+ #ifdef DATA_IN_ExtSRAM
+ SystemInit_ExtMemCtl();
+ #endif /* DATA_IN_ExtSRAM */
+#endif
+
+ /* Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers */
+ /* Configure the Flash Latency cycles and enable prefetch buffer */
+ SetSysClock();
+
+#ifdef VECT_TAB_SRAM
+ SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */
+#else
+ SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */
+#endif
+}
+
+/**
+ * @brief Update SystemCoreClock variable according to Clock Register Values.
+ * The SystemCoreClock variable contains the core clock (HCLK), it can
+ * be used by the user application to setup the SysTick timer or configure
+ * other parameters.
+ *
+ * @note Each time the core clock (HCLK) changes, this function must be called
+ * to update SystemCoreClock variable value. Otherwise, any configuration
+ * based on this variable will be incorrect.
+ *
+ * @note - The system frequency computed by this function is not the real
+ * frequency in the chip. It is calculated based on the predefined
+ * constant and the selected clock source:
+ *
+ * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
+ *
+ * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
+ *
+ * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
+ * or HSI_VALUE(*) multiplied by the PLL factors.
+ *
+ * (*) HSI_VALUE is a constant defined in stm32f1xx.h file (default value
+ * 8 MHz) but the real value may vary depending on the variations
+ * in voltage and temperature.
+ *
+ * (**) HSE_VALUE is a constant defined in stm32f1xx.h file (default value
+ * 8 MHz or 25 MHz, depending on the product used), user has to ensure
+ * that HSE_VALUE is same as the real frequency of the crystal used.
+ * Otherwise, this function may have wrong result.
+ *
+ * - The result of this function could be not correct when using fractional
+ * value for HSE crystal.
+ * @param None
+ * @retval None
+ */
+void SystemCoreClockUpdate (void)
+{
+ uint32_t tmp = 0, pllmull = 0, pllsource = 0;
+
+#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || (defined STM32F10X_HD_VL)
+ uint32_t prediv1factor = 0;
+#endif /* STM32F10X_LD_VL or STM32F10X_MD_VL or STM32F10X_HD_VL */
+
+ /* Get SYSCLK source -------------------------------------------------------*/
+ tmp = RCC->CFGR & RCC_CFGR_SWS;
+
+ switch (tmp)
+ {
+ case 0x00: /* HSI used as system clock */
+ SystemCoreClock = HSI_VALUE;
+ break;
+ case 0x04: /* HSE used as system clock */
+ SystemCoreClock = HSE_VALUE;
+ break;
+ case 0x08: /* PLL used as system clock */
+
+ /* Get PLL clock source and multiplication factor ----------------------*/
+ pllmull = RCC->CFGR & RCC_CFGR_PLLMULL;
+ pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
+
+ pllmull = ( pllmull >> 18) + 2;
+
+ if (pllsource == 0x00)
+ {
+ /* HSI oscillator clock divided by 2 selected as PLL clock entry */
+ SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
+ }
+ else
+ {
+ #if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || (defined STM32F10X_HD_VL)
+ prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1;
+ /* HSE oscillator clock selected as PREDIV1 clock entry */
+ SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull;
+ #else
+ /* HSE selected as PLL clock entry */
+ if ((RCC->CFGR & RCC_CFGR_PLLXTPRE) != (uint32_t)RESET)
+ {/* HSE oscillator clock divided by 2 */
+ SystemCoreClock = (HSE_VALUE >> 1) * pllmull;
+ }
+ else
+ {
+ SystemCoreClock = HSE_VALUE * pllmull;
+ }
+ #endif
+ }
+
+ break;
+
+ default:
+ SystemCoreClock = HSI_VALUE;
+ break;
+ }
+
+ /* Compute HCLK clock frequency ----------------*/
+ /* Get HCLK prescaler */
+ tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
+ /* HCLK clock frequency */
+ SystemCoreClock >>= tmp;
+}
+
+/**
+ * @brief Configures the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers.
+ * @param None
+ * @retval None
+ */
+static void SetSysClock(void)
+{
+#ifdef SYSCLK_FREQ_HSE
+ SetSysClockToHSE();
+#elif defined SYSCLK_FREQ_24MHz
+ SetSysClockTo24();
+#elif defined SYSCLK_FREQ_36MHz
+ SetSysClockTo36();
+#elif defined SYSCLK_FREQ_48MHz
+ SetSysClockTo48();
+#elif defined SYSCLK_FREQ_56MHz
+ SetSysClockTo56();
+#elif defined SYSCLK_FREQ_72MHz
+ SetSysClockTo72();
+#endif
+
+ /* If none of the define above is enabled, the HSI is used as System clock
+ source (default after reset) */
+}
+
+/**
+ * @brief Setup the external memory controller. Called in startup_stm32f10x.s
+ * before jump to __main
+ * @param None
+ * @retval None
+ */
+#ifdef DATA_IN_ExtSRAM
+/**
+ * @brief Setup the external memory controller.
+ * Called in startup_stm32f10x_xx.s/.c before jump to main.
+ * This function configures the external SRAM mounted on STM3210E-EVAL
+ * board (STM32 High density devices). This SRAM will be used as program
+ * data memory (including heap and stack).
+ * @param None
+ * @retval None
+ */
+void SystemInit_ExtMemCtl(void)
+{
+/*!< FSMC Bank1 NOR/SRAM3 is used for the STM3210E-EVAL, if another Bank is
+ required, then adjust the Register Addresses */
+
+ /* Enable FSMC clock */
+ RCC->AHBENR = 0x00000114;
+
+ /* Enable GPIOD, GPIOE, GPIOF and GPIOG clocks */
+ RCC->APB2ENR = 0x000001E0;
+
+/* --------------- SRAM Data lines, NOE and NWE configuration ---------------*/
+/*---------------- SRAM Address lines configuration -------------------------*/
+/*---------------- NOE and NWE configuration --------------------------------*/
+/*---------------- NE3 configuration ----------------------------------------*/
+/*---------------- NBL0, NBL1 configuration ---------------------------------*/
+
+ GPIOD->CRL = 0x44BB44BB;
+ GPIOD->CRH = 0xBBBBBBBB;
+
+ GPIOE->CRL = 0xB44444BB;
+ GPIOE->CRH = 0xBBBBBBBB;
+
+ GPIOF->CRL = 0x44BBBBBB;
+ GPIOF->CRH = 0xBBBB4444;
+
+ GPIOG->CRL = 0x44BBBBBB;
+ GPIOG->CRH = 0x44444B44;
+
+/*---------------- FSMC Configuration ---------------------------------------*/
+/*---------------- Enable FSMC Bank1_SRAM Bank ------------------------------*/
+
+ FSMC_Bank1->BTCR[4] = 0x00001011;
+ FSMC_Bank1->BTCR[5] = 0x00000200;
+}
+#endif /* DATA_IN_ExtSRAM */
+
+#ifdef SYSCLK_FREQ_HSE
+/**
+ * @brief Selects HSE as System clock source and configure HCLK, PCLK2
+ * and PCLK1 prescalers.
+ * @note This function should be used only after reset.
+ * @param None
+ * @retval None
+ */
+static void SetSysClockToHSE(void)
+{
+ __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+
+ /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/
+ /* Enable HSE */
+ RCC->CR |= ((uint32_t)RCC_CR_HSEON);
+
+ /* Wait till HSE is ready and if Time out is reached exit */
+ do
+ {
+ HSEStatus = RCC->CR & RCC_CR_HSERDY;
+ StartUpCounter++;
+ } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
+
+ if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+ {
+ HSEStatus = (uint32_t)0x01;
+ }
+ else
+ {
+ HSEStatus = (uint32_t)0x00;
+ }
+
+ if (HSEStatus == (uint32_t)0x01)
+ {
+
+#if !defined STM32F10X_LD_VL && !defined STM32F10X_MD_VL && !defined STM32F10X_HD_VL
+ /* Enable Prefetch Buffer */
+ FLASH->ACR |= FLASH_ACR_PRFTBE;
+
+ /* Flash 0 wait state */
+ FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY);
+
+ FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_0;
+#endif
+
+ /* HCLK = SYSCLK */
+ RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
+
+ /* PCLK2 = HCLK */
+ RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
+
+ /* PCLK1 = HCLK */
+ RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV1;
+
+ /* Select HSE as system clock source */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+ RCC->CFGR |= (uint32_t)RCC_CFGR_SW_HSE;
+
+ /* Wait till HSE is used as system clock source */
+ while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x04)
+ {
+ }
+ }
+ else
+ { /* If HSE fails to start-up, the application will have wrong clock
+ configuration. User can add here some code to deal with this error */
+ }
+}
+#elif defined SYSCLK_FREQ_24MHz
+/**
+ * @brief Sets System clock frequency to 24MHz and configure HCLK, PCLK2
+ * and PCLK1 prescalers.
+ * @note This function should be used only after reset.
+ * @param None
+ * @retval None
+ */
+static void SetSysClockTo24(void)
+{
+ __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+
+ /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/
+ /* Enable HSE */
+ RCC->CR |= ((uint32_t)RCC_CR_HSEON);
+
+ /* Wait till HSE is ready and if Time out is reached exit */
+ do
+ {
+ HSEStatus = RCC->CR & RCC_CR_HSERDY;
+ StartUpCounter++;
+ } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
+
+ if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+ {
+ HSEStatus = (uint32_t)0x01;
+ }
+ else
+ {
+ HSEStatus = (uint32_t)0x00;
+ }
+
+ if (HSEStatus == (uint32_t)0x01)
+ {
+#if !defined STM32F10X_LD_VL && !defined STM32F10X_MD_VL && !defined STM32F10X_HD_VL
+ /* Enable Prefetch Buffer */
+ FLASH->ACR |= FLASH_ACR_PRFTBE;
+
+ /* Flash 0 wait state */
+ FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY);
+ FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_0;
+#endif
+
+ /* HCLK = SYSCLK */
+ RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
+
+ /* PCLK2 = HCLK */
+ RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
+
+ /* PCLK1 = HCLK */
+ RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV1;
+
+#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL)
+ /* PLL configuration: = (HSE / 2) * 6 = 24 MHz */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
+ RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_PREDIV1 | RCC_CFGR_PLLXTPRE_PREDIV1_Div2 | RCC_CFGR_PLLMULL6);
+#else
+ /* PLL configuration: = (HSE / 2) * 6 = 24 MHz */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
+ RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLXTPRE_HSE_Div2 | RCC_CFGR_PLLMULL6);
+#endif /* STM32F10X_XX */
+
+ /* Enable PLL */
+ RCC->CR |= RCC_CR_PLLON;
+
+ /* Wait till PLL is ready */
+ while((RCC->CR & RCC_CR_PLLRDY) == 0)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+ RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
+
+ /* Wait till PLL is used as system clock source */
+ while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08)
+ {
+ }
+ }
+ else
+ { /* If HSE fails to start-up, the application will have wrong clock
+ configuration. User can add here some code to deal with this error */
+ }
+}
+#elif defined SYSCLK_FREQ_36MHz
+/**
+ * @brief Sets System clock frequency to 36MHz and configure HCLK, PCLK2
+ * and PCLK1 prescalers.
+ * @note This function should be used only after reset.
+ * @param None
+ * @retval None
+ */
+static void SetSysClockTo36(void)
+{
+ __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+
+ /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/
+ /* Enable HSE */
+ RCC->CR |= ((uint32_t)RCC_CR_HSEON);
+
+ /* Wait till HSE is ready and if Time out is reached exit */
+ do
+ {
+ HSEStatus = RCC->CR & RCC_CR_HSERDY;
+ StartUpCounter++;
+ } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
+
+ if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+ {
+ HSEStatus = (uint32_t)0x01;
+ }
+ else
+ {
+ HSEStatus = (uint32_t)0x00;
+ }
+
+ if (HSEStatus == (uint32_t)0x01)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH->ACR |= FLASH_ACR_PRFTBE;
+
+ /* Flash 1 wait state */
+ FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY);
+ FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_1;
+
+ /* HCLK = SYSCLK */
+ RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
+
+ /* PCLK2 = HCLK */
+ RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
+
+ /* PCLK1 = HCLK */
+ RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV1;
+
+ /* PLL configuration: PLLCLK = (HSE / 2) * 9 = 36 MHz */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
+ RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLXTPRE_HSE_Div2 | RCC_CFGR_PLLMULL9);
+
+ /* Enable PLL */
+ RCC->CR |= RCC_CR_PLLON;
+
+ /* Wait till PLL is ready */
+ while((RCC->CR & RCC_CR_PLLRDY) == 0)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+ RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
+
+ /* Wait till PLL is used as system clock source */
+ while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08)
+ {
+ }
+ }
+ else
+ { /* If HSE fails to start-up, the application will have wrong clock
+ configuration. User can add here some code to deal with this error */
+ }
+}
+#elif defined SYSCLK_FREQ_48MHz
+/**
+ * @brief Sets System clock frequency to 48MHz and configure HCLK, PCLK2
+ * and PCLK1 prescalers.
+ * @note This function should be used only after reset.
+ * @param None
+ * @retval None
+ */
+static void SetSysClockTo48(void)
+{
+ __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+
+ /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/
+ /* Enable HSE */
+ RCC->CR |= ((uint32_t)RCC_CR_HSEON);
+
+ /* Wait till HSE is ready and if Time out is reached exit */
+ do
+ {
+ HSEStatus = RCC->CR & RCC_CR_HSERDY;
+ StartUpCounter++;
+ } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
+
+ if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+ {
+ HSEStatus = (uint32_t)0x01;
+ }
+ else
+ {
+ HSEStatus = (uint32_t)0x00;
+ }
+
+ if (HSEStatus == (uint32_t)0x01)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH->ACR |= FLASH_ACR_PRFTBE;
+
+ /* Flash 1 wait state */
+ FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY);
+ FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_1;
+
+ /* HCLK = SYSCLK */
+ RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
+
+ /* PCLK2 = HCLK */
+ RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
+
+ /* PCLK1 = HCLK */
+ RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2;
+
+ /* PLL configuration: PLLCLK = HSE * 6 = 48 MHz */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
+ RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMULL6);
+
+ /* Enable PLL */
+ RCC->CR |= RCC_CR_PLLON;
+
+ /* Wait till PLL is ready */
+ while((RCC->CR & RCC_CR_PLLRDY) == 0)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+ RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
+
+ /* Wait till PLL is used as system clock source */
+ while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08)
+ {
+ }
+ }
+ else
+ { /* If HSE fails to start-up, the application will have wrong clock
+ configuration. User can add here some code to deal with this error */
+ }
+}
+
+#elif defined SYSCLK_FREQ_56MHz
+/**
+ * @brief Sets System clock frequency to 56MHz and configure HCLK, PCLK2
+ * and PCLK1 prescalers.
+ * @note This function should be used only after reset.
+ * @param None
+ * @retval None
+ */
+static void SetSysClockTo56(void)
+{
+ __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+
+ /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/
+ /* Enable HSE */
+ RCC->CR |= ((uint32_t)RCC_CR_HSEON);
+
+ /* Wait till HSE is ready and if Time out is reached exit */
+ do
+ {
+ HSEStatus = RCC->CR & RCC_CR_HSERDY;
+ StartUpCounter++;
+ } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
+
+ if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+ {
+ HSEStatus = (uint32_t)0x01;
+ }
+ else
+ {
+ HSEStatus = (uint32_t)0x00;
+ }
+
+ if (HSEStatus == (uint32_t)0x01)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH->ACR |= FLASH_ACR_PRFTBE;
+
+ /* Flash 2 wait state */
+ FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY);
+ FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_2;
+
+ /* HCLK = SYSCLK */
+ RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
+
+ /* PCLK2 = HCLK */
+ RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
+
+ /* PCLK1 = HCLK */
+ RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2;
+
+
+ /* PLL configuration: PLLCLK = HSE * 7 = 56 MHz */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
+ RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMULL7);
+
+ /* Enable PLL */
+ RCC->CR |= RCC_CR_PLLON;
+
+ /* Wait till PLL is ready */
+ while((RCC->CR & RCC_CR_PLLRDY) == 0)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+ RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
+
+ /* Wait till PLL is used as system clock source */
+ while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08)
+ {
+ }
+ }
+ else
+ { /* If HSE fails to start-up, the application will have wrong clock
+ configuration. User can add here some code to deal with this error */
+ }
+}
+
+#elif defined SYSCLK_FREQ_72MHz
+/**
+ * @brief Sets System clock frequency to 72MHz and configure HCLK, PCLK2
+ * and PCLK1 prescalers.
+ * @note This function should be used only after reset.
+ * @param None
+ * @retval None
+ */
+static void SetSysClockTo72(void)
+{
+ __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+
+ /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/
+ /* Enable HSE */
+ RCC->CR |= ((uint32_t)RCC_CR_HSEON);
+
+ /* Wait till HSE is ready and if Time out is reached exit */
+ do
+ {
+ HSEStatus = RCC->CR & RCC_CR_HSERDY;
+ StartUpCounter++;
+ } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
+
+ if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+ {
+ HSEStatus = (uint32_t)0x01;
+ }
+ else
+ {
+ HSEStatus = (uint32_t)0x00;
+ }
+
+ if (HSEStatus == (uint32_t)0x01)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH->ACR |= FLASH_ACR_PRFTBE;
+
+ /* Flash 2 wait state */
+ FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY);
+ FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_2;
+
+
+ /* HCLK = SYSCLK */
+ RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
+
+ /* PCLK2 = HCLK */
+ RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
+
+ /* PCLK1 = HCLK */
+ RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2;
+
+ /* PLL configuration: PLLCLK = HSE * 9 = 72 MHz */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE |
+ RCC_CFGR_PLLMULL));
+ RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMULL9);
+
+ /* Enable PLL */
+ RCC->CR |= RCC_CR_PLLON;
+
+ /* Wait till PLL is ready */
+ while((RCC->CR & RCC_CR_PLLRDY) == 0)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+ RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
+
+ /* Wait till PLL is used as system clock source */
+ while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08)
+ {
+ }
+ }
+ else
+ { /* If HSE fails to start-up, the application will have wrong clock
+ configuration. User can add here some code to deal with this error */
+ }
+}
+#endif
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/system_stm32l1xx.c b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/system_stm32l1xx.c
new file mode 100644
index 0000000..1be659d
--- /dev/null
+++ b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/system_stm32l1xx.c
@@ -0,0 +1,533 @@
+/**
+ ******************************************************************************
+ * @file system_stm32l1xx.c
+ * @author MCD Application Team
+ * @version V4.0.0
+ * @date 21-January-2013
+ * @brief CMSIS Cortex-M3 Device Peripheral Access Layer System Source File.
+ * This file contains the system clock configuration for STM32L1xx Ultra
+ * Low Power devices, and is generated by the clock configuration
+ * tool "STM32L1xx_Clock_Configuration_V1.1.0.xls".
+ *
+ * 1. This file provides two functions and one global variable to be called from
+ * user application:
+ * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier
+ * and Divider factors, AHB/APBx prescalers and Flash settings),
+ * depending on the configuration made in the clock xls tool.
+ * This function is called at startup just after reset and
+ * before branch to main program. This call is made inside
+ * the "startup_stm32l1xx_xx.s" file.
+ *
+ * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
+ * by the user application to setup the SysTick
+ * timer or configure other parameters.
+ *
+ * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
+ * be called whenever the core clock is changed
+ * during program execution.
+ *
+ * 2. After each device reset the MSI (2.1 MHz Range) is used as system clock source.
+ * Then SystemInit() function is called, in "startup_stm32l1xx_xx.s" file, to
+ * configure the system clock before to branch to main program.
+ *
+ * 3. If the system clock source selected by user fails to startup, the SystemInit()
+ * function will do nothing and MSI still used as system clock source. User can
+ * add some code to deal with this issue inside the SetSysClock() function.
+ *
+ * 4. The default value of HSE crystal is set to 8MHz, refer to "HSE_VALUE" define
+ * in "stm32l1xx.h" file. When HSE is used as system clock source, directly or
+ * through PLL, and you are using different crystal you have to adapt the HSE
+ * value to your own configuration.
+ *
+ * 5. This file configures the system clock as follows:
+ *=============================================================================
+ * System Clock Configuration
+ *=============================================================================
+ * System Clock source | PLL(HSE)
+ *-----------------------------------------------------------------------------
+ * SYSCLK | 32000000 Hz
+ *-----------------------------------------------------------------------------
+ * HCLK | 32000000 Hz
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * HSE Frequency | 8000000 Hz
+ *-----------------------------------------------------------------------------
+ * PLL DIV | 3
+ *-----------------------------------------------------------------------------
+ * PLL MUL | 12
+ *-----------------------------------------------------------------------------
+ * VDD | 3.3 V
+ *-----------------------------------------------------------------------------
+ * Vcore | 1.8 V (Range 1)
+ *-----------------------------------------------------------------------------
+ * Flash Latency | 1 WS
+ *-----------------------------------------------------------------------------
+ * SDIO clock (SDIOCLK) | 48000000 Hz
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB clock | Disabled
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+ *
+ * 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 stm32l1xx_system
+ * @{
+ */
+
+/** @addtogroup STM32L1xx_System_Private_Includes
+ * @{
+ */
+
+#include "stm32l1xx.h"
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32L1xx_System_Private_TypesDefinitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32L1xx_System_Private_Defines
+ * @{
+ */
+
+/*!< Uncomment the following line if you need to use external SRAM mounted
+ on STM32L152D_EVAL board as data memory */
+/* #define DATA_IN_ExtSRAM */
+
+/*!< Uncomment the following line if you need to relocate your vector Table in
+ Internal SRAM. */
+/* #define VECT_TAB_SRAM */
+#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field.
+ This value must be a multiple of 0x200. */
+/**
+ * @}
+ */
+
+/** @addtogroup STM32L1xx_System_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32L1xx_System_Private_Variables
+ * @{
+ */
+uint32_t SystemCoreClock = 32000000;
+__I uint8_t PLLMulTable[9] = {3, 4, 6, 8, 12, 16, 24, 32, 48};
+__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32L1xx_System_Private_FunctionPrototypes
+ * @{
+ */
+
+static void SetSysClock(void);
+#ifdef DATA_IN_ExtSRAM
+ static void SystemInit_ExtMemCtl(void);
+#endif /* DATA_IN_ExtSRAM */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32L1xx_System_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Setup the microcontroller system.
+ * Initialize the Embedded Flash Interface, the PLL and update the
+ * SystemCoreClock variable.
+ * @param None
+ * @retval None
+ */
+void SystemInit (void)
+{
+ /*!< Set MSION bit */
+ RCC->CR |= (uint32_t)0x00000100;
+
+ /*!< Reset SW[1:0], HPRE[3:0], PPRE1[2:0], PPRE2[2:0], MCOSEL[2:0] and MCOPRE[2:0] bits */
+ RCC->CFGR &= (uint32_t)0x88FFC00C;
+
+ /*!< Reset HSION, HSEON, CSSON and PLLON bits */
+ RCC->CR &= (uint32_t)0xEEFEFFFE;
+
+ /*!< Reset HSEBYP bit */
+ RCC->CR &= (uint32_t)0xFFFBFFFF;
+
+ /*!< Reset PLLSRC, PLLMUL[3:0] and PLLDIV[1:0] bits */
+ RCC->CFGR &= (uint32_t)0xFF02FFFF;
+
+ /*!< Disable all interrupts */
+ RCC->CIR = 0x00000000;
+
+#ifdef DATA_IN_ExtSRAM
+ SystemInit_ExtMemCtl();
+#endif /* DATA_IN_ExtSRAM */
+
+ /* Configure the System clock frequency, AHB/APBx prescalers and Flash settings */
+ SetSysClock();
+
+#ifdef VECT_TAB_SRAM
+ SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */
+#else
+ SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */
+#endif
+}
+
+/**
+ * @brief Update SystemCoreClock according to Clock Register Values
+ * The SystemCoreClock variable contains the core clock (HCLK), it can
+ * be used by the user application to setup the SysTick timer or configure
+ * other parameters.
+ *
+ * @note Each time the core clock (HCLK) changes, this function must be called
+ * to update SystemCoreClock variable value. Otherwise, any configuration
+ * based on this variable will be incorrect.
+ *
+ * @note - The system frequency computed by this function is not the real
+ * frequency in the chip. It is calculated based on the predefined
+ * constant and the selected clock source:
+ *
+ * - If SYSCLK source is MSI, SystemCoreClock will contain the MSI
+ * value as defined by the MSI range.
+ *
+ * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
+ *
+ * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
+ *
+ * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
+ * or HSI_VALUE(*) multiplied/divided by the PLL factors.
+ *
+ * (*) HSI_VALUE is a constant defined in stm32l1xx.h file (default value
+ * 16 MHz) but the real value may vary depending on the variations
+ * in voltage and temperature.
+ *
+ * (**) HSE_VALUE is a constant defined in stm32l1xx.h file (default value
+ * 8 MHz), user has to ensure that HSE_VALUE is same as the real
+ * frequency of the crystal used. Otherwise, this function may
+ * have wrong result.
+ *
+ * - The result of this function could be not correct when using fractional
+ * value for HSE crystal.
+ * @param None
+ * @retval None
+ */
+void SystemCoreClockUpdate (void)
+{
+ uint32_t tmp = 0, pllmul = 0, plldiv = 0, pllsource = 0, msirange = 0;
+
+ /* Get SYSCLK source -------------------------------------------------------*/
+ tmp = RCC->CFGR & RCC_CFGR_SWS;
+
+ switch (tmp)
+ {
+ case 0x00: /* MSI used as system clock */
+ msirange = (RCC->ICSCR & RCC_ICSCR_MSIRANGE) >> 13;
+ SystemCoreClock = (32768 * (1 << (msirange + 1)));
+ break;
+ case 0x04: /* HSI used as system clock */
+ SystemCoreClock = HSI_VALUE;
+ break;
+ case 0x08: /* HSE used as system clock */
+ SystemCoreClock = HSE_VALUE;
+ break;
+ case 0x0C: /* PLL used as system clock */
+ /* Get PLL clock source and multiplication factor ----------------------*/
+ pllmul = RCC->CFGR & RCC_CFGR_PLLMUL;
+ plldiv = RCC->CFGR & RCC_CFGR_PLLDIV;
+ pllmul = PLLMulTable[(pllmul >> 18)];
+ plldiv = (plldiv >> 22) + 1;
+
+ pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
+
+ if (pllsource == 0x00)
+ {
+ /* HSI oscillator clock selected as PLL clock entry */
+ SystemCoreClock = (((HSI_VALUE) * pllmul) / plldiv);
+ }
+ else
+ {
+ /* HSE selected as PLL clock entry */
+ SystemCoreClock = (((HSE_VALUE) * pllmul) / plldiv);
+ }
+ break;
+ default: /* MSI used as system clock */
+ msirange = (RCC->ICSCR & RCC_ICSCR_MSIRANGE) >> 13;
+ SystemCoreClock = (32768 * (1 << (msirange + 1)));
+ break;
+ }
+ /* Compute HCLK clock frequency --------------------------------------------*/
+ /* Get HCLK prescaler */
+ tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
+ /* HCLK clock frequency */
+ SystemCoreClock >>= tmp;
+}
+
+/**
+ * @brief Configures the System clock frequency, AHB/APBx prescalers and Flash
+ * settings.
+ * @note This function should be called only once the RCC clock configuration
+ * is reset to the default reset state (done in SystemInit() function).
+ * @param None
+ * @retval None
+ */
+static void SetSysClock(void)
+{
+ __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+
+ /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/
+ /* Enable HSE */
+ RCC->CR |= ((uint32_t)RCC_CR_HSEON);
+
+ /* Wait till HSE is ready and if Time out is reached exit */
+ do
+ {
+ HSEStatus = RCC->CR & RCC_CR_HSERDY;
+ StartUpCounter++;
+ } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
+
+ if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+ {
+ HSEStatus = (uint32_t)0x01;
+ }
+ else
+ {
+ HSEStatus = (uint32_t)0x00;
+ }
+
+ if (HSEStatus == (uint32_t)0x01)
+ {
+ /* Enable 64-bit access */
+ FLASH->ACR |= FLASH_ACR_ACC64;
+
+ /* Enable Prefetch Buffer */
+ FLASH->ACR |= FLASH_ACR_PRFTEN;
+
+ /* Flash 1 wait state */
+ FLASH->ACR |= FLASH_ACR_LATENCY;
+
+ /* Power enable */
+ RCC->APB1ENR |= RCC_APB1ENR_PWREN;
+
+ /* Select the Voltage Range 1 (1.8 V) */
+ PWR->CR = PWR_CR_VOS_0;
+
+ /* Wait Until the Voltage Regulator is ready */
+ while((PWR->CSR & PWR_CSR_VOSF) != RESET)
+ {
+ }
+
+ /* HCLK = SYSCLK /1*/
+ RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
+
+ /* PCLK2 = HCLK /1*/
+ RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
+
+ /* PCLK1 = HCLK /1*/
+ RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV1;
+
+ /* PLL configuration */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLMUL |
+ RCC_CFGR_PLLDIV));
+ RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMUL12 | RCC_CFGR_PLLDIV3);
+
+ /* Enable PLL */
+ RCC->CR |= RCC_CR_PLLON;
+
+ /* Wait till PLL is ready */
+ while((RCC->CR & RCC_CR_PLLRDY) == 0)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+ RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
+
+ /* Wait till PLL is used as system clock source */
+ while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)RCC_CFGR_SWS_PLL)
+ {
+ }
+ }
+ else
+ {
+ /* If HSE fails to start-up, the application will have wrong clock
+ configuration. User can add here some code to deal with this error */
+ }
+}
+
+#ifdef DATA_IN_ExtSRAM
+/**
+ * @brief Setup the external memory controller.
+ * Called in SystemInit() function before jump to main.
+ * This function configures the external SRAM mounted on STM32L152D_EVAL board
+ * This SRAM will be used as program data memory (including heap and stack).
+ * @param None
+ * @retval None
+ */
+void SystemInit_ExtMemCtl(void)
+{
+/*-- GPIOs Configuration -----------------------------------------------------*/
+/*
+ +-------------------+--------------------+------------------+------------------+
+ + SRAM pins assignment +
+ +-------------------+--------------------+------------------+------------------+
+ | PD0 <-> FSMC_D2 | PE0 <-> FSMC_NBL0 | PF0 <-> FSMC_A0 | PG0 <-> FSMC_A10 |
+ | PD1 <-> FSMC_D3 | PE1 <-> FSMC_NBL1 | PF1 <-> FSMC_A1 | PG1 <-> FSMC_A11 |
+ | PD4 <-> FSMC_NOE | PE7 <-> FSMC_D4 | PF2 <-> FSMC_A2 | PG2 <-> FSMC_A12 |
+ | PD5 <-> FSMC_NWE | PE8 <-> FSMC_D5 | PF3 <-> FSMC_A3 | PG3 <-> FSMC_A13 |
+ | PD8 <-> FSMC_D13 | PE9 <-> FSMC_D6 | PF4 <-> FSMC_A4 | PG4 <-> FSMC_A14 |
+ | PD9 <-> FSMC_D14 | PE10 <-> FSMC_D7 | PF5 <-> FSMC_A5 | PG5 <-> FSMC_A15 |
+ | PD10 <-> FSMC_D15 | PE11 <-> FSMC_D8 | PF12 <-> FSMC_A6 | PG10<-> FSMC_NE2 |
+ | PD11 <-> FSMC_A16 | PE12 <-> FSMC_D9 | PF13 <-> FSMC_A7 |------------------+
+ | PD12 <-> FSMC_A17 | PE13 <-> FSMC_D10 | PF14 <-> FSMC_A8 |
+ | PD13 <-> FSMC_A18 | PE14 <-> FSMC_D11 | PF15 <-> FSMC_A9 |
+ | PD14 <-> FSMC_D0 | PE15 <-> FSMC_D12 |------------------+
+ | PD15 <-> FSMC_D1 |--------------------+
+ +-------------------+
+*/
+
+ /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */
+ RCC->AHBENR = 0x000080D8;
+
+ /* Connect PDx pins to FSMC Alternate function */
+ GPIOD->AFR[0] = 0x00CC00CC;
+ GPIOD->AFR[1] = 0xCCCCCCCC;
+ /* Configure PDx pins in Alternate function mode */
+ GPIOD->MODER = 0xAAAA0A0A;
+ /* Configure PDx pins speed to 40 MHz */
+ GPIOD->OSPEEDR = 0xFFFF0F0F;
+ /* Configure PDx pins Output type to push-pull */
+ GPIOD->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PDx pins */
+ GPIOD->PUPDR = 0x00000000;
+
+ /* Connect PEx pins to FSMC Alternate function */
+ GPIOE->AFR[0] = 0xC00000CC;
+ GPIOE->AFR[1] = 0xCCCCCCCC;
+ /* Configure PEx pins in Alternate function mode */
+ GPIOE->MODER = 0xAAAA800A;
+ /* Configure PEx pins speed to 40 MHz */
+ GPIOE->OSPEEDR = 0xFFFFC00F;
+ /* Configure PEx pins Output type to push-pull */
+ GPIOE->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PEx pins */
+ GPIOE->PUPDR = 0x00000000;
+
+ /* Connect PFx pins to FSMC Alternate function */
+ GPIOF->AFR[0] = 0x00CCCCCC;
+ GPIOF->AFR[1] = 0xCCCC0000;
+ /* Configure PFx pins in Alternate function mode */
+ GPIOF->MODER = 0xAA000AAA;
+ /* Configure PFx pins speed to 40 MHz */
+ GPIOF->OSPEEDR = 0xFF000FFF;
+ /* Configure PFx pins Output type to push-pull */
+ GPIOF->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PFx pins */
+ GPIOF->PUPDR = 0x00000000;
+
+ /* Connect PGx pins to FSMC Alternate function */
+ GPIOG->AFR[0] = 0x00CCCCCC;
+ GPIOG->AFR[1] = 0x00000C00;
+ /* Configure PGx pins in Alternate function mode */
+ GPIOG->MODER = 0x00200AAA;
+ /* Configure PGx pins speed to 40 MHz */
+ GPIOG->OSPEEDR = 0x00300FFF;
+ /* Configure PGx pins Output type to push-pull */
+ GPIOG->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PGx pins */
+ GPIOG->PUPDR = 0x00000000;
+
+/*-- FSMC Configuration ------------------------------------------------------*/
+ /* Enable the FSMC interface clock */
+ RCC->AHBENR = 0x400080D8;
+
+ /* Configure and enable Bank1_SRAM3 */
+ FSMC_Bank1->BTCR[4] = 0x00001011;
+ FSMC_Bank1->BTCR[5] = 0x00000300;
+ FSMC_Bank1E->BWTR[4] = 0x0FFFFFFF;
+/*
+ Bank1_SRAM3 is configured as follow:
+
+ p.FSMC_AddressSetupTime = 0;
+ p.FSMC_AddressHoldTime = 0;
+ p.FSMC_DataSetupTime = 3;
+ p.FSMC_BusTurnAroundDuration = 0;
+ p.FSMC_CLKDivision = 0;
+ p.FSMC_DataLatency = 0;
+ p.FSMC_AccessMode = FSMC_AccessMode_A;
+
+ FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM3;
+ FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_SRAM;
+ FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b;
+ FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low;
+ FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState;
+ FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &p;
+ FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &p;
+
+ FSMC_NORSRAMInit(&FSMC_NORSRAMInitStructure);
+
+ FSMC_NORSRAMCmd(FSMC_Bank1_NORSRAM3, ENABLE);
+*/
+
+}
+#endif /* DATA_IN_ExtSRAM */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/usb_istr.c b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/usb_istr.c
new file mode 100644
index 0000000..c863226
--- /dev/null
+++ b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Device_Firmware_Upgrade/src/usb_istr.c
@@ -0,0 +1,231 @@
+/**
+ ******************************************************************************
+ * @file usb_istr.c
+ * @author MCD Application Team
+ * @version V4.0.0
+ * @date 21-January-2013
+ * @brief ISTR events interrupt service routines
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+ *
+ * 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 "usb_lib.h"
+#include "usb_prop.h"
+#include "usb_pwr.h"
+#include "usb_istr.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+__IO uint16_t wIstr; /* ISTR register last read value */
+__IO uint8_t bIntPackSOF = 0; /* SOFs received between 2 consecutive packets */
+__IO uint32_t esof_counter =0; /* expected SOF counter */
+__IO uint32_t wCNTR=0;
+
+/* Extern variables ----------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+/* function pointers to non-control endpoints service routines */
+void (*pEpInt_IN[7])(void) =
+ {
+ EP1_IN_Callback,
+ EP2_IN_Callback,
+ EP3_IN_Callback,
+ EP4_IN_Callback,
+ EP5_IN_Callback,
+ EP6_IN_Callback,
+ EP7_IN_Callback,
+ };
+
+void (*pEpInt_OUT[7])(void) =
+ {
+ EP1_OUT_Callback,
+ EP2_OUT_Callback,
+ EP3_OUT_Callback,
+ EP4_OUT_Callback,
+ EP5_OUT_Callback,
+ EP6_OUT_Callback,
+ EP7_OUT_Callback,
+ };
+
+/*******************************************************************************
+* Function Name : USB_Istr
+* Description : ISTR events interrupt service routine
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void USB_Istr(void)
+{
+ uint32_t i=0;
+ __IO uint32_t EP[8];
+
+ wIstr = _GetISTR();
+
+#if (IMR_MSK & ISTR_CTR)
+ if (wIstr & ISTR_CTR & wInterrupt_Mask)
+ {
+ /* servicing of the endpoint correct transfer interrupt */
+ /* clear of the CTR flag into the sub */
+ CTR_LP();
+#ifdef CTR_CALLBACK
+ CTR_Callback();
+#endif
+ }
+#endif
+ /*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
+#if (IMR_MSK & ISTR_RESET)
+ if (wIstr & ISTR_RESET & wInterrupt_Mask)
+ {
+ _SetISTR((uint16_t)CLR_RESET);
+ Device_Property.Reset();
+#ifdef RESET_CALLBACK
+ RESET_Callback();
+#endif
+ }
+#endif
+ /*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
+#if (IMR_MSK & ISTR_DOVR)
+ if (wIstr & ISTR_DOVR & wInterrupt_Mask)
+ {
+ _SetISTR((uint16_t)CLR_DOVR);
+#ifdef DOVR_CALLBACK
+ DOVR_Callback();
+#endif
+ }
+#endif
+ /*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
+#if (IMR_MSK & ISTR_ERR)
+ if (wIstr & ISTR_ERR & wInterrupt_Mask)
+ {
+ _SetISTR((uint16_t)CLR_ERR);
+#ifdef ERR_CALLBACK
+ ERR_Callback();
+#endif
+ }
+#endif
+ /*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
+#if (IMR_MSK & ISTR_WKUP)
+ if (wIstr & ISTR_WKUP & wInterrupt_Mask)
+ {
+ _SetISTR((uint16_t)CLR_WKUP);
+ Resume(RESUME_EXTERNAL);
+#ifdef WKUP_CALLBACK
+ WKUP_Callback();
+#endif
+ }
+#endif
+ /*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
+#if (IMR_MSK & ISTR_SUSP)
+ if (wIstr & ISTR_SUSP & wInterrupt_Mask)
+ {
+
+ /* check if SUSPEND is possible */
+ if (fSuspendEnabled)
+ {
+ Suspend();
+ }
+ else
+ {
+ /* if not possible then resume after xx ms */
+ Resume(RESUME_LATER);
+ }
+ /* clear of the ISTR bit must be done after setting of CNTR_FSUSP */
+ _SetISTR((uint16_t)CLR_SUSP);
+#ifdef SUSP_CALLBACK
+ SUSP_Callback();
+#endif
+ }
+#endif
+ /*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
+#if (IMR_MSK & ISTR_SOF)
+ if (wIstr & ISTR_SOF & wInterrupt_Mask)
+ {
+ _SetISTR((uint16_t)CLR_SOF);
+ bIntPackSOF++;
+
+#ifdef SOF_CALLBACK
+ SOF_Callback();
+#endif
+ }
+#endif
+ /*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
+#if (IMR_MSK & ISTR_ESOF)
+ if (wIstr & ISTR_ESOF & wInterrupt_Mask)
+ {
+ /* clear ESOF flag in ISTR */
+ _SetISTR((uint16_t)CLR_ESOF);
+
+ if ((_GetFNR()&FNR_RXDP)!=0)
+ {
+ /* increment ESOF counter */
+ esof_counter ++;
+
+ /* test if we enter in ESOF more than 3 times with FSUSP =0 and RXDP =1=>> possible missing SUSP flag*/
+ if ((esof_counter >3)&&((_GetCNTR()&CNTR_FSUSP)==0))
+ {
+ /* this a sequence to apply a force RESET*/
+
+ /*Store CNTR value */
+ wCNTR = _GetCNTR();
+
+ /*Store endpoints registers status */
+ for (i=0;i<8;i++) EP[i] = _GetENDPOINT(i);
+
+ /*apply FRES */
+ wCNTR|=CNTR_FRES;
+ _SetCNTR(wCNTR);
+
+ /*clear FRES*/
+ wCNTR&=~CNTR_FRES;
+ _SetCNTR(wCNTR);
+
+ /*poll for RESET flag in ISTR*/
+ while((_GetISTR()&ISTR_RESET) == 0);
+
+ /* clear RESET flag in ISTR */
+ _SetISTR((uint16_t)CLR_RESET);
+
+ /*restore Enpoints*/
+ for (i=0;i<8;i++)
+ _SetENDPOINT(i, EP[i]);
+
+ esof_counter = 0;
+ }
+ }
+ else
+ {
+ esof_counter = 0;
+ }
+
+ /* resume handling timing is made with ESOFs */
+ Resume(RESUME_ESOF); /* request without change of the machine state */
+
+#ifdef ESOF_CALLBACK
+ ESOF_Callback();
+#endif
+ }
+#endif
+} /* USB_Istr */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+