aboutsummaryrefslogtreecommitdiff
path: root/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src
diff options
context:
space:
mode:
Diffstat (limited to 'thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src')
-rw-r--r--thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/hw_config.c461
-rw-r--r--thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/i2s_codec.c1573
-rw-r--r--thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/main.c87
-rw-r--r--thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/stm32_it.c336
-rw-r--r--thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/system_stm32f10x.c917
-rw-r--r--thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/system_stm32l1xx.c533
-rw-r--r--thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/usb_desc.c251
-rw-r--r--thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/usb_istr.c248
-rw-r--r--thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/usb_pwr.c318
9 files changed, 4724 insertions, 0 deletions
diff --git a/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/hw_config.c b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/hw_config.c
new file mode 100644
index 0000000..74eb8ed
--- /dev/null
+++ b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/hw_config.c
@@ -0,0 +1,461 @@
+/**
+ ******************************************************************************
+ * @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 "stm32_it.h"
+#include "usb_lib.h"
+#include "usb_desc.h"
+#include "usb_pwr.h"
+#include "usb_prop.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define TIM2ARRValue 3273 /* 22KHz = 72MHz / 3273 */
+/* 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.
+* Return : None.
+*******************************************************************************/
+void Set_System(void)
+{
+#if !defined(STM32L1XX_MD)
+ GPIO_InitTypeDef GPIO_InitStructure;
+#endif /* STM32L1XX_MD */
+#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_stm32xxx.s) before to branch to application main.
+ To reconfigure the default setting of SystemInit() function, refer to
+ system_stm32xxx.c file
+ */
+
+#ifdef STM32L1XX_MD
+ /* Enable the SYSCFG module clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
+#endif /* STM32L1XX_MD */
+
+#ifdef USE_STM3210B_EVAL
+ /* Enable GPIOB, TIM2 & TIM4 clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB , ENABLE);
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM4 , ENABLE);
+#endif /* USE_STM3210B_EVAL */
+
+#if !defined(STM32L1XX_MD)
+ /* Configure USB pull-up */
+ 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);
+#endif /* STM32L1XX_MD */
+
+#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 */
+
+ USB_Cable_Config(DISABLE);
+
+ 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.
+* Return : None.
+*******************************************************************************/
+void Set_USBClock(void)
+{
+#ifdef STM32L1XX_MD
+ /* Enable USB clock */
+ 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.
+* 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.
+* 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_Interrupts_Config
+* Description : Configures the USB interrupts
+* Input : None.
+* Return : None.
+*******************************************************************************/
+void USB_Config(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+ NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
+
+#ifdef STM32L1XX_MD
+ 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 and configure the priority of the USB_HP IRQ Channel*/
+ NVIC_InitStructure.NVIC_IRQChannel = USB_HP_IRQn;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
+ NVIC_Init(&NVIC_InitStructure);
+
+ /* Enable the USB Wake-up interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = USB_FS_WKUP_IRQn;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+#else /* USE_STM3210B_EVAL or USE_STM3210E_EVAL */
+
+ /* Enable and configure the priority of the USB_LP IRQ Channel*/
+ 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 and configure the priority of the USB_HP IRQ Channel*/
+ NVIC_InitStructure.NVIC_IRQChannel = USB_HP_CAN1_TX_IRQn;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
+
+ /* Enable the USB Wake-up interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = USBWakeUp_IRQn;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
+ NVIC_Init(&NVIC_InitStructure);
+
+#endif /* STM32L1XX_MD */
+
+ /* Audio Components Interrupt configuration */
+ Audio_Config();
+}
+/*******************************************************************************
+* Function Name : USB_Interrupts_Config
+* Description : Configures the USB interrupts
+* Input : None.
+* Return : None.
+*******************************************************************************/
+void Audio_Config(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#if defined(USE_STM32L152_EVAL)
+ /* Enable the TIM2 Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = TIM6_IRQn;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+#elif defined(USE_STM3210B_EVAL)
+ /* Enable the TIM2 Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQn;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+#elif defined(USE_STM3210E_EVAL)
+ /* SPI2 IRQ Channel configuration */
+ NVIC_InitStructure.NVIC_IRQChannel = SPI2_IRQn;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+#endif /* USE_STM3210B_EVAL */
+}
+/*******************************************************************************
+* Function Name : USB_Cable_Config
+* Description : Software Connection/Disconnection of USB Cable
+* Input : None.
+* Return : Status
+*******************************************************************************/
+void USB_Cable_Config (FunctionalState NewState)
+{
+#ifdef STM32L1XX_MD
+ 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_MD */
+}
+
+/*******************************************************************************
+* Function Name : Speaker_Timer_Config
+* Description : Configure and enable the timer
+* Input : None.
+* Return : None.
+*******************************************************************************/
+void Speaker_Config(void)
+{
+#ifdef USE_STM32L152_EVAL
+ DAC_InitTypeDef DAC_InitStructure;
+ GPIO_InitTypeDef GPIO_InitStructure;
+ uint16_t TIM6ARRValue = 4000;
+
+ /* TIM6 and DAC clocks enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM6 | RCC_APB1Periph_DAC, ENABLE);
+
+ /* Enable GPIOA clock */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOA, ENABLE);
+
+ /* Configure DAC Channel1 and Channel2 as output */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4 | GPIO_Pin_5;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_40MHz;
+ GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL ;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* TIM6 Configuration */
+ TIM_DeInit(TIM6);
+
+ TIM6ARRValue = (uint32_t)(SystemCoreClock/22000); /* Audio Sample Rate = 22KHz */
+
+ /* Set the timer auto reload value dependent on the audio frequency */
+ TIM_SetAutoreload(TIM6, TIM6ARRValue); /* 22.KHz = 32MHz / 1454 */
+
+ /* TIM6 TRGO selection */
+ TIM_SelectOutputTrigger(TIM6, TIM_TRGOSource_Update);
+
+ /* Enable TIM6 update interrupt */
+ TIM_ITConfig(TIM6, TIM_IT_Update, ENABLE);
+
+ /* DAC deinitialize */
+ DAC_DeInit();
+ DAC_StructInit(&DAC_InitStructure);
+
+ /* Fill DAC InitStructure */
+ DAC_InitStructure.DAC_Trigger = DAC_Trigger_T6_TRGO;
+ DAC_InitStructure.DAC_WaveGeneration = DAC_WaveGeneration_None;
+ DAC_InitStructure.DAC_OutputBuffer = DAC_OutputBuffer_Disable;
+
+/* DAC Channel1: 8bit right---------------------------------------------------*/
+ /* DAC Channel1 Init */
+ DAC_Init(DAC_Channel_1, &DAC_InitStructure);
+
+ /* Enable DAC Channel1 */
+ DAC_Cmd(DAC_Channel_1, ENABLE);
+
+ /* Start TIM6 */
+ TIM_Cmd(TIM6, ENABLE);
+
+#elif defined(USE_STM3210B_EVAL)
+ GPIO_InitTypeDef GPIO_InitStructure;
+ TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+ TIM_OCInitTypeDef TIM_OCInitStructure;
+
+ /* Configure PB.08 as alternate function (TIM4_OC3) */
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_8;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+ /* TIM4 configuration */
+ TIM_TimeBaseStructure.TIM_Prescaler = 0x00; /* TIM4CLK = 72 MHz */
+ TIM_TimeBaseStructure.TIM_Period = 0xFF; /* PWM frequency : 281.250KHz*/
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0x0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+ TIM_TimeBaseInit(TIM4, &TIM_TimeBaseStructure);
+ /* TIM4's Channel3 in PWM1 mode */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
+ TIM_OCInitStructure.TIM_Pulse = 0x7F; /* Duty cycle: 50%*/
+ TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High; /* set high polarity */
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OC3Init(TIM4, &TIM_OCInitStructure);
+ TIM_OC3PreloadConfig(TIM4, TIM_OCPreload_Enable);
+
+ /* TIM2 configuration */
+ TIM_TimeBaseStructure.TIM_Period = TIM2ARRValue;
+ TIM_TimeBaseStructure.TIM_Prescaler = 0x00; /* TIM2CLK = 72 MHz */
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0x0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+ TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure);
+ /* Output Compare Inactive Mode configuration: Channel1 */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_Timing;
+ TIM_OCInitStructure.TIM_Pulse = 0x0;
+ TIM_OC1Init(TIM2, &TIM_OCInitStructure);
+ TIM_OC1PreloadConfig(TIM2, TIM_OCPreload_Disable);
+
+ /* Start TIM4 */
+ TIM_Cmd(TIM4, ENABLE);
+
+ /* Start TIM2 */
+ TIM_Cmd(TIM2, ENABLE);
+
+ /* Enable TIM2 update interrupt */
+ TIM_ITConfig(TIM2, TIM_IT_Update, ENABLE);
+
+#else
+ /* Configure the initialization parameters */
+ I2S_GPIO_Config();
+ I2S_Config(I2S_Standard_Phillips, I2S_MCLKOutput_Enable, I2S_AudioFreq_22k);
+ CODEC_Config(OutputDevice_SPEAKER, I2S_Standard_Phillips, I2S_MCLKOutput_Enable, 0x08);
+ SPI_I2S_ITConfig(SPI2, SPI_I2S_IT_TXE, ENABLE);
+
+#endif
+}
+
+/*******************************************************************************
+* 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, &Speaker_StringSerial[2] , 8);
+ IntToUnicode (Device_Serial1, &Speaker_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/Audio_Speaker/src/i2s_codec.c b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/i2s_codec.c
new file mode 100644
index 0000000..6dd4168
--- /dev/null
+++ b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/i2s_codec.c
@@ -0,0 +1,1573 @@
+/**
+ ******************************************************************************
+ * @file i2s_codec.c
+ * @author MCD Application Team
+ * @version V4.0.0
+ * @date 21-January-2013
+ * @brief This file includes the I2S Codec driver for AK4343 Audio Codec.
+ ******************************************************************************
+ * @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 "i2s_codec.h"
+
+/* Private typedef -----------------------------------------------------------*/
+typedef enum
+{
+ LittleEndian,
+ BigEndian
+}Endianness;
+
+/* Private define ------------------------------------------------------------*/
+
+/* Audio file header size */
+#define HEADER_SIZE 100
+
+/* EvalBoard pins related to the Codec */
+#define Codec_PDN_GPIO GPIOG
+#define Codec_PDN_Pin GPIO_Pin_11
+
+/* Uncomment this line to enable verifying data sent to codec after each write operation */
+//#define VERIFY_WRITTENDATA
+
+/* The 7 bits Codec address mask */
+#define CODEC_ADDRESS 0x27 /* b00100111 */
+
+/* Audio Parsing Constants */
+#define ChunkID 0x52494646 /* correspond to the letters 'RIFF' */
+#define FileFormat 0x57415645 /* correspond to the letters 'WAVE' */
+#define FormatID 0x666D7420 /* correspond to the letters 'fmt ' */
+#define DataID 0x64617461 /* correspond to the letters 'data' */
+#define FactID 0x66616374 /* correspond to the letters 'fact' */
+
+#define WAVE_FORMAT_PCM 0x01
+#define FormatChunkSize 0x10
+#define Channel_MONO 0x01
+#define Channel_STEREO 0x02
+
+#define SampleRate_8000 8000
+#define SampleRate_16000 16000
+#define SampleRate_22050 22050
+#define SampleRate_44100 44100
+#define SampleRate_48000 48000
+#define Bits_Per_Sample_8 8
+#define Bits_Per_Sample_16 16
+
+#define DUMMY_DATA 0x1111
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Audio Frequency value */
+uint16_t i2saudiofreq = I2S_AudioFreq_8k;
+
+/* Header Table containing the audio file information */
+uint8_t HeaderTabIndex = 0;
+uint8_t AudioFileHeader[HEADER_SIZE];
+
+/* Audio Codec variables */
+__IO uint32_t AudioFileAddress = 0x0;
+uint32_t AudioDataLength = 0;//7000000;
+uint32_t DataStartAddr = 0x0;
+__IO uint32_t AudioDataIndex = 0;
+static __IO uint32_t AudioReplay = 0xFFFF;
+static uint32_t AudioReplayCount = 0xFFFF;
+static __IO uint32_t SendDummyData = 0;
+static __IO uint32_t AudioPlayStatus = AudioPlayStatus_STOPPED;
+static uint32_t CurrentOutputDevice = OutputDevice_HEADPHONE;
+static uint8_t CurrentVolume = DEFAULT_VOL;
+static uint32_t errorcode = 0xFF;
+static __IO uint32_t monovar = 0, tmpvar = 0;
+
+/* Wave details names table */
+WAVE_FormatTypeDef WAVE_Format;
+__IO ErrorCode WaveFileStatus = Unvalid_RIFF_ID;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+static void NVIC_Config(void);
+static void I2C_Config(void);
+static uint32_t CODEC_WriteRegister(uint32_t RegisterAddr, uint32_t RegisterValue);
+static uint32_t CODEC_ReadRegister(uint32_t RegisterAddr);
+static uint32_t ReadUnit(uint8_t NbrOfBytes, Endianness BytesFormat);
+uint32_t AudioFile_Init(void);
+
+/*******************************************************************************
+* Function Name : I2S_CODEC_Init
+* Description : Initializes the I2S audio codec according parameters configured
+* by I2S_CODEC_Config function.
+* Input : - OutputDevice: Could be OutoutDevice_SPEAKER or
+* OutoutDevice_HEADPHONE.
+* - Address: Specifies the location of the audio file in the memory.
+* Output : None
+* Return : - 0: if all initializations are OK.
+* - 1: if memory initialization failed (LD2 is turned on).
+* - 2: if audio file initialization failed (LD2 is turned on).
+* - 3: if Codec initialization failed (LD1 is turned on).
+*******************************************************************************/
+uint32_t I2S_CODEC_Init(uint32_t OutputDevice, uint32_t Address)
+{
+ uint32_t count = 0;
+
+ /* Set the audio file address */
+ AudioFileAddress = (uint32_t) Address;
+
+ /* Configure I2S interrupt Channel */
+ NVIC_Config();
+
+ /* Configure the I2S2, I2C1 and GPIOF pins */
+ I2S_GPIO_Config();
+
+ /* Read the Audio file to extract the audio data length and frequency */
+ errorcode = AudioFile_Init();
+
+ if (errorcode < 3)
+ {
+ /* Turn on LD2 connected to PF.07 */
+ GPIO_SetBits(GPIOF, GPIO_Pin_7);
+
+ return errorcode;
+ }
+
+ /* Configure the SPI2 peripheral in I2S mode */
+ I2S_Config(I2S_STANDARD, I2S_MCLKOUTPUT, i2saudiofreq);
+
+ /* Set the current output device */
+ CurrentOutputDevice = OutputDevice;
+
+ /* Codec Configuration via I2C interface */
+ count = CODEC_Config(OutputDevice, I2S_STANDARD, I2S_MCLKOUTPUT, DEFAULT_VOL);
+
+ if (count != 0)
+ {
+ /* Turn on LD1 connected to PF.06 */
+ GPIO_SetBits(GPIOF, GPIO_Pin_6);
+
+ return 3;
+ }
+
+ /* Turn on LD4 connected to PF.09 */
+ GPIO_SetBits(GPIOF, GPIO_Pin_9);
+
+ return 0; /* Configuration is OK */
+}
+
+/*******************************************************************************
+* Function Name : I2S_CODEC_ReplayConfig
+* Description : Set AudioReplay variable value .
+* Input : Repetions: Number of repetitions
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2S_CODEC_ReplayConfig(uint32_t Repetions)
+{
+ /* Audio Replay number set by user */
+ AudioReplay = Repetions;
+
+ /* Audio Replays number remaining (if AudioReplay != 0) */
+ AudioReplayCount = Repetions;
+}
+
+/*******************************************************************************
+* Function Name : I2S_CODEC_Play
+* Description : Plays the audio file.
+* Input : - AudioStartPosition: Address from which the wave data begin
+* Output : None
+* Return : AudioDataIndex value.
+*******************************************************************************/
+uint32_t I2S_CODEC_Play(uint32_t AudioStartPosition)
+{
+ /* Send the read command to the media */
+ Media_StartReadSequence(AudioFileAddress + AudioStartPosition + 1);
+
+ /* Set Playing status to inform other modules about the codec status */
+ SetVar_AudioPlayStatus(AudioPlayStatus_PLAYING);
+
+ /* Enable the I2S2 TXE Interrupt => Generate the clocks*/
+ SPI_I2S_ITConfig(SPI2, SPI_I2S_IT_TXE, ENABLE);
+
+ return AudioDataIndex;
+}
+
+/*******************************************************************************
+* Function Name : I2S_CODEC_Pause
+* Description : Pause playing the audio file.
+* Input : None
+* Output : None
+* Return : Current Position.
+*******************************************************************************/
+uint32_t I2S_CODEC_Pause()
+{
+ /* Disable the I2S2 TXE Interrupt => stop the clocks*/
+ SPI_I2S_ITConfig(SPI2, SPI_I2S_IT_TXE, DISABLE);
+
+ /* Set Paused status to inform other modules about the codec status */
+ SetVar_AudioPlayStatus(AudioPlayStatus_PAUSED);
+
+ /* Reset local variables */
+ monovar = 0;
+ tmpvar = 0;
+
+ if (WAVE_Format.NumChannels == Channel_MONO)
+ {
+ /* Force the parity of the address */
+ AudioDataIndex &= 0xFFFFFFFE;
+ }
+ /* Return the current data pointer position */
+ return AudioDataIndex;
+}
+
+/*******************************************************************************
+* Function Name : I2S_CODEC_Stop
+* Description : Stop playing the audio file, reset the pointer and power off
+* : the Codec.
+* Input : None
+* Output : None
+* Return : 0 if operation complete.
+*******************************************************************************/
+uint32_t I2S_CODEC_Stop()
+{
+ /* Disable the I2S2 TXE Interrupt => stop the clocks */
+ SPI_I2S_ITConfig(SPI2, SPI_I2S_IT_TXE, DISABLE);
+
+ /* Reinitialize the audio data pointer */
+ AudioDataIndex = 0;
+
+ /* Power off the Codec to save power and protect the Codec itself */
+ I2S_CODEC_PowerDown(CodecPowerDown_SW);
+
+ /* Set Paused status to inform other modules about the codec status */
+ SetVar_AudioPlayStatus(AudioPlayStatus_STOPPED);
+
+ /* Reset local variables */
+ monovar = 0;
+ tmpvar = 0;
+
+ return 0;
+}
+
+/*******************************************************************************
+* Function Name : I2S_CODEC_ControlVolume
+* Description : Controls the audio volume.
+* Input : - direction: VolumeDirection_HIGH (0xF) to increase the volume,
+* : VolumeDirection_LOW (0xA) to decrease the volume or
+* : VolumeDirection_LEVEL (0x0) to set a defined level of volume.
+* : - Volume: the step of volume increasing/decreasing (when direction == 0)
+* : or the volume level to be set (when direction != 0).
+* Output : None
+* Return : 0-> correct communication, else wrong communication
+*******************************************************************************/
+uint32_t I2S_CODEC_ControlVolume(uint32_t direction, uint8_t Volume)
+{
+ uint32_t counter = 0;
+
+ if (direction == VolumeDirection_HIGH)
+ {
+ /* Check if the volume high limit is reached */
+ if (CurrentVolume < VOLStep)
+ {
+ CurrentVolume = 0;
+ }
+ else
+ {
+ /* Save the current volume level */
+ CurrentVolume = CODEC_ReadRegister(0x0A) - Volume;
+ }
+
+ /* Set the new volume */
+ counter += CODEC_WriteRegister(0x0A, CurrentVolume);
+ }
+ else if (direction == VolumeDirection_LOW)
+ {
+ /* Check if the volume low limit is reached */
+ if (CurrentVolume > (0xFF - VOLStep))
+ {
+ CurrentVolume = 0xFF;
+ }
+ else
+ {
+ /* Save the current volume level */
+ CurrentVolume = CODEC_ReadRegister(0x0A) + Volume;
+ }
+
+ /* Set the new volume */
+ counter += CODEC_WriteRegister(0x0A, CurrentVolume);
+ }
+ else if (direction == VolumeDirection_LEVEL)
+ {
+ CurrentVolume = Volume;
+
+ /* Set the new volume */
+ counter += CODEC_WriteRegister(0x0A, Volume);
+ }
+ else
+ {
+ return 0xFF; //Error verifying the Codec registers
+ }
+
+ return counter;
+}
+
+/*******************************************************************************
+* Function Name : I2S_CODEC_Mute
+* Description : Enable or disable the MUTE mode by software
+* Input : - Command: could be MUTEON to mute sound or MUTEOFF to restore volume
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void I2S_CODEC_Mute(uint32_t Command)
+{
+ uint32_t tmp = 0;
+
+ /* Read the current value of the config register number 0x0E */
+ tmp = CODEC_ReadRegister(0x0E);
+
+ /* Set the Mute mode */
+ if (Command == MUTE_ON)
+ {
+ tmp |= 0x20;
+ }
+ else /* MUTE_OFF Disable the Mute */
+ {
+ tmp &= 0xD1;
+ }
+
+ /* Write back the CODEC config register w/the new value */
+ CODEC_WriteRegister(0x0E, tmp);
+}
+
+/*******************************************************************************
+* Function Name : I2S_CODEC_ForwardPlay
+* Description : Forward function.
+* Input : - Step: number of steps forward
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void I2S_CODEC_ForwardPlay(uint32_t Step)
+{
+ /* Pause Playing the audio file */
+ I2S_CODEC_Pause();
+
+ /* Increment the Audio pointer */
+ IncrementVar_AudioDataIndex((AudioDataLength / 100) * Step);
+
+ /* Insure the index parity */
+ AudioDataIndex &= 0xFFFFFFFE;
+
+ /* Resume playing from the new position */
+ I2S_CODEC_Play((GetVar_AudioDataIndex()));
+}
+
+/*******************************************************************************
+* Function Name : I2S_CODEC_RewindPlay
+* Description : Rewind function.
+* Input : - Step: number of steps back
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void I2S_CODEC_RewindPlay(uint32_t Step)
+{
+ /* Pause Playing the audio file */
+ I2S_CODEC_Pause();
+
+ /* Increment the Audio pointer */
+ DecrementVar_AudioDataIndex((AudioDataLength / 100) * Step);
+
+ /* Insure the index parity */
+ AudioDataIndex &= 0xFFFFFFFE;
+
+ /* Resume playing from the new position */
+ I2S_CODEC_Play((GetVar_AudioDataIndex()));
+}
+
+/*******************************************************************************
+* Function Name : I2S_CODEC_PowerDown
+* Description : Power down the Audio Codec.
+* Input : - CodecPowerDown_Mode: could be CodecPowerDown_SW for power down
+* : after communication, CodecPowerDown_HW simply shut down the codec
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2S_CODEC_PowerDown(uint32_t CodecPowerDown_Mode)
+{
+ if (CodecPowerDown_Mode == CodecPowerDown_SW)
+ {
+ /* Power down the DAC and the speaker (PMDAC and PMSPK bits)*/
+ (void)CODEC_WriteRegister(0x00, 0x40);
+ /* Power down the VCOM*/
+ (void)CODEC_WriteRegister(0x00, 0x00);
+ }
+ else /* CodecPowerDown_HW */
+ {
+ /* Power Down the Codec */
+ GPIO_ResetBits(Codec_PDN_GPIO, Codec_PDN_Pin);
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2S_CODEC_Reset
+* Description : Reset the Audio Codec.
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void I2S_CODEC_Reset(void)
+{
+ /* Power Down the Codec */
+ GPIO_ResetBits(Codec_PDN_GPIO, Codec_PDN_Pin);
+
+ /* wait for a delay to allow registers erasing */
+ delay(0xFF);
+
+ /* Power On the Codec after the power off => all registers are reinitialized*/
+ GPIO_SetBits(Codec_PDN_GPIO, Codec_PDN_Pin);
+
+}
+
+/*******************************************************************************
+* Function Name : I2S_CODEC_SpeakerHeadphoneSwap
+* Description : Configure the Audio Codec output to Speaker or Headphone while
+* : the audio wave is Paused or stopped.
+* Input : - OutputDevice: could be OutputDevice_Speaker or OutputDevice_Headphone
+* or OutputDevice_Both .
+* - Address: Specifies the audio file location in the memory.
+* Output : None.
+* Return : - 0: Operation done without failures.
+* - 1: Memory failure occur.
+* - 2: Audio file initialization failure occur
+* - 3: I2C communication failure occur
+*******************************************************************************/
+uint32_t I2S_CODEC_SpeakerHeadphoneSwap(uint32_t OutputDevice, uint32_t Address)
+{
+ uint32_t tmp_pointer = 0, err = 0;
+
+ /* Reset all Codec Registers */
+ I2S_CODEC_Reset();
+
+ /* Save the current position */
+ tmp_pointer = GetVar_AudioDataIndex();
+
+ /* Reinitialize the CODEC with the new configured parameters */
+ err = I2S_CODEC_Init(OutputDevice, Address);
+
+ if (err != 0)
+ {
+ return err;
+ }
+
+ /* Restore the last pointer position */
+ AudioDataIndex = tmp_pointer;
+
+ /* Restore the last volume level */
+ I2S_CODEC_ControlVolume(VolumeDirection_LEVEL, CurrentVolume);
+
+ /* Play from current position */
+ I2S_CODEC_Play(tmp_pointer);
+
+ return 0;
+}
+
+/*******************************************************************************
+* Function Name : I2S_CODEC_UpdateStatus
+* Description : Check if STOP or PAUSE command are generated and performs the
+* : relative action (STOP or PAUSE playing)
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void I2S_CODEC_UpdateStatus(void)
+{
+ /* STOP command is generated => Stop playing the audio file */
+ if ((GetVar_AudioPlayStatus() == AudioPlayStatus_STOPPED) && (SPI_I2S_GetFlagStatus(SPI2, I2S_FLAG_CHSIDE) == SET))
+ {
+ I2S_CODEC_Stop();
+ }
+
+ /* PAUSE Command is generated => PAUSE playing the audio File */
+ if ((GetVar_AudioPlayStatus() == AudioPlayStatus_PAUSED) && (SPI_I2S_GetFlagStatus(SPI2, I2S_FLAG_CHSIDE) == SET))
+ {
+ I2S_CODEC_Pause();
+ }
+}
+
+/*******************************************************************************
+* Function Name : GetVar_DataStartAddr
+* Description : returns DataStartAddr variable value (used by stm32f10x_it.c file).
+* Input : None
+* Output : None
+* Return : AudioDataIndex
+*******************************************************************************/
+uint32_t GetVar_DataStartAddr(void)
+{
+ return DataStartAddr;
+}
+
+
+/*******************************************************************************
+* Function Name : GetVar_CurrentVolume
+* Description : returns CurrentVolume variable value (used by extern files).
+* Input : None
+* Output : None
+* Return : CurrentVolume
+*******************************************************************************/
+uint8_t GetVar_CurrentVolume(void)
+{
+ return CurrentVolume;
+}
+
+/*******************************************************************************
+* Function Name : I2S_CODEC_WaveParsing
+* Description : Checks the format of the .WAV file and gets information about
+* the audio format. This is done by reading the value of a
+* number of parameters stored in the file header and comparing
+* these to the values expected authenticates the format of a
+* standard .WAV file (44 bytes will be read). If it is a valid
+* .WAV file format, it continues reading the header to determine
+* the audio format such as the sample rate and the sampled data
+* size. If the audio format is supported by this application,
+* it retrieves the audio format in WAVE_Format structure and
+* returns a zero value. Otherwise the function fails and the
+* return value is nonzero.In this case, the return value specifies
+* the cause of the function fails. The error codes that can be
+* returned by this function are declared in the header file.
+* Input : None
+* Output : None
+* Return : Zero value if the function succeed, otherwise it return
+* a nonzero value which specifies the error code.
+*******************************************************************************/
+ErrorCode I2S_CODEC_WaveParsing(uint8_t* HeaderTab)
+{
+ uint32_t Temp = 0x00;
+ uint32_t ExtraFormatBytes = 0;
+
+ /* Initialize the HeaderTabIndex variable */
+ HeaderTabIndex = 0;
+
+ /* Read chunkID, must be 'RIFF' ----------------------------------------------*/
+ Temp = ReadUnit(4, BigEndian);
+ if (Temp != ChunkID)
+ {
+ return(Unvalid_RIFF_ID);
+ }
+ /* Read the file length ----------------------------------------------------*/
+ WAVE_Format.RIFFchunksize = ReadUnit(4, LittleEndian);
+
+ /* Read the file format, must be 'WAVE' ------------------------------------*/
+ Temp = ReadUnit(4, BigEndian);
+ if (Temp != FileFormat)
+ {
+ return(Unvalid_WAVE_Format);
+ }
+ /* Read the format chunk, must be 'fmt ' -----------------------------------*/
+ Temp = ReadUnit(4, BigEndian);
+ if (Temp != FormatID)
+ {
+ return(Unvalid_FormatChunk_ID);
+ }
+ /* Read the length of the 'fmt' data, must be 0x10 -------------------------*/
+ Temp = ReadUnit(4, LittleEndian);
+ if (Temp != 0x10)
+ {
+ ExtraFormatBytes = 1;
+ }
+ /* Read the audio format, must be 0x01 (PCM) -------------------------------*/
+ WAVE_Format.FormatTag = ReadUnit(2, LittleEndian);
+ if (WAVE_Format.FormatTag != WAVE_FORMAT_PCM)
+ {
+ return(Unsupporetd_FormatTag);
+ }
+ /* Read the number of channels: 0x02->Stereo 0x01->Mono --------------------*/
+ WAVE_Format.NumChannels = ReadUnit(2, LittleEndian);
+
+ /* Read the Sample Rate ----------------------------------------------------*/
+ WAVE_Format.SampleRate = ReadUnit(4, LittleEndian);
+
+ /* Update the I2S_AudioFreq value according to the .WAV file Sample Rate */
+ switch (WAVE_Format.SampleRate)
+ {
+ case SampleRate_8000 :
+ i2saudiofreq = I2S_AudioFreq_8k;
+ break;
+ case SampleRate_16000:
+ i2saudiofreq = I2S_AudioFreq_16k;
+ break;
+ case SampleRate_22050:
+ i2saudiofreq = I2S_AudioFreq_22k;
+ break;
+ case SampleRate_44100:
+ i2saudiofreq = I2S_AudioFreq_44k;
+ break;
+ case SampleRate_48000:
+ i2saudiofreq = I2S_AudioFreq_48k;
+ break;
+ default:
+ return(Unsupporetd_Sample_Rate);
+ }
+ /* Read the Byte Rate ------------------------------------------------------*/
+ WAVE_Format.ByteRate = ReadUnit(4, LittleEndian);
+
+ /* Read the block alignment ------------------------------------------------*/
+ WAVE_Format.BlockAlign = ReadUnit(2, LittleEndian);
+
+ /* Read the number of bits per sample --------------------------------------*/
+ WAVE_Format.BitsPerSample = ReadUnit(2, LittleEndian);
+ if (WAVE_Format.BitsPerSample != Bits_Per_Sample_16)
+ {
+ return(Unsupporetd_Bits_Per_Sample);
+ }
+ /* If there are Extra format bytes, these bytes will be defined in "Fact Chunk" */
+ if (ExtraFormatBytes == 1)
+ {
+ /* Read th Extra format bytes, must be 0x00 ------------------------------*/
+ Temp = ReadUnit(2, LittleEndian);
+ if (Temp != 0x00)
+ {
+ return(Unsupporetd_ExtraFormatBytes);
+ }
+ /* Read the Fact chunk, must be 'fact' -----------------------------------*/
+ Temp = ReadUnit(4, BigEndian);
+ if (Temp != FactID)
+ {
+ return(Unvalid_FactChunk_ID);
+ }
+ /* Read Fact chunk data Size ---------------------------------------------*/
+ Temp = ReadUnit(4, LittleEndian);
+
+ /* Set the index to start reading just after the header end */
+ HeaderTabIndex += Temp;
+ }
+ /* Read the Data chunk, must be 'data' -------------------------------------*/
+ Temp = ReadUnit(4, BigEndian);
+ if (Temp != DataID)
+ {
+ return(Unvalid_DataChunk_ID);
+ }
+ /* Read the number of sample data ------------------------------------------*/
+ WAVE_Format.DataSize = ReadUnit(4, LittleEndian);
+
+ /* Set the data pointer at the beginning of the effective audio data */
+ DataStartAddr += HeaderTabIndex;
+
+ return(Valid_WAVE_File);
+}
+
+/*******************************************************************************
+* Function Name : GetVar_AudioDataIndex
+* Description : returns AudioDataIndex variable value (used by stm32f10x_it.c file).
+* Input : None
+* Output : None
+* Return : AudioDataIndex
+*******************************************************************************/
+uint32_t GetVar_AudioDataIndex(void)
+{
+ return AudioDataIndex;
+}
+
+/*******************************************************************************
+* Function Name : SetVar_AudioDataIndex
+* Description : Sets AudioDataIndex variable value (used by stm32f10x_it.c file).
+* Input : None
+* Output : None
+* Return : AudioDataIndex
+*******************************************************************************/
+void SetVar_AudioDataIndex(uint32_t value)
+{
+ AudioDataIndex = value;
+}
+
+/*******************************************************************************
+* Function Name : IncrementVar_AudioDataIndex
+* Description : Increment the AudioDataIndex variable.
+* Input : - IncrementNumber: number of incrementations.
+* Output : None
+* Return : None
+*******************************************************************************/
+void IncrementVar_AudioDataIndex(uint32_t IncrementNumber)
+{
+ AudioDataIndex += (uint32_t)IncrementNumber;
+
+ if (AudioDataIndex >= AudioDataLength)
+ {
+ ResetVar_AudioDataIndex();
+ Decrement_AudioReplay();
+ }
+}
+
+/*******************************************************************************
+* Function Name : DecrementVar_AudioDataIndex
+* Description : Set the AudioDataIndex variable to 1.
+* Input : None
+* Output : None
+* Return : None.
+*******************************************************************************/
+void DecrementVar_AudioDataIndex(uint32_t DecrementNumber)
+{
+ if (DecrementNumber >= AudioDataIndex)
+ {
+ ResetVar_AudioDataIndex();
+ }
+ else
+ {
+ AudioDataIndex -= (uint32_t)DecrementNumber;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ResetVar_AudioDataIndex
+* Description : Reset the AudioDataIndex variable.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ResetVar_AudioDataIndex(void)
+{
+ AudioDataIndex = DataStartAddr;
+
+ /* Send the read command to the media */
+ Media_StartReadSequence(AudioFileAddress + DataStartAddr + 1);
+}
+
+/*******************************************************************************
+* Function Name : GetVar_SendDummyData
+* Description : returns SendDummyData variable value (used by stm32f10x_it.c file).
+* Input : None
+* Output : None
+* Return : SendDummyData
+*******************************************************************************/
+uint32_t GetVar_SendDummyData(void)
+{
+ return SendDummyData;
+}
+
+/*******************************************************************************
+* Function Name : SetVar_SendDummyData
+* Description : Set the SendDummyData variable to 1.
+* Input : None
+* Output : None
+* Return : SendDummyData
+*******************************************************************************/
+uint32_t SetVar_SendDummyData(void)
+{
+ SendDummyData = (uint32_t)0x1;
+
+ return SendDummyData;
+}
+
+/*******************************************************************************
+* Function Name : ResetVar_SendDummyData
+* Description : Reset the SendDummyData variable to 0.
+* Input : None
+* Output : None
+* Return : SendDummyData
+*******************************************************************************/
+uint32_t ResetVar_SendDummyData(void)
+{
+ SendDummyData = (uint32_t)0;
+
+ return SendDummyData;
+}
+
+/*******************************************************************************
+* Function Name : GetVar_AudioPlayStatus
+* Description : returns AudioPlayStatus variable value (used by stm32f10x_it.c file).
+* Input : None
+* Output : None
+* Return : AudioPlayStatus value.
+*******************************************************************************/
+uint32_t GetVar_AudioPlayStatus(void)
+{
+ return AudioPlayStatus;
+}
+
+/*******************************************************************************
+* Function Name : SetVar_AudioPlayStatus
+* Description : Set the AudioDataIndex variable to Status.
+* Input : Status: could be AudioPlayStatus_STOPPED, AudioPlayStatus_PLAYING
+* : or AudioPlayStatus_PAUSED.
+* Output : None
+* Return : AudioPlayStatus value.
+*******************************************************************************/
+uint32_t SetVar_AudioPlayStatus(uint32_t Status)
+{
+ AudioPlayStatus = (uint32_t)Status;
+
+ return AudioPlayStatus;
+}
+
+/*******************************************************************************
+* Function Name : GetVar_AudioReplay
+* Description : returns AudioReplay variable value.
+* Input : None
+* Output : None
+* Return : AudioReplay value.
+*******************************************************************************/
+uint32_t GetVar_AudioReplay(void)
+{
+ return AudioReplay;
+}
+
+/*******************************************************************************
+* Function Name : SetVar_AudioReplay
+* Description : Decrement the AudioReplayCount variable if AudioReplay is different
+* : from zero (infinite replaying).
+* Input : None.
+* Output : None
+* Return : AudioPlayStatus value.
+*******************************************************************************/
+void Decrement_AudioReplay(void)
+{
+ if (AudioReplay != 0)
+ {
+ AudioReplayCount--;
+
+ if (AudioReplayCount == 0)
+ {
+ /* Command the Stop of the audio playing */
+ SetVar_AudioPlayStatus(AudioPlayStatus_STOPPED);
+
+ /* Reset the counter */
+ AudioReplayCount = AudioReplay;
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : GetVar_CurrentOutputDevice
+* Description : Get the current output device selected .
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+uint32_t GetVar_CurrentOutputDevice(void)
+{
+ return CurrentOutputDevice;
+}
+
+/*******************************************************************************
+* Function Name : GetVar_AudioDataLength
+* Description : Get the current audio file data length .
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+uint32_t GetVar_AudioDataLength(void)
+{
+ return AudioDataLength;
+}
+
+/*******************************************************************************
+* Function Name : GetVar_i2saudiofreq
+* Description : Get the current audio frequency .
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+uint16_t GetVar_i2saudiofreq(void)
+{
+ return i2saudiofreq;
+}
+
+/*******************************************************************************
+* Function Name : AudioFile_Init
+* Description : Initializes the SPI_Flash and returns the Wavadatalength variable.
+* Input : None
+* Output : None
+* Return : - The length of the wave file read from the SPI_Flash
+* - 1 if an error occurred when initializing the memory.
+* - 2 if an error occurred on the audio file initialization.
+*******************************************************************************/
+uint32_t AudioFile_Init(void)
+{
+ uint32_t err = 0;
+
+ /* Initialize the media support */
+ err = Media_Init();
+
+ /* Check if Memory initialization is OK */
+ if (err != 0)
+ {
+ return 1;
+ }
+
+ /* Read a Byte buffer and store it in the Header table*/
+ Media_BufferRead(AudioFileHeader, AudioFileAddress, HEADER_SIZE);
+
+ /* Read and check the audio file Header */
+ WaveFileStatus = I2S_CODEC_WaveParsing(AudioFileHeader);
+
+ /* Check if the selected file is a correct wave file */
+ if (WaveFileStatus == Valid_WAVE_File)
+ {
+ /* Read and set the audio data length (/!\ data are counted as BYTES /!\) */
+ AudioDataLength = WAVE_Format.DataSize ;
+
+ /* Read and set the audio frequency */
+ i2saudiofreq = (uint16_t)WAVE_Format.SampleRate;
+
+ /* Return the audio file length */
+ return AudioDataLength;
+ }
+ else /* Wrong wave file */
+ {
+ return 2;
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Config
+* Description : Configure the I2Ss NVIC channel.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+static void NVIC_Config(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+ /* SPI2 IRQ Channel configuration */
+ NVIC_InitStructure.NVIC_IRQChannel = SPI2_IRQn;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Config
+* Description : Initializes the GPIO pins used by the codec application.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2S_GPIO_Config(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Enable GPIOB, GPIOC and AFIO clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB | RCC_APB2Periph_GPIOC | RCC_APB2Periph_GPIOG |
+ RCC_APB2Periph_GPIOF | RCC_APB2Periph_AFIO, ENABLE);
+
+ /* I2S2 SD, CK and WS pins configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12 | GPIO_Pin_13 | GPIO_Pin_15;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+ /* I2S2 MCK pin configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+
+ /* LEDs pins configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIOF, &GPIO_InitStructure);
+
+ /* I2C1 SCL PB6 and SDA PB7 pins configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_OD;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+ /* Enable the I2C1 APB1 clock */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1, ENABLE);
+
+ /* Turn Off All LEDs */
+ GPIO_ResetBits(GPIOF, GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9);
+ GPIO_ResetBits(Codec_PDN_GPIO, Codec_PDN_Pin);
+
+ /* Configure the Codec PDN pin as output PushPull */
+ GPIO_InitStructure.GPIO_Pin = Codec_PDN_Pin;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(Codec_PDN_GPIO, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : I2S_Config
+* Description : Configure the I2S Peripheral.
+* Input : - Standard: I2S_Standard_Phillips, I2S_Standard_MSB or I2S_Standard_LSB
+* - MCLKOutput: I2S_MCLKOutput_Enable or I2S_MCLKOutput_Disable
+* - AudioFreq: I2S_AudioFreq_8K, I2S_AudioFreq_16K, I2S_AudioFreq_22K,
+* I2S_AudioFreq_44K or I2S_AudioFreq_48K
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2S_Config(uint16_t Standard, uint16_t MCLKOutput, uint16_t AudioFreq)
+{
+ I2S_InitTypeDef I2S_InitStructure;
+
+ /* Enable I2S2 APB1 clock */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE);
+
+ /* Deinitialize SPI2 peripheral */
+ SPI_I2S_DeInit(SPI2);
+
+ /* I2S2 peripheral configuration */
+ I2S_InitStructure.I2S_Mode = I2S_Mode_MasterTx;
+ I2S_InitStructure.I2S_Standard = Standard;
+ I2S_InitStructure.I2S_DataFormat = I2S_DataFormat_16b;
+ I2S_InitStructure.I2S_MCLKOutput = MCLKOutput;
+ I2S_InitStructure.I2S_AudioFreq = AudioFreq;
+ I2S_InitStructure.I2S_CPOL = I2S_CPOL_Low;
+ I2S_Init(SPI2, &I2S_InitStructure);
+
+ /* Disable the I2S2 TXE Interrupt */
+ SPI_I2S_ITConfig(SPI2, SPI_I2S_IT_TXE, DISABLE);
+
+ /* Enable the SPI2/I2S2 peripheral */
+ I2S_Cmd(SPI2, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : I2C_Config
+* Description : Configure the I2C1 Peripheral.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+static void I2C_Config(void)
+{
+ I2C_InitTypeDef I2C_InitStructure;
+
+ /* I2C1 configuration */
+ I2C_InitStructure.I2C_Mode = I2C_Mode_I2C;
+ I2C_InitStructure.I2C_DutyCycle = I2C_DutyCycle_2;
+ I2C_InitStructure.I2C_OwnAddress1 = 0x33;
+ I2C_InitStructure.I2C_Ack = I2C_Ack_Enable;
+ I2C_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
+ I2C_InitStructure.I2C_ClockSpeed = 200000;
+ I2C_Init(I2C1, &I2C_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : CODEC_Config
+* Description : Configure the Codec in Headphone mode.
+* Input : - OutputDevice: OutputDeviceHEADPHONE or OutputDeviceSPEAKER
+* : - I2S_Standard: I2S communication standard could be I2S_Standard_Phillips
+* : I2S_Standard_MSB or I2S_Standard_LSB.
+* : - I2S_MCLKOutput: could be I2S_MCLKOutput_
+* : - Volume:
+* Output : None
+* Return : 0-> correct communication, else wrong communication
+*******************************************************************************/
+uint32_t CODEC_Config(uint16_t OutputDevice, uint16_t I2S_Standard, uint16_t I2S_MCLKOutput, uint8_t Volume)
+{
+ uint32_t Standard = 0, counter = 0, PLLMode = 0;
+
+ /* Command the sending of dummy data */
+ ResetVar_SendDummyData();
+
+ /* Reset the Codec Registers */
+ I2S_CODEC_Reset();
+
+ /* Determine the I2S standard used */
+ switch (I2S_Standard)
+ {
+ case I2S_Standard_Phillips:
+ Standard = 0x03;
+ break;
+ case I2S_Standard_MSB:
+ Standard = 0x02;
+ break;
+ default :
+ Standard = 0x01;
+ break;
+ }
+
+ /* HEADPHONE codec configuration */
+ if ((OutputDevice & OutputDevice_HEADPHONE) != 0)
+ {
+ /* PLL Slave SD/WS reference mode ----------------------*/
+ if (I2S_MCLKOutput == I2S_MCLKOutput_Disable)
+ {
+ /* set the PLLMode variable */
+ PLLMode = 0x1;
+
+ /* Phillips(0x03)/MSB(0x02)/LSB(0x01) mode with PLL */
+ counter += CODEC_WriteRegister(0x04, (Standard | 0x20));
+ /* MCKI input frequency = 256.Fs */
+ counter += CODEC_WriteRegister(0x05, 0x03);
+ /* VCOM Power up (PMVCM bit)*/
+ counter += CODEC_WriteRegister(0x00, 0x40);
+ /* Enable PLL*/
+ counter += CODEC_WriteRegister(0x01, 0x01);
+ }
+ /* Ext Slave mode with no PLL --------------------------*/
+ else
+ {
+ /* Reset the PLL mode variable */
+ PLLMode = 0;
+
+ /* Phillips(0x03)/MSB(0x02)/LSB(0x01) mode with no PLL */
+ counter += CODEC_WriteRegister(0x04, Standard);
+ /* MCKI input frequency = 256.Fs */
+ counter += CODEC_WriteRegister(0x05, 0x00);
+ /* VCOM Power up (PMVCM bit)*/
+ counter += CODEC_WriteRegister(0x00, 0x40);
+ }
+
+ /* Command the sending of dummy data */
+ SetVar_SendDummyData();
+
+ /* Enable the I2S2 TXE Interrupt => Generate the clocks*/
+ SPI_I2S_ITConfig(SPI2, SPI_I2S_IT_TXE, ENABLE);
+
+ /* Extra Configuration (of the ALC) */
+ counter += CODEC_WriteRegister(0x06, 0x3C );
+ counter += CODEC_WriteRegister(0x08, 0xE1 );
+ counter += CODEC_WriteRegister(0x0B, 0x00 );
+ counter += CODEC_WriteRegister(0x07, 0x20 );
+ counter += CODEC_WriteRegister(0x09, 0xC1 );
+ counter += CODEC_WriteRegister(0x0C, 0xC1 );
+
+ /* MCKI is 256.Fs with no PLL */
+ counter += CODEC_WriteRegister(0x05, 0x00 );
+ /* Switch control from DAC to Headphone */
+ counter += CODEC_WriteRegister(0x0F, 0x09 );
+ /* Bass Boost and Deemphasis enable */
+ counter += CODEC_WriteRegister(0x0E, 0x18 );
+ /* Left Channel Digital Volume control */
+ counter += CODEC_WriteRegister(0x0A, Volume);
+ /* Right Channel Digital Volume control */
+ counter += CODEC_WriteRegister(0x0D, Volume);
+ /* Power up MIN and DAC (PMMIN and PMDAC bits)*/
+ counter += CODEC_WriteRegister(0x00, 0x74);
+ /* Enable Slave mode and Left/Right HP lines*/
+ counter += CODEC_WriteRegister(0x01, (0x30 | PLLMode));
+ /* Exit HP mute mode */
+ counter += CODEC_WriteRegister(0x01, (0x70 | PLLMode));
+ }
+
+ /* SPEAKER codec configuration */
+ if ((OutputDevice & OutputDevice_SPEAKER) != 0)
+ {
+ /* PLL Slave SD/WS reference mode ----------------------*/
+ if (I2S_MCLKOutput == I2S_MCLKOutput_Disable)
+ {
+ /* Phillips(0x03)/MSB(0x02)/LSB(0x01) mode with no PLL */
+ counter += CODEC_WriteRegister(0x04, (Standard | 0x20));
+ /* MCKI input frequency = 256.Fs */
+ counter += CODEC_WriteRegister(0x05, 0x03);
+ /* VCOM Power up (PMVCM bit)*/
+ counter += CODEC_WriteRegister(0x00, 0x40);
+ /* Enable PLL*/
+ counter += CODEC_WriteRegister(0x01, 0x01);
+ }
+ /* Ext Slave mode with no PLL --------------------------*/
+ else
+ {
+ /* Phillips(0x03)/MSB(0x02)/LSB(0x01) mode with no PLL */
+ counter += CODEC_WriteRegister(0x04, Standard);
+ /* MCKI input frequency = 256.Fs */
+ counter += CODEC_WriteRegister(0x05, 0x00);
+ /* VCOM Power up (PMVCM bit)*/
+ counter += CODEC_WriteRegister(0x00, 0x40);
+ }
+
+ /* Command the sending of dummy data */
+ SetVar_SendDummyData();
+
+ /* Enable the I2S2 TXE Interrupt => Generate the clocks*/
+ SPI_I2S_ITConfig(SPI2, SPI_I2S_IT_TXE, ENABLE);
+
+ /* ReSelect the MCKI frequency (FS0-1 bits): 256.Fs */
+ counter += CODEC_WriteRegister(0x05, 0x02 );
+ /* Set up the path "DAC->Speaker-Amp" with no power save (DACS and SPPSN bits) */
+ counter += CODEC_WriteRegister(0x02, 0x20 );
+ /* Speaker Gain (SPKG0-1 bits): Gain=+10.65dB(ALC off)/+12.65(ALC on) */
+ counter += CODEC_WriteRegister(0x03, 0x10);
+
+ /* Extra Configuration (of the ALC) */
+ counter += CODEC_WriteRegister(0x06, 0x3C );
+ counter += CODEC_WriteRegister(0x08, 0xE1 );
+ counter += CODEC_WriteRegister(0x0B, 0x00 );
+ counter += CODEC_WriteRegister(0x07, 0x20 );
+ counter += CODEC_WriteRegister(0x09, 0x91 );
+ counter += CODEC_WriteRegister(0x0C, 0x91 );
+
+ /* Left Channel Digital Volume control */
+ counter += CODEC_WriteRegister(0x0A, Volume);
+ /* Right Channel Digital Volume control */
+ counter += CODEC_WriteRegister(0x0D, Volume);
+ /* Power up Speaker and DAC (PMSPK and PMDAC bits)*/
+ counter += CODEC_WriteRegister(0x00, 0x54);
+ /* Set up the path "DAC -> Speaker-Amp" with no power save */
+ counter += CODEC_WriteRegister(0x02, 0xA0 /*0xA1*/);
+ }
+
+ /* Disable the I2S2 TXE Interrupt */
+ SPI_I2S_ITConfig(SPI2, SPI_I2S_IT_TXE, DISABLE);
+
+ /* Disable the sending of Dummy data */
+ ResetVar_SendDummyData();
+
+ /* Return the counter value */
+ return counter;
+}
+
+/*******************************************************************************
+* Function Name : CODEC_WriteRegister
+* Description : Writes a value in a register of the audio Codec through I2C.
+* Input : - RegisterAddr: The target register address (between 00x and 0x24)
+* : - RegisterValue: The target register value to be written
+* : - Verify: 0-> Don't verify the written data, 1-> Verify the written data
+* Output : None
+* Return : - 0 -> Correct write operation
+* : - !0 -> Incorrect write operation
+*******************************************************************************/
+uint32_t CODEC_WriteRegister(uint32_t RegisterAddr, uint32_t RegisterValue)
+{
+ uint32_t read_verif = 0;
+
+ /* Reset all I2C2 registers */
+ I2C_SoftwareResetCmd(I2C1, ENABLE);
+ I2C_SoftwareResetCmd(I2C1, DISABLE);
+
+ /* Enable the I2C1 peripheral */
+ I2C_Cmd(I2C1, ENABLE);
+
+ /* Configure the I2C peripheral */
+ I2C_Config();
+
+ /* Begin the config sequence */
+ I2C_GenerateSTART(I2C1, ENABLE);
+
+ /* Test on EV5 and clear it */
+ while (!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_MODE_SELECT))
+ {}
+ /* Transmit the slave address and enable writing operation */
+ I2C_Send7bitAddress(I2C1, CODEC_ADDRESS, I2C_Direction_Transmitter);
+
+ /* Test on EV6 and clear it */
+ while (!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED))
+ {}
+ /* Transmit the first address for r/w operations */
+ I2C_SendData(I2C1, RegisterAddr);
+
+ /* Test on EV8 and clear it */
+ while (!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_BYTE_TRANSMITTED))
+ {}
+
+ /* Prepare the register value to be sent */
+ I2C_SendData(I2C1, RegisterValue);
+
+ /* Test on EV8 and clear it */
+ while (!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_BYTE_TRANSMITTED))
+ {}
+
+ /* End the configuration sequence */
+ I2C_GenerateSTOP(I2C1, ENABLE);
+
+ /* Verify (if needed) that the loaded data is correct */
+#ifdef VERIFY_WRITTENDATA
+ /* Read the just written register*/
+ read_verif = CODEC_ReadRegister(RegisterAddr);
+
+ /* Load the register and verify its value */
+ if (read_verif != RegisterValue)
+ {
+ /* Control data wrongly transferred */
+ read_verif = 1;
+ }
+ else
+ {
+ /* Control data correctly transferred */
+ read_verif = 0;
+ }
+#endif
+
+ /* Return the verifying value: 0 (Passed) or 1 (Failed) */
+ return read_verif;
+}
+
+/*******************************************************************************
+* Function Name : CODEC_ReadRegister
+* Description : Reads a register of the audio Codec through I2C.
+* Input : - RegisterAddr: The target register address (between 00x and 0x24)
+* Output : None
+* Return : The value of the read register
+*******************************************************************************/
+uint32_t CODEC_ReadRegister(uint32_t RegisterAddr)
+{
+ uint32_t tmp = 0;
+
+ /* Disable the I2C1 peripheral */
+ I2C_Cmd(I2C1, DISABLE);
+
+ /* Reset all I2C2 registers */
+ I2C_SoftwareResetCmd(I2C1, ENABLE);
+ I2C_SoftwareResetCmd(I2C1, DISABLE);
+
+ /* Configure the I2C peripheral */
+ I2C_Config();
+
+ /* Enable the I2C peripheral */
+ I2C_GenerateSTART(I2C1, ENABLE);
+
+ /* Test on EV5 and clear it */
+ while (!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_MODE_SELECT))
+ {}
+
+ /* Disable Acknowledgement */
+ I2C_AcknowledgeConfig(I2C1, DISABLE);
+
+ /* Transmit the slave address and enable writing operation */
+ I2C_Send7bitAddress(I2C1, CODEC_ADDRESS, I2C_Direction_Transmitter);
+
+ /* Test on EV6 and clear it */
+ while (!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED))
+ {}
+
+ /* Transmit the first address for r/w operations */
+ I2C_SendData(I2C1, RegisterAddr);
+
+ /* Test on EV8 and clear it */
+ while (!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_BYTE_TRANSMITTED))
+ {}
+
+ /* Regenerate a start condition */
+ I2C_GenerateSTART(I2C1, ENABLE);
+
+ /* Test on EV5 and clear it */
+ while (!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_MODE_SELECT))
+ {}
+
+ /* Transmit the slave address and enable writing operation */
+ I2C_Send7bitAddress(I2C1, CODEC_ADDRESS, I2C_Direction_Receiver);
+
+ /* Test on EV6 and clear it */
+ while (!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED))
+ {}
+
+ /* Test on EV7 and clear it */
+ while (!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_BYTE_RECEIVED))
+ {}
+
+ /* End the configuration sequence */
+ I2C_GenerateSTOP(I2C1, ENABLE);
+
+ /* Load the register value */
+ tmp = I2C_ReceiveData(I2C1);
+
+ /* Disable Acknowledgement */
+ I2C_AcknowledgeConfig(I2C1, ENABLE);
+
+ /* Return the read value */
+ return tmp;
+}
+
+/*******************************************************************************
+* Function Name : ReadUnit
+* Description : Reads a number of bytes from the SPI Flash and reorder them
+* in Big or little endian.
+* Input : - NbrOfBytes : number of bytes to read.
+* This parameter must be a number between 1 and 4.
+* - ReadAddr : external memory address to read from.
+* - Endians : specifies the bytes endianness.
+* This parameter can be one of the following values:
+* - LittleEndian
+* - BigEndian
+* Output : None
+* Return : Bytes read from the SPI Flash.
+*******************************************************************************/
+static uint32_t ReadUnit(uint8_t NbrOfBytes, Endianness BytesFormat)
+{
+ uint32_t index = 0;
+ uint32_t Temp = 0;
+
+ if (BytesFormat == LittleEndian)
+ {
+ for (index = 0; index < NbrOfBytes; index++)
+ {
+ Temp |= AudioFileHeader[HeaderTabIndex++] << (index * 8);
+ }
+ }
+ else
+ {
+ for (index = NbrOfBytes; index != 0; index--)
+ {
+ Temp |= AudioFileHeader[HeaderTabIndex++] << ((index - 1) * 8);
+ }
+ }
+
+ return Temp;
+}
+
+/*******************************************************************************
+* Function Name : I2S_CODEC_MediaReadHalfWord
+* Description : Read one half word from the media (SPI_Flash/NOR/NAND memories..)
+* Input : - Offset: the address offset for read operation
+* Output : None.
+* Return : Data read from the media memory.
+*******************************************************************************/
+uint16_t Media_ReadHalfWord(uint32_t Offset)
+{
+ /* Test if the left channel is to be sent */
+ if (monovar == 0)
+ {
+ /* Enable the FSMC that share a pin w/ I2C1 (LBAR) */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_FSMC, ENABLE);
+
+ tmpvar = (*(__IO uint16_t *) (AudioFileAddress + Offset));
+
+ /* Disable the FSMC that share a pin w/ I2C1 (LBAR) */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_FSMC, DISABLE);
+
+ /* Increment the mono variable only if the file is in mono format */
+ if (WAVE_Format.NumChannels == Channel_MONO)
+ {
+ /* Increment the monovar variable */
+ monovar++;
+ }
+
+ /* Return the read value */
+ return tmpvar;
+ }
+ /* Right channel to be sent in mono format */
+ else
+ {
+ /* Reset the monovar variable */
+ monovar = 0;
+
+ /* Return the previous read data in mono format */
+ return tmpvar;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2S_CODEC_MediaReadByte
+* Description : Read one byte from the media (SPI_Flash/NOR/NAND memories..)
+* Input : - Offset: the address offset for read operation
+* Output : None.
+* Return : Data read from the media memory.
+*******************************************************************************/
+uint8_t Media_ReadByte(uint32_t Offset)
+{
+ uint8_t tmp = 0;
+
+ /* Enable the FSMC that share a pin w/ I2C1 (LBAR) */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_FSMC, ENABLE);
+
+ /* Read data from the specified location */
+ tmp = (*(__IO uint8_t *) (AudioFileAddress + Offset));
+
+ /* Disable the FSMC that share a pin w/ I2C1 (LBAR) */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_FSMC, DISABLE);
+
+ return tmp;
+}
+
+/*******************************************************************************
+* Function Name : Media_Init
+* Description : Read one byte from the media (SPI_Flash/NOR/NAND memories..)
+* Input : - Offset: the address offset for read operation
+* Output : None.
+* Return : - 0 if initialization is OK
+* - 1 if initialization failed..
+*******************************************************************************/
+uint32_t Media_Init(void)
+{
+ return 0;
+}
+
+/*******************************************************************************
+* Function Name : Media_BufferRead
+* Description : Read a buffer from the memory media
+* Input : - pBuffer: Destination buffer address
+* : - ReadAddr: start reading position
+* : - NumByteToRead: size of the buffer to read
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void Media_BufferRead(uint8_t* pBuffer, uint32_t ReadAddr, uint16_t NumByteToRead)
+{
+ /* Enable the FSMC that share a pin w/ I2C1 (LBAR) */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_FSMC, ENABLE);
+
+ /* Read the data */
+ while (NumByteToRead--)
+ {
+ *pBuffer++ = *(__IO uint8_t *)ReadAddr++;
+ }
+
+ /* Disable the FSMC that share a pin w/ I2C1 (LBAR) */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_FSMC, DISABLE);
+}
+
+/*******************************************************************************
+* Function Name : Media_StartReadSequence
+* Description : Initialize reading sequence on the media.
+* Input : - ReadAddr: start reading position
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void Media_StartReadSequence(uint32_t ReadAddr)
+{
+ /* This function could be used for memories needing a start read sequence
+ like SPI_Flash memory */
+}
+
+/*******************************************************************************
+* Function Name : I2S_CODEC_DataTransfer
+* Description : Sends the audio data using the SPI2 peripheral and checks the
+* : audio playing status (if a command (Pause/Stop) is pending
+* : the playing status is updated). If the TXE flag interrupt
+* : is used to synchronize data sending, this function should be
+* : called in the SPI2 ISR.
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void I2S_CODEC_DataTransfer(void)
+{
+ /* Audio codec configuration section -------------------------------------*/
+ if (GetVar_SendDummyData() == 1)
+ {
+ /* Send a dummy data just to generate the I2S clock */
+ SPI_I2S_SendData(SPI2, DUMMY_DATA);
+ }
+ /* Audio codec communication section -------------------------------------*/
+ else
+ {
+ /* Send the data read from the memory */
+ SPI_I2S_SendData(SPI2, (Media_ReadHalfWord(AudioDataIndex)));
+
+ /* Increment the index */
+ IncrementVar_AudioDataIndex(WAVE_Format.NumChannels);
+
+ /* Check and update the stream playing status */
+ I2S_CODEC_UpdateStatus();
+ }
+}
+/*******************************************************************************
+* Function Name : delay
+* Description : Inserts a delay time.
+* Input : nCount: specifies the delay time length
+* Output : None
+* Return : The length of the wave file read from the SPI_Flash
+*******************************************************************************/
+void delay(__IO uint32_t nCount)
+{
+ for (; nCount != 0; nCount--);
+}
+#endif
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/main.c b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/main.c
new file mode 100644
index 0000000..b58c6c3
--- /dev/null
+++ b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/main.c
@@ -0,0 +1,87 @@
+/**
+ ******************************************************************************
+ * @file main.c
+ * @author MCD Application Team
+ * @version V4.0.0
+ * @date 21-January-2013
+ * @brief Audio Speaker 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_desc.h"
+#include "usb_prop.h"
+#include "usb_pwr.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Extern variables ----------------------------------------------------------*/
+extern uint32_t MUTE_DATA;
+extern uint16_t In_Data_Offset;
+extern uint16_t Out_Data_Offset;
+extern uint8_t Stream_Buff[24];
+extern uint8_t IT_Clock_Sent;
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : main.
+* Description : Main routine.
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+int main(void)
+{
+ Set_System();
+ Set_USBClock();
+ USB_Config();
+ USB_Init();
+ Speaker_Config();
+ 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/Audio_Speaker/src/stm32_it.c b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/stm32_it.c
new file mode 100644
index 0000000..74ba641
--- /dev/null
+++ b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/stm32_it.c
@@ -0,0 +1,336 @@
+/**
+ ******************************************************************************
+ * @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_istr.h"
+#include "usb_lib.h"
+#include "usb_pwr.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define DUMMYDATA 0x1111
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+uint16_t Out_Data_Offset;
+extern uint16_t In_Data_Offset;
+extern uint8_t Stream_Buff[24];
+extern uint32_t MUTE_DATA;
+
+/* 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 PendSV_Handler 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_HP_CAN1_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN1 TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN1_TX_IRQHandler(void)
+{
+ CTR_HP();
+}
+
+/*******************************************************************************
+* Function Name : USB_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+#if defined(STM32L1XX_MD)
+void USB_LP_IRQHandler(void)
+#else
+void USB_LP_CAN1_RX0_IRQHandler(void)
+#endif
+{
+ USB_Istr();
+}
+
+#ifdef USE_STM3210B_EVAL
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+ if (TIM_GetITStatus(TIM2, TIM_IT_Update) != RESET)
+ {
+ /* Clear TIM2 update interrupt */
+ TIM_ClearITPendingBit(TIM2, TIM_IT_Update);
+
+ if ((Out_Data_Offset < In_Data_Offset) && ((uint8_t)(MUTE_DATA) == 0))
+ {
+ TIM_SetCompare3(TIM4, Stream_Buff[Out_Data_Offset]);
+ Out_Data_Offset++;
+ }
+ }
+}
+#endif /* USE_STM3210B_EVAL */
+
+#if defined (USE_STM3210E_EVAL)
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+ static uint8_t channel = 0;
+
+ if ((SPI_I2S_GetITStatus(SPI2, SPI_I2S_IT_TXE) == SET))
+ {
+ /* Audio codec configuration section */
+ if (GetVar_SendDummyData() == 1)
+ {
+ /* Send a dummy data just to generate the I2S clock */
+ SPI_I2S_SendData(SPI2, DUMMYDATA);
+ }
+
+ else if ((Out_Data_Offset < In_Data_Offset) && ((uint8_t)(MUTE_DATA) == 0))
+ {
+ if ((channel++) & 1)
+ {
+ SPI_I2S_SendData(SPI2, (uint16_t)Stream_Buff[Out_Data_Offset++]);
+ }
+ else
+ {
+ SPI_I2S_SendData(SPI2, (uint16_t)Stream_Buff[Out_Data_Offset]);
+ }
+ }
+ }
+}
+
+#endif /* USE_STM3210E_EVAL */
+
+#if defined(STM32L1XX_MD)
+
+/**
+ * @brief This function handles TIM6 global interrupt request.
+ * @param None
+ * @retval None
+ */
+void TIM6_IRQHandler(void)
+{
+ if (TIM_GetITStatus(TIM6, TIM_IT_Update) != RESET)
+ {
+ /* Clear TIM6 update interrupt */
+ TIM_ClearITPendingBit(TIM6, TIM_IT_Update);
+
+ if ((Out_Data_Offset < In_Data_Offset) && ((uint8_t)(MUTE_DATA) == 0))
+ {
+ /* Set DAC Channel1 DHR register */
+ DAC_SetChannel1Data(DAC_Align_8b_R, Stream_Buff[Out_Data_Offset]);
+ Out_Data_Offset++;
+ }
+ }
+}
+
+#endif /* STM32L1XX_XD */
+
+/*******************************************************************************
+* Function Name : USB_HP_IRQHandler
+* Description : This function handles USB High Priority interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_IRQHandler(void)
+{
+ CTR_HP();
+}
+
+/*******************************************************************************
+* Function Name : USB_WakeUP_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+#if defined(STM32L1XX_MD)
+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/Audio_Speaker/src/system_stm32f10x.c b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/system_stm32f10x.c
new file mode 100644
index 0000000..3686a2f
--- /dev/null
+++ b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/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/Audio_Speaker/src/system_stm32l1xx.c b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/system_stm32l1xx.c
new file mode 100644
index 0000000..1be659d
--- /dev/null
+++ b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/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/Audio_Speaker/src/usb_desc.c b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/usb_desc.c
new file mode 100644
index 0000000..7f56731
--- /dev/null
+++ b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/usb_desc.c
@@ -0,0 +1,251 @@
+/**
+ ******************************************************************************
+ * @file usb_desc.c
+ * @author MCD Application Team
+ * @version V4.0.0
+ * @date 21-January-2013
+ * @brief Descriptors for Audio Speaker Demo
+ ******************************************************************************
+ * @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_desc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private constants----------------------------------------------------------*/
+/* USB Standard Device Descriptor */
+const uint8_t Speaker_DeviceDescriptor[] =
+ {
+ SPEAKER_SIZ_DEVICE_DESC, /* bLength */
+ USB_DEVICE_DESCRIPTOR_TYPE, /* bDescriptorType */
+ 0x00, /* 2.00 */ /* bcdUSB */
+ 0x02,
+ 0x00, /* bDeviceClass */
+ 0x00, /* bDeviceSubClass */
+ 0x00, /* bDeviceProtocol */
+ 0x40, /* bMaxPacketSize 40 */
+ 0x83, /* idVendor */
+ 0x04,
+ 0x30, /* idProduct = 0x5730*/
+ 0x57,
+ 0x00, /* 2.00 */ /* bcdDevice */
+ 0x02,
+ 1, /* iManufacturer */
+ 2, /* iProduct */
+ 3, /* iSerialNumber */
+ 0x01 /* bNumConfigurations */
+ };
+
+/* USB Configuration Descriptor */
+/* All Descriptors (Configuration, Interface, Endpoint, Class, Vendor */
+const uint8_t Speaker_ConfigDescriptor[] =
+ {
+ /* Configuration 1 */
+ 0x09, /* bLength */
+ USB_CONFIGURATION_DESCRIPTOR_TYPE, /* bDescriptorType */
+ 0x6D, /* wTotalLength 110 bytes*/
+ 0x00,
+ 0x02, /* bNumInterfaces */
+ 0x01, /* bConfigurationValue */
+ 0x00, /* iConfiguration */
+ 0xC0, /* bmAttributes Self Powred*/
+ 0x32, /* bMaxPower = 100 mA*/
+ /* 09 byte*/
+
+ /* USB Speaker Standard interface descriptor */
+ SPEAKER_SIZ_INTERFACE_DESC_SIZE, /* bLength */
+ USB_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */
+ 0x00, /* bInterfaceNumber */
+ 0x00, /* bAlternateSetting */
+ 0x00, /* bNumEndpoints */
+ USB_DEVICE_CLASS_AUDIO, /* bInterfaceClass */
+ AUDIO_SUBCLASS_AUDIOCONTROL, /* bInterfaceSubClass */
+ AUDIO_PROTOCOL_UNDEFINED, /* bInterfaceProtocol */
+ 0x00, /* iInterface */
+ /* 09 byte*/
+
+ /* USB Speaker Class-specific AC Interface Descriptor */
+ SPEAKER_SIZ_INTERFACE_DESC_SIZE, /* bLength */
+ AUDIO_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */
+ AUDIO_CONTROL_HEADER, /* bDescriptorSubtype */
+ 0x00, /* 1.00 */ /* bcdADC */
+ 0x01,
+ 0x27, /* wTotalLength = 39*/
+ 0x00,
+ 0x01, /* bInCollection */
+ 0x01, /* baInterfaceNr */
+ /* 09 byte*/
+
+ /* USB Speaker Input Terminal Descriptor */
+ AUDIO_INPUT_TERMINAL_DESC_SIZE, /* bLength */
+ AUDIO_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */
+ AUDIO_CONTROL_INPUT_TERMINAL, /* bDescriptorSubtype */
+ 0x01, /* bTerminalID */
+ 0x01, /* wTerminalType AUDIO_TERMINAL_USB_STREAMING 0x0101 */
+ 0x01,
+ 0x00, /* bAssocTerminal */
+ 0x01, /* bNrChannels */
+ 0x00, /* wChannelConfig 0x0000 Mono */
+ 0x00,
+ 0x00, /* iChannelNames */
+ 0x00, /* iTerminal */
+ /* 12 byte*/
+
+ /* USB Speaker Audio Feature Unit Descriptor */
+ 0x09, /* bLength */
+ AUDIO_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */
+ AUDIO_CONTROL_FEATURE_UNIT, /* bDescriptorSubtype */
+ 0x02, /* bUnitID */
+ 0x01, /* bSourceID */
+ 0x01, /* bControlSize */
+ AUDIO_CONTROL_MUTE, /* bmaControls(0) */
+ 0x00, /* bmaControls(1) */
+ 0x00, /* iTerminal */
+ /* 09 byte*/
+
+ /*USB Speaker Output Terminal Descriptor */
+ 0x09, /* bLength */
+ AUDIO_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */
+ AUDIO_CONTROL_OUTPUT_TERMINAL, /* bDescriptorSubtype */
+ 0x03, /* bTerminalID */
+ 0x01, /* wTerminalType 0x0301*/
+ 0x03,
+ 0x00, /* bAssocTerminal */
+ 0x02, /* bSourceID */
+ 0x00, /* iTerminal */
+ /* 09 byte*/
+
+ /* USB Speaker Standard AS Interface Descriptor - Audio Streaming Zero Bandwith */
+ /* Interface 1, Alternate Setting 0 */
+ SPEAKER_SIZ_INTERFACE_DESC_SIZE, /* bLength */
+ USB_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */
+ 0x01, /* bInterfaceNumber */
+ 0x00, /* bAlternateSetting */
+ 0x00, /* bNumEndpoints */
+ USB_DEVICE_CLASS_AUDIO, /* bInterfaceClass */
+ AUDIO_SUBCLASS_AUDIOSTREAMING, /* bInterfaceSubClass */
+ AUDIO_PROTOCOL_UNDEFINED, /* bInterfaceProtocol */
+ 0x00, /* iInterface */
+ /* 09 byte*/
+
+ /* USB Speaker Standard AS Interface Descriptor - Audio Streaming Operational */
+ /* Interface 1, Alternate Setting 1 */
+ SPEAKER_SIZ_INTERFACE_DESC_SIZE, /* bLength */
+ USB_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */
+ 0x01, /* bInterfaceNumber */
+ 0x01, /* bAlternateSetting */
+ 0x01, /* bNumEndpoints */
+ USB_DEVICE_CLASS_AUDIO, /* bInterfaceClass */
+ AUDIO_SUBCLASS_AUDIOSTREAMING, /* bInterfaceSubClass */
+ AUDIO_PROTOCOL_UNDEFINED, /* bInterfaceProtocol */
+ 0x00, /* iInterface */
+ /* 09 byte*/
+
+ /* USB Speaker Audio Streaming Interface Descriptor */
+ AUDIO_STREAMING_INTERFACE_DESC_SIZE, /* bLength */
+ AUDIO_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */
+ AUDIO_STREAMING_GENERAL, /* bDescriptorSubtype */
+ 0x01, /* bTerminalLink */
+ 0x01, /* bDelay */
+ 0x02, /* wFormatTag AUDIO_FORMAT_PCM8 0x0002*/
+ 0x00,
+ /* 07 byte*/
+
+ /* USB Speaker Audio Type I Format Interface Descriptor */
+ 0x0B, /* bLength */
+ AUDIO_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */
+ AUDIO_STREAMING_FORMAT_TYPE, /* bDescriptorSubtype */
+ AUDIO_FORMAT_TYPE_I, /* bFormatType */
+ 0x01, /* bNrChannels */
+ 0x01, /* bSubFrameSize */
+ 8, /* bBitResolution */
+ 0x01, /* bSamFreqType */
+ 0xF0, /* tSamFreq 22000 = 0x55F0 */
+ 0x55,
+ 0x00,
+ /* 11 byte*/
+
+ /* Endpoint 1 - Standard Descriptor */
+ AUDIO_STANDARD_ENDPOINT_DESC_SIZE, /* bLength */
+ USB_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType */
+ 0x01, /* bEndpointAddress 1 out endpoint*/
+ USB_ENDPOINT_TYPE_ISOCHRONOUS, /* bmAttributes */
+ 0x16, /* wMaxPacketSize 22 bytes*/
+ 0x00,
+ 0x01, /* bInterval */
+ 0x00, /* bRefresh */
+ 0x00, /* bSynchAddress */
+ /* 09 byte*/
+
+ /* Endpoint - Audio Streaming Descriptor*/
+ AUDIO_STREAMING_ENDPOINT_DESC_SIZE, /* bLength */
+ AUDIO_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType */
+ AUDIO_ENDPOINT_GENERAL, /* bDescriptor */
+ 0x00, /* bmAttributes */
+ 0x00, /* bLockDelayUnits */
+ 0x00, /* wLockDelay */
+ 0x00,
+ /* 07 byte*/
+ };
+
+/* USB String Descriptor (optional) */
+const uint8_t Speaker_StringLangID[SPEAKER_SIZ_STRING_LANGID] =
+ {
+ 0x04,
+ 0x03,
+ 0x09,
+ 0x04
+ }
+ ; /* LangID = 0x0409: U.S. English */
+
+const uint8_t Speaker_StringVendor[SPEAKER_SIZ_STRING_VENDOR] =
+ {
+ SPEAKER_SIZ_STRING_VENDOR, /* Size of manufacturer string */
+ USB_STRING_DESCRIPTOR_TYPE, /* bDescriptorType*/
+ /* Manufacturer: "STMicroelectronics" */
+ 'S', 0, 'T', 0, 'M', 0, 'i', 0, 'c', 0, 'r', 0, 'o', 0, 'e', 0,
+ 'l', 0, 'e', 0, 'c', 0, 't', 0, 'r', 0, 'o', 0, 'n', 0, 'i', 0,
+ 'c', 0, 's', 0
+ };
+
+const uint8_t Speaker_StringProduct[SPEAKER_SIZ_STRING_PRODUCT] =
+ {
+ SPEAKER_SIZ_STRING_PRODUCT, /* bLength */
+ USB_STRING_DESCRIPTOR_TYPE, /* bDescriptorType */
+ 'S', 0, 'T', 0, 'M', 0, '3', 0, '2', 0, ' ', 0,
+ 'S', 0, 'p', 0, 'e', 0, 'a', 0, 'k', 0, 'e', 0, 'r', 0
+ };
+
+uint8_t Speaker_StringSerial[SPEAKER_SIZ_STRING_SERIAL] =
+ {
+ SPEAKER_SIZ_STRING_SERIAL, /* bLength */
+ USB_STRING_DESCRIPTOR_TYPE, /* bDescriptorType */
+ 'S', 0, 'T', 0, 'M', 0, '3', 0, '2', 0
+ };
+/* Extern variables ----------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Extern function prototypes ------------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/usb_istr.c b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/usb_istr.c
new file mode 100644
index 0000000..f5786a2
--- /dev/null
+++ b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/usb_istr.c
@@ -0,0 +1,248 @@
+/**
+ ******************************************************************************
+ * @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 ----------------------------------------------------------*/
+extern uint16_t In_Data_Offset;
+extern uint16_t Out_Data_Offset;
+/* 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 */
+
+/*******************************************************************************
+* Function Name : USB_Istr
+* Description : Start of frame callback function.
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void SOF_Callback(void)
+{
+ In_Data_Offset = 0;
+ Out_Data_Offset = 0;
+}
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/usb_pwr.c b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/usb_pwr.c
new file mode 100644
index 0000000..a2253a8
--- /dev/null
+++ b/thirdparty/STM32_USB-FS-Device_Lib_V4.0.0/Projects/Audio_Speaker/src/usb_pwr.c
@@ -0,0 +1,318 @@
+/**
+ ******************************************************************************
+ * @file usb_pwr.c
+ * @author MCD Application Team
+ * @version V4.0.0
+ * @date 21-January-2013
+ * @brief Connection/disconnection & power management
+ ******************************************************************************
+ * @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_conf.h"
+#include "usb_pwr.h"
+#include "hw_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+__IO uint32_t bDeviceState = UNCONNECTED; /* USB device status */
+__IO bool fSuspendEnabled = TRUE; /* true when suspend is possible */
+__IO uint32_t EP[8];
+
+struct
+{
+ __IO RESUME_STATE eState;
+ __IO uint8_t bESOFcnt;
+}
+ResumeS;
+
+__IO uint32_t remotewakeupon=0;
+
+/* Extern variables ----------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Extern function prototypes ------------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : PowerOn
+* Description :
+* Input : None.
+* Output : None.
+* Return : USB_SUCCESS.
+*******************************************************************************/
+RESULT PowerOn(void)
+{
+ uint16_t wRegVal;
+
+ /*** cable plugged-in ? ***/
+ USB_Cable_Config(ENABLE);
+
+ /*** CNTR_PWDN = 0 ***/
+ wRegVal = CNTR_FRES;
+ _SetCNTR(wRegVal);
+
+ /*** CNTR_FRES = 0 ***/
+ wInterrupt_Mask = 0;
+ _SetCNTR(wInterrupt_Mask);
+ /*** Clear pending interrupts ***/
+ _SetISTR(0);
+ /*** Set interrupt mask ***/
+ wInterrupt_Mask = CNTR_RESETM | CNTR_SUSPM | CNTR_WKUPM;
+ _SetCNTR(wInterrupt_Mask);
+
+ return USB_SUCCESS;
+}
+
+/*******************************************************************************
+* Function Name : PowerOff
+* Description : handles switch-off conditions
+* Input : None.
+* Output : None.
+* Return : USB_SUCCESS.
+*******************************************************************************/
+RESULT PowerOff()
+{
+ /* disable all interrupts and force USB reset */
+ _SetCNTR(CNTR_FRES);
+ /* clear interrupt status register */
+ _SetISTR(0);
+ /* Disable the Pull-Up*/
+ USB_Cable_Config(DISABLE);
+ /* switch-off device */
+ _SetCNTR(CNTR_FRES + CNTR_PDWN);
+ /* sw variables reset */
+ /* ... */
+
+ return USB_SUCCESS;
+}
+
+/*******************************************************************************
+* Function Name : Suspend
+* Description : sets suspend mode operating conditions
+* Input : None.
+* Output : None.
+* Return : USB_SUCCESS.
+*******************************************************************************/
+void Suspend(void)
+{
+ uint32_t i =0;
+ uint16_t wCNTR;
+ uint32_t tmpreg = 0;
+ __IO uint32_t savePWR_CR=0;
+ /* suspend preparation */
+ /* ... */
+
+ /*Store CNTR value */
+ wCNTR = _GetCNTR();
+
+ /* This a sequence to apply a force RESET to handle a robustness case */
+
+ /*Store endpoints registers status */
+ for (i=0;i<8;i++) EP[i] = _GetENDPOINT(i);
+
+ /* unmask RESET flag */
+ wCNTR|=CNTR_RESETM;
+ _SetCNTR(wCNTR);
+
+ /*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]);
+
+ /* Now it is safe to enter macrocell in suspend mode */
+ wCNTR |= CNTR_FSUSP;
+ _SetCNTR(wCNTR);
+
+ /* force low-power mode in the macrocell */
+ wCNTR = _GetCNTR();
+ wCNTR |= CNTR_LPMODE;
+ _SetCNTR(wCNTR);
+
+ /*prepare entry in low power mode (STOP mode)*/
+ /* Select the regulator state in STOP mode*/
+ savePWR_CR = PWR->CR;
+ tmpreg = PWR->CR;
+ /* Clear PDDS and LPDS bits */
+ tmpreg &= ((uint32_t)0xFFFFFFFC);
+ /* Set LPDS bit according to PWR_Regulator value */
+ tmpreg |= PWR_Regulator_LowPower;
+ /* Store the new value */
+ PWR->CR = tmpreg;
+ /* Set SLEEPDEEP bit of Cortex System Control Register */
+#if defined (STM32F30X) || defined (STM32F37X)
+ SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
+#else
+ SCB->SCR |= SCB_SCR_SLEEPDEEP;
+#endif
+
+ /* enter system in STOP mode, only when wakeup flag in not set */
+ if((_GetISTR()&ISTR_WKUP)==0)
+ {
+ __WFI();
+ /* Reset SLEEPDEEP bit of Cortex System Control Register */
+#if defined (STM32F30X) || defined (STM32F37X)
+ SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk);
+#else
+ SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP);
+#endif
+ }
+ else
+ {
+ /* Clear Wakeup flag */
+ _SetISTR(CLR_WKUP);
+ /* clear FSUSP to abort entry in suspend mode */
+ wCNTR = _GetCNTR();
+ wCNTR&=~CNTR_FSUSP;
+ _SetCNTR(wCNTR);
+
+ /*restore sleep mode configuration */
+ /* restore Power regulator config in sleep mode*/
+ PWR->CR = savePWR_CR;
+
+ /* Reset SLEEPDEEP bit of Cortex System Control Register */
+#if defined (STM32F30X) || defined (STM32F37X)
+ SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk);
+#else
+ SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP);
+#endif
+ }
+}
+
+/*******************************************************************************
+* Function Name : Resume_Init
+* Description : Handles wake-up restoring normal operations
+* Input : None.
+* Output : None.
+* Return : USB_SUCCESS.
+*******************************************************************************/
+void Resume_Init(void)
+{
+ uint16_t wCNTR;
+
+ /* ------------------ ONLY WITH BUS-POWERED DEVICES ---------------------- */
+ /* restart the clocks */
+ /* ... */
+
+ /* CNTR_LPMODE = 0 */
+ wCNTR = _GetCNTR();
+ wCNTR &= (~CNTR_LPMODE);
+ _SetCNTR(wCNTR);
+
+ /* restore full power */
+ /* ... on connected devices */
+ Leave_LowPowerMode();
+
+ /* reset FSUSP bit */
+ _SetCNTR(IMR_MSK);
+
+ /* reverse suspend preparation */
+ /* ... */
+
+}
+
+/*******************************************************************************
+* Function Name : Resume
+* Description : This is the state machine handling resume operations and
+* timing sequence. The control is based on the Resume structure
+* variables and on the ESOF interrupt calling this subroutine
+* without changing machine state.
+* Input : a state machine value (RESUME_STATE)
+* RESUME_ESOF doesn't change ResumeS.eState allowing
+* decrementing of the ESOF counter in different states.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void Resume(RESUME_STATE eResumeSetVal)
+{
+ uint16_t wCNTR;
+
+ if (eResumeSetVal != RESUME_ESOF)
+ ResumeS.eState = eResumeSetVal;
+ switch (ResumeS.eState)
+ {
+ case RESUME_EXTERNAL:
+ if (remotewakeupon ==0)
+ {
+ Resume_Init();
+ ResumeS.eState = RESUME_OFF;
+ }
+ else /* RESUME detected during the RemoteWAkeup signalling => keep RemoteWakeup handling*/
+ {
+ ResumeS.eState = RESUME_ON;
+ }
+ break;
+ case RESUME_INTERNAL:
+ Resume_Init();
+ ResumeS.eState = RESUME_START;
+ remotewakeupon = 1;
+ break;
+ case RESUME_LATER:
+ ResumeS.bESOFcnt = 2;
+ ResumeS.eState = RESUME_WAIT;
+ break;
+ case RESUME_WAIT:
+ ResumeS.bESOFcnt--;
+ if (ResumeS.bESOFcnt == 0)
+ ResumeS.eState = RESUME_START;
+ break;
+ case RESUME_START:
+ wCNTR = _GetCNTR();
+ wCNTR |= CNTR_RESUME;
+ _SetCNTR(wCNTR);
+ ResumeS.eState = RESUME_ON;
+ ResumeS.bESOFcnt = 10;
+ break;
+ case RESUME_ON:
+ ResumeS.bESOFcnt--;
+ if (ResumeS.bESOFcnt == 0)
+ {
+ wCNTR = _GetCNTR();
+ wCNTR &= (~CNTR_RESUME);
+ _SetCNTR(wCNTR);
+ ResumeS.eState = RESUME_OFF;
+ remotewakeupon = 0;
+ }
+ break;
+ case RESUME_OFF:
+ case RESUME_ESOF:
+ default:
+ ResumeS.eState = RESUME_OFF;
+ break;
+ }
+}
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/