diff --git a/stm32f0xx_conf.h b/stm32f0xx_conf.h
deleted file mode 100644
--- a/stm32f0xx_conf.h
+++ /dev/null
@@ -1,81 +0,0 @@
-/**
- ******************************************************************************
- * @file stm32F0xx_conf.h
- * @author MCD Application Team
- * @version V1.0.0
- * @date 23-March-2012
- * @brief Library configuration file.
- ******************************************************************************
- * @attention
- *
- *
© COPYRIGHT 2012 STMicroelectronics
- *
- * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
- * You may not use this file except in compliance with the License.
- * You may obtain a copy of the License at:
- *
- * http://www.st.com/software_license_agreement_liberty_v2
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- *
- ******************************************************************************
- */
-
-/* Define to prevent recursive inclusion -------------------------------------*/
-#ifndef __STM32F0XX_CONF_H
-#define __STM32F0XX_CONF_H
-
-/* Includes ------------------------------------------------------------------*/
-/* Comment the line below to disable peripheral header file inclusion */
-/* #include "stm32f0xx_adc.h" */
-#include "stm32f0xx_cec.h"
-#include "stm32f0xx_crc.h"
-#include "stm32f0xx_comp.h"
-#include "stm32f0xx_dac.h"
-#include "stm32f0xx_dbgmcu.h"
-#include "stm32f0xx_dma.h"
-#include "stm32f0xx_exti.h"
-#include "stm32f0xx_flash.h"
-#include "stm32f0xx_gpio.h"
-#include "stm32f0xx_syscfg.h"
-#include "stm32f0xx_i2c.h"
-#include "stm32f0xx_iwdg.h"
-#include "stm32f0xx_pwr.h"
-#include "stm32f0xx_rcc.h"
-#include "stm32f0xx_rtc.h"
-#include "stm32f0xx_spi.h"
-#include "stm32f0xx_tim.h"
-#include "stm32f0xx_usart.h"
-#include "stm32f0xx_wwdg.h"
-#include "stm32f0xx_misc.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */
-
-/* Exported types ------------------------------------------------------------*/
-/* Exported constants --------------------------------------------------------*/
-/* Uncomment the line below to expanse the "assert_param" macro in the
- Standard Peripheral Library drivers code */
-/* #define USE_FULL_ASSERT 1 */
-/* Exported macro ------------------------------------------------------------*/
-#ifdef USE_FULL_ASSERT
-
-/**
- * @brief The assert_param macro is used for function's parameters check.
- * @param expr: If expr is false, it calls assert_failed function which reports
- * the name of the source file and the source line number of the call
- * that failed. If expr is true, it returns no value.
- * @retval None
- */
- #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
-/* Exported functions ------------------------------------------------------- */
- void assert_failed(uint8_t* file, uint32_t line);
-#else
- #define assert_param(expr) ((void)0)
-#endif /* USE_FULL_ASSERT */
-
-#endif /* __STM32F0XX_CONF_H */
-
-/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
-
diff --git a/stm32f0xx_it.h b/stm32f0xx_it.h
--- a/stm32f0xx_it.h
+++ b/stm32f0xx_it.h
@@ -1,66 +1,58 @@
-/**
- ******************************************************************************
- * @file stm32f0xx_it.h
- * @author MCD Application Team
- * @version V1.0.0
- * @date 29-July-2013
- * @brief This file contains the headers of the interrupt handlers.
- ******************************************************************************
- * @attention
- *
- * © COPYRIGHT 2013 STMicroelectronics
- *
- * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
- * You may not use this file except in compliance with the License.
- * You may obtain a copy of the License at:
- *
- * http://www.st.com/software_license_agreement_liberty_v2
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- *
- ******************************************************************************
- */
-
-/* Define to prevent recursive inclusion -------------------------------------*/
-#ifndef __STM32F0xx_IT_H
-#define __STM32F0xx_IT_H
-
-#ifdef __cplusplus
- extern "C" {
-#endif
-
-/* Includes ------------------------------------------------------------------*/
-#include "stm32f0xx.h"
-#include "platform_config.h"
-
-
-/* Exported types ------------------------------------------------------------*/
-/* Exported constants --------------------------------------------------------*/
-/* Exported macro ------------------------------------------------------------*/
-/* Exported functions ------------------------------------------------------- */
-
-void NMI_Handler(void);
-void HardFault_Handler(void);
-void MemManage_Handler(void);
-void BusFault_Handler(void);
-void UsageFault_Handler(void);
-void SVC_Handler(void);
-void DebugMon_Handler(void);
-void PendSV_Handler(void);
-void SysTick_Handler(void);
-void USBWakeUp_IRQHandler(void);
-void USB_FS_WKUP_IRQHandler(void);
-
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __STM32F0xx_IT_H */
-
-/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
-
+/**
+ ******************************************************************************
+ * @file stm32f0xx_it.h
+ * @date 03/01/2015 14:04:02
+ * @brief This file contains the headers of the interrupt handlers.
+ ******************************************************************************
+ *
+ * COPYRIGHT(c) 2015 STMicroelectronics
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F0xx_IT_H
+#define __STM32F0xx_IT_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void USB_IRQHandler(void);
+void SysTick_Handler(void);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F0xx_IT_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/therm-cube.ioc b/therm-cube.ioc
--- a/therm-cube.ioc
+++ b/therm-cube.ioc
@@ -1,5 +1,5 @@
#MicroXplorer Configuration settings - do not modify
-#Fri Nov 14 22:42:15 EST 2014
+#Sat Jan 03 14:03:06 EST 2015
File.Version=4
KeepUserPlacement=false
Mcu.Family=STM32F0
@@ -7,55 +7,57 @@ Mcu.IP0=NVIC
Mcu.IP1=RCC
Mcu.IP2=SPI1
Mcu.IP3=SYS
-Mcu.IP4=USART1
-Mcu.IP5=USB
-Mcu.IP6=USB_DEVICE
-Mcu.IPNb=7
-Mcu.Name=STM32F042K(4-6)Ux
-Mcu.Package=UFQFPN32
-Mcu.Pin0=PA1
-Mcu.Pin1=PA2
-Mcu.Pin10=PA12
-Mcu.Pin11=PA13
-Mcu.Pin12=PA14
-Mcu.Pin13=PA15
-Mcu.Pin14=PB3
-Mcu.Pin15=PB4
-Mcu.Pin16=PB5
-Mcu.Pin17=PB6
-Mcu.Pin18=PB7
-Mcu.Pin19=PB8
-Mcu.Pin2=PA3
-Mcu.Pin20=VP_RCC_USB
-Mcu.Pin21=VP_USB_DEVICE_VS_USB_DEVICE_CDC_FS
-Mcu.Pin3=PA4
-Mcu.Pin4=PA5
-Mcu.Pin5=PA6
-Mcu.Pin6=PA7
-Mcu.Pin7=PA9
-Mcu.Pin8=PA10
-Mcu.Pin9=PA11
-Mcu.PinsNb=22
-Mcu.UserName=STM32F042K6Ux
-NVIC.SysTick_IRQn=true\:0\:0
-NVIC.USB_IRQn=true\:0\:0
+Mcu.IP4=USB
+Mcu.IP5=USB_DEVICE
+Mcu.IPNb=6
+Mcu.Name=STM32F042K6Tx
+Mcu.Package=LQFP32
+Mcu.Pin0=PF0-OSC_IN
+Mcu.Pin1=PA1
+Mcu.Pin10=PA11
+Mcu.Pin11=PA12
+Mcu.Pin12=PA13
+Mcu.Pin13=PA14
+Mcu.Pin14=PA15
+Mcu.Pin15=PB3
+Mcu.Pin16=PB4
+Mcu.Pin17=PB5
+Mcu.Pin18=PB6
+Mcu.Pin19=PB7
+Mcu.Pin2=PA2
+Mcu.Pin20=VP_USB_DEVICE_VS_USB_DEVICE_CDC_FS
+Mcu.Pin3=PA3
+Mcu.Pin4=PA4
+Mcu.Pin5=PA5
+Mcu.Pin6=PA6
+Mcu.Pin7=PA7
+Mcu.Pin8=PA9
+Mcu.Pin9=PA10
+Mcu.PinsNb=21
+Mcu.UserName=STM32F042K6Tx
+MxCube.Version=4.5.0
+NVIC.SysTick_IRQn=true\:0\:0\:false
+NVIC.USB_IRQn=true\:0\:0\:false
PA1.Locked=true
PA1.Signal=GPIO_Output
PA10.Locked=true
-PA10.Mode=Asynchronous
PA10.Signal=USART1_RX
-PA11.Locked=true
PA11.Mode=Device
PA11.Signal=USB_DM
+PA12.Locked=true
PA12.Mode=Device
PA12.Signal=USB_DP
PA13.Locked=true
PA13.Mode=Serial-WireDebug
PA13.Signal=SYS_SWDIO
+PA14.Locked=true
PA14.Mode=Serial-WireDebug
PA14.Signal=SYS_SWCLK
+PA15.GPIOParameters=GPIO_PuPd,GPIO_Mode
+PA15.GPIO_Mode=GPIO_MODE_INPUT
+PA15.GPIO_PuPd=GPIO_PULLUP
PA15.Locked=true
-PA15.Signal=GPIO_Output
+PA15.Signal=GPIO_Input
PA2.Locked=true
PA2.Signal=GPIO_Output
PA3.Locked=true
@@ -72,86 +74,68 @@ PA7.Locked=true
PA7.Mode=Full_Duplex_Master
PA7.Signal=SPI1_MOSI
PA9.Locked=true
-PA9.Mode=Asynchronous
PA9.Signal=USART1_TX
+PB3.GPIOParameters=GPIO_PuPd,GPIO_Mode
+PB3.GPIO_Mode=GPIO_MODE_INPUT
+PB3.GPIO_PuPd=GPIO_PULLUP
PB3.Locked=true
PB3.Signal=GPIO_Input
+PB4.GPIOParameters=GPIO_PuPd,GPIO_Mode
+PB4.GPIO_Mode=GPIO_MODE_INPUT
+PB4.GPIO_PuPd=GPIO_PULLUP
PB4.Locked=true
PB4.Signal=GPIO_Input
+PB5.GPIOParameters=GPIO_PuPd,GPIO_Mode
+PB5.GPIO_Mode=GPIO_MODE_INPUT
+PB5.GPIO_PuPd=GPIO_PULLUP
PB5.Locked=true
PB5.Signal=GPIO_Input
+PB6.GPIOParameters=GPIO_PuPd,GPIO_Mode
+PB6.GPIO_Mode=GPIO_MODE_INPUT
+PB6.GPIO_PuPd=GPIO_PULLUP
PB6.Locked=true
PB6.Signal=GPIO_Input
+PB7.GPIOParameters=GPIO_PuPd,GPIO_Mode
+PB7.GPIO_Mode=GPIO_MODE_INPUT
+PB7.GPIO_PuPd=GPIO_PULLUP
PB7.Locked=true
PB7.Signal=GPIO_Input
-PB8.Locked=true
-PB8.Signal=GPIO_Output
PCC.Family=STM32F0
-PCC.MCU=STM32F042K(4-6)Ux
-PCC.MXVersion=4.4.0
-PCC.PartNumber=STM32F042K6Ux
+PCC.MCU=STM32F042K6Tx
+PCC.MXVersion=4.5.0
+PCC.PartNumber=STM32F042K6Tx
PCC.Seq0=0
PCC.SubFamily=STM32F0x2
PCC.Temperature=25
PCC.Vdd=3.6
-RCC.CECEnable-ClockTree=false
-RCC.EnableHSE-ClockTree=false
-RCC.EnableHSERTCDevisor-ClockTree=false
-RCC.EnableLSE-ClockTree=false
-RCC.EnableLSERTC-ClockTree=false
-RCC.EnableMCOMultDivisor-ClockTree=false
-RCC.FLatency-AdvancedSettings=FLASH_LATENCY_0
+PF0-OSC_IN.Locked=true
+PF0-OSC_IN.Signal=GPIO_Output
+RCC.AHBFreq_Value=48000000
+RCC.APB1Freq_Value=48000000
+RCC.APB1TimFreq_Value=48000000
+RCC.FCLKCortexFreq_Value=48000000
RCC.FamilyName=M
-RCC.HSEState-ClockTree=RCC_HSE_OFF
-RCC.HSI14State-ClockTree=RCC_HSI14_OFF
-RCC.HSI48State-ClockTree=RCC_HSI48_ON
-RCC.HSIState-ClockTree=RCC_HSI_ON
-RCC.I2C1Enable-ClockTree=false
-RCC.IPParameters=OscillatorTypeHSE-ClockTree,RTCEnable-ClockTree,EnableLSE-ClockTree,CECEnable-ClockTree,ReloadValue-AdvancedSettings,PLLCLKFreq_Value,FamilyName,PREFETCH_ENABLE-AdvancedSettings,OscillatorTypeHSI48-ClockTree,USBEnable-ClockTree,HSI14State-ClockTree,PLLMCOFreq_Value,IWDGEnable-ClockTree,HSI48State-ClockTree,FLatency-AdvancedSettings,EnableLSERTC-ClockTree,USART2Enable-ClockTree,Source-AdvancedSettings,VCOOutput2Freq_Value,MCOEnable-ClockTree,OscillatorTypeHSI-ClockTree,EnableMCOMultDivisor-ClockTree,I2C1Enable-ClockTree,HSIState-ClockTree,LSIState-ClockTree,PLLState-ClockTree,RCC_PERIPHCLK_USART1Var-ClockTree,USART1Enable-ClockTree,HSEState-ClockTree,EnableHSE-ClockTree,EnableHSERTCDevisor-ClockTree,OscillatorTypeLSI-ClockTree
-RCC.IWDGEnable-ClockTree=false
-RCC.LSIState-ClockTree=RCC_LSI_OFF
-RCC.MCOEnable-ClockTree=false
-RCC.OscillatorTypeHSE-ClockTree=
-RCC.OscillatorTypeHSI-ClockTree=RCC_OSCILLATORTYPE_HSI
-RCC.OscillatorTypeHSI48-ClockTree=RCC_OSCILLATORTYPE_HSI48
-RCC.OscillatorTypeLSI-ClockTree=
-RCC.PLLCLKFreq_Value=16000000
-RCC.PLLMCOFreq_Value=16000000
-RCC.PLLState-ClockTree=RCC_PLL_OFF
-RCC.PREFETCH_ENABLE-AdvancedSettings=0
-RCC.RCC_PERIPHCLK_USART1Var-ClockTree=RCC_PERIPHCLK_USART1
-RCC.RTCEnable-ClockTree=false
-RCC.ReloadValue-AdvancedSettings=__HAL_RCC_CRS_CALCULATE_RELOADVALUE(48000000,
-RCC.Source-AdvancedSettings=RCC_CRS_SYNC_SOURCE_USB
-RCC.USART1Enable-ClockTree=true
-RCC.USART2Enable-ClockTree=false
-RCC.USBEnable-ClockTree=true
-RCC.VCOOutput2Freq_Value=8000000
+RCC.HCLKFreq_Value=48000000
+RCC.HSICECFreq_Value=32786.88524590164
+RCC.I2SFreq_Value=48000000
+RCC.IPParameters=HCLKFreq_Value,SYSCLKFreq_VALUE,PLLCLKFreq_Value,FamilyName,PLLMCOFreq_Value,SYSCLKSource,FCLKCortexFreq_Value,PLLSourceVirtual,HSICECFreq_Value,MCOFreq_Value,VCOOutput2Freq_Value,I2SFreq_Value,APB1Freq_Value,USART1Freq_Value,APB1TimFreq_Value,AHBFreq_Value,TimSysFreq_Value
+RCC.MCOFreq_Value=48000000
+RCC.PLLCLKFreq_Value=96000000
+RCC.PLLMCOFreq_Value=96000000
+RCC.PLLSourceVirtual=RCC_PLLSOURCE_HSI48
+RCC.SYSCLKFreq_VALUE=48000000
+RCC.SYSCLKSource=RCC_SYSCLKSOURCE_HSI48
+RCC.TimSysFreq_Value=6000000
+RCC.USART1Freq_Value=48000000
+RCC.VCOOutput2Freq_Value=48000000
+SPI1.BaudRatePrescaler-Full_Duplex_Master=SPI_BAUDRATEPRESCALER_4
+SPI1.CalculateBaudRate-Full_Duplex_Master=12.0 MBits/s
SPI1.DataSize-Full_Duplex_Master=SPI_DATASIZE_8BIT
-SPI1.Direction-Full_Duplex_Master=SPI_DIRECTION_2LINES
-SPI1.IPParameters=Direction-Full_Duplex_Master,VirtualType-Full_Duplex_Master,TIMode-Full_Duplex_Master,Mode-Full_Duplex_Master,DataSize-Full_Duplex_Master,NSS-Full_Duplex_Master
+SPI1.IPParameters=CalculateBaudRate-Full_Duplex_Master,BaudRatePrescaler-Full_Duplex_Master,Mode-Full_Duplex_Master,DataSize-Full_Duplex_Master
SPI1.Mode-Full_Duplex_Master=SPI_MODE_MASTER
-SPI1.NSS-Full_Duplex_Master=SPI_NSS_SOFT
-SPI1.TIMode-Full_Duplex_Master=SPI_TIMODE_DISABLED
-SPI1.VirtualType-Full_Duplex_Master=VM_MASTER
-USART1.BaudRate=115200
-USART1.HwFlowCtl-Asynchronous=UART_HWCONTROL_NONE
-USART1.IPParameters=VirtualMode-Asynchronous,BaudRate,HwFlowCtl-Asynchronous,WordLength-Asynchronous
-USART1.VirtualMode-Asynchronous=VM_ASYNC
-USART1.WordLength-Asynchronous=UART_WORDLENGTH_7B
-USB.IPParameters=phy_itface-Device,speed-Device
-USB.phy_itface-Device=PCD_PHY_EMBEDDED
-USB.speed-Device=PCD_SPEED_FULL
-USB_DEVICE.CLASS_NAME-CDC_FS=CDC
-USB_DEVICE.IPParameters=CLASS_NAME-CDC_FS,VirtualModeFS,VirtualMode,USBD_HandleTypeDef,hUsbDevice-CDC_FS,USBD_HandleTypeDef-CDC_FS,VirtualModeFS-CDC_FS,VirtualMode-CDC_FS
+USB_DEVICE.IPParameters=VirtualModeFS,VirtualMode,USBD_HandleTypeDef
USB_DEVICE.USBD_HandleTypeDef=hUsbDeviceFS
-USB_DEVICE.USBD_HandleTypeDef-CDC_FS=hUsbDeviceFS
USB_DEVICE.VirtualMode=Cdc
-USB_DEVICE.VirtualMode-CDC_FS=Cdc
USB_DEVICE.VirtualModeFS=Cdc_FS
-USB_DEVICE.VirtualModeFS-CDC_FS=Cdc_FS
-USB_DEVICE.hUsbDevice-CDC_FS=hDeviceDuSmolt
-VP_RCC_USB.Mode=CRS SYNC Source USB
-VP_RCC_USB.Signal=RCC_USB
VP_USB_DEVICE_VS_USB_DEVICE_CDC_FS.Mode=CDC_FS
VP_USB_DEVICE_VS_USB_DEVICE_CDC_FS.Signal=USB_DEVICE_VS_USB_DEVICE_CDC_FS
diff --git a/usb_conf.h b/usb_conf.h
deleted file mode 100644
--- a/usb_conf.h
+++ /dev/null
@@ -1,103 +0,0 @@
-/**
- ******************************************************************************
- * @file usb_conf.h
- * @author MCD Application Team
- * @version V4.0.0
- * @date 21-January-2013
- * @brief Virtual COM Port Demo configuration header
- ******************************************************************************
- * @attention
- *
- * © COPYRIGHT 2013 STMicroelectronics
- *
- * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
- * You may not use this file except in compliance with the License.
- * You may obtain a copy of the License at:
- *
- * http://www.st.com/software_license_agreement_liberty_v2
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- *
- ******************************************************************************
- */
-
-
-/* Define to prevent recursive inclusion -------------------------------------*/
-#ifndef __USB_CONF_H
-#define __USB_CONF_H
-
-/* Includes ------------------------------------------------------------------*/
-/* Exported types ------------------------------------------------------------*/
-/* Exported constants --------------------------------------------------------*/
-/* Exported macro ------------------------------------------------------------*/
-/* Exported functions ------------------------------------------------------- */
-/* External variables --------------------------------------------------------*/
-
-/*-------------------------------------------------------------*/
-/* EP_NUM */
-/* defines how many endpoints are used by the device */
-/*-------------------------------------------------------------*/
-
-#define EP_NUM (4)
-
-/*-------------------------------------------------------------*/
-/* -------------- Buffer Description Table -----------------*/
-/*-------------------------------------------------------------*/
-/* buffer table base address */
-/* buffer table base address */
-#define BTABLE_ADDRESS (0x00)
-
-/* EP0 */
-/* rx/tx buffer base address */
-#define ENDP0_RXADDR (0x40)
-#define ENDP0_TXADDR (0x80)
-
-/* EP1 */
-/* tx buffer base address */
-#define ENDP1_TXADDR (0xC0)
-#define ENDP2_TXADDR (0x100)
-#define ENDP3_RXADDR (0x110)
-
-
-/*-------------------------------------------------------------*/
-/* ------------------- ISTR events -------------------------*/
-/*-------------------------------------------------------------*/
-/* IMR_MSK */
-/* mask defining which events has to be handled */
-/* by the device application software */
-#define IMR_MSK (CNTR_CTRM | CNTR_WKUPM | CNTR_SUSPM | CNTR_ERRM | CNTR_SOFM \
- | CNTR_ESOFM | CNTR_RESETM )
-
-/*#define CTR_CALLBACK*/
-/*#define DOVR_CALLBACK*/
-/*#define ERR_CALLBACK*/
-/*#define WKUP_CALLBACK*/
-/*#define SUSP_CALLBACK*/
-/*#define RESET_CALLBACK*/
-/*#define SOF_CALLBACK*/
-/*#define ESOF_CALLBACK*/
-/* CTR service routines */
-/* associated to defined endpoints */
-/*#define EP1_IN_Callback NOP_Process*/
-#define EP2_IN_Callback NOP_Process
-#define EP3_IN_Callback NOP_Process
-#define EP4_IN_Callback NOP_Process
-#define EP5_IN_Callback NOP_Process
-#define EP6_IN_Callback NOP_Process
-#define EP7_IN_Callback NOP_Process
-
-#define EP1_OUT_Callback NOP_Process
-#define EP2_OUT_Callback NOP_Process
-/*#define EP3_OUT_Callback NOP_Process*/
-#define EP4_OUT_Callback NOP_Process
-#define EP5_OUT_Callback NOP_Process
-#define EP6_OUT_Callback NOP_Process
-#define EP7_OUT_Callback NOP_Process
-
-#endif /* __USB_CONF_H */
-
-/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/usb_desc.c b/usb_desc.c
deleted file mode 100644
--- a/usb_desc.c
+++ /dev/null
@@ -1,174 +0,0 @@
-/**
- ******************************************************************************
- * @file usb_desc.c
- * @author MCD Application Team
- * @version V4.0.0
- * @date 21-January-2013
- * @brief Descriptors for Virtual Com Port Demo
- ******************************************************************************
- * @attention
- *
- * © COPYRIGHT 2013 STMicroelectronics
- *
- * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
- * You may not use this file except in compliance with the License.
- * You may obtain a copy of the License at:
- *
- * http://www.st.com/software_license_agreement_liberty_v2
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- *
- ******************************************************************************
- */
-
-
-/* Includes ------------------------------------------------------------------*/
-#include "usb_lib.h"
-#include "usb_desc.h"
-
-/* USB Standard Device Descriptor */
-const uint8_t Virtual_Com_Port_DeviceDescriptor[] =
- {
- 0x12, /* bLength */
- USB_DEVICE_DESCRIPTOR_TYPE, /* bDescriptorType */
- 0x00,
- 0x02, /* bcdUSB = 2.00 */
- 0x02, /* bDeviceClass: CDC */
- 0x00, /* bDeviceSubClass */
- 0x00, /* bDeviceProtocol */
- 0x40, /* bMaxPacketSize0 */
- 0x83,
- 0x04, /* idVendor = 0x0483 */
- 0x40,
- 0x57, /* idProduct = 0x7540 */
- 0x00,
- 0x02, /* bcdDevice = 2.00 */
- 1, /* Index of string descriptor describing manufacturer */
- 2, /* Index of string descriptor describing product */
- 3, /* Index of string descriptor describing the device's serial number */
- 0x01 /* bNumConfigurations */
- };
-
-const uint8_t Virtual_Com_Port_ConfigDescriptor[] =
- {
- /*Configuration Descriptor*/
- 0x09, /* bLength: Configuration Descriptor size */
- USB_CONFIGURATION_DESCRIPTOR_TYPE, /* bDescriptorType: Configuration */
- VIRTUAL_COM_PORT_SIZ_CONFIG_DESC, /* wTotalLength:no of returned bytes */
- 0x00,
- 0x02, /* bNumInterfaces: 2 interface */
- 0x01, /* bConfigurationValue: Configuration value */
- 0x00, /* iConfiguration: Index of string descriptor describing the configuration */
- 0xC0, /* bmAttributes: self powered */
- 0x32, /* MaxPower 0 mA */
- /*Interface Descriptor*/
- 0x09, /* bLength: Interface Descriptor size */
- USB_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType: Interface */
- /* Interface descriptor type */
- 0x00, /* bInterfaceNumber: Number of Interface */
- 0x00, /* bAlternateSetting: Alternate setting */
- 0x01, /* bNumEndpoints: One endpoints used */
- 0x02, /* bInterfaceClass: Communication Interface Class */
- 0x02, /* bInterfaceSubClass: Abstract Control Model */
- 0x01, /* bInterfaceProtocol: Common AT commands */
- 0x00, /* iInterface: */
- /*Header Functional Descriptor*/
- 0x05, /* bLength: Endpoint Descriptor size */
- 0x24, /* bDescriptorType: CS_INTERFACE */
- 0x00, /* bDescriptorSubtype: Header Func Desc */
- 0x10, /* bcdCDC: spec release number */
- 0x01,
- /*Call Management Functional Descriptor*/
- 0x05, /* bFunctionLength */
- 0x24, /* bDescriptorType: CS_INTERFACE */
- 0x01, /* bDescriptorSubtype: Call Management Func Desc */
- 0x00, /* bmCapabilities: D0+D1 */
- 0x01, /* bDataInterface: 1 */
- /*ACM Functional Descriptor*/
- 0x04, /* bFunctionLength */
- 0x24, /* bDescriptorType: CS_INTERFACE */
- 0x02, /* bDescriptorSubtype: Abstract Control Management desc */
- 0x02, /* bmCapabilities */
- /*Union Functional Descriptor*/
- 0x05, /* bFunctionLength */
- 0x24, /* bDescriptorType: CS_INTERFACE */
- 0x06, /* bDescriptorSubtype: Union func desc */
- 0x00, /* bMasterInterface: Communication class interface */
- 0x01, /* bSlaveInterface0: Data Class Interface */
- /*Endpoint 2 Descriptor*/
- 0x07, /* bLength: Endpoint Descriptor size */
- USB_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType: Endpoint */
- 0x82, /* bEndpointAddress: (IN2) */
- 0x03, /* bmAttributes: Interrupt */
- VIRTUAL_COM_PORT_INT_SIZE, /* wMaxPacketSize: */
- 0x00,
- 0xFF, /* bInterval: */
- /*Data class interface descriptor*/
- 0x09, /* bLength: Endpoint Descriptor size */
- USB_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType: */
- 0x01, /* bInterfaceNumber: Number of Interface */
- 0x00, /* bAlternateSetting: Alternate setting */
- 0x02, /* bNumEndpoints: Two endpoints used */
- 0x0A, /* bInterfaceClass: CDC */
- 0x00, /* bInterfaceSubClass: */
- 0x00, /* bInterfaceProtocol: */
- 0x00, /* iInterface: */
- /*Endpoint 3 Descriptor*/
- 0x07, /* bLength: Endpoint Descriptor size */
- USB_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType: Endpoint */
- 0x03, /* bEndpointAddress: (OUT3) */
- 0x02, /* bmAttributes: Bulk */
- VIRTUAL_COM_PORT_DATA_SIZE, /* wMaxPacketSize: */
- 0x00,
- 0x00, /* bInterval: ignore for Bulk transfer */
- /*Endpoint 1 Descriptor*/
- 0x07, /* bLength: Endpoint Descriptor size */
- USB_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType: Endpoint */
- 0x81, /* bEndpointAddress: (IN1) */
- 0x02, /* bmAttributes: Bulk */
- VIRTUAL_COM_PORT_DATA_SIZE, /* wMaxPacketSize: */
- 0x00,
- 0x00 /* bInterval */
- };
-
-/* USB String Descriptors */
-const uint8_t Virtual_Com_Port_StringLangID[VIRTUAL_COM_PORT_SIZ_STRING_LANGID] =
- {
- VIRTUAL_COM_PORT_SIZ_STRING_LANGID,
- USB_STRING_DESCRIPTOR_TYPE,
- 0x09,
- 0x04 /* LangID = 0x0409: U.S. English */
- };
-
-const uint8_t Virtual_Com_Port_StringVendor[VIRTUAL_COM_PORT_SIZ_STRING_VENDOR] =
- {
- VIRTUAL_COM_PORT_SIZ_STRING_VENDOR, /* Size of Vendor 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 Virtual_Com_Port_StringProduct[VIRTUAL_COM_PORT_SIZ_STRING_PRODUCT] =
- {
- VIRTUAL_COM_PORT_SIZ_STRING_PRODUCT, /* bLength */
- USB_STRING_DESCRIPTOR_TYPE, /* bDescriptorType */
- /* Product name: "STM32 Virtual COM Port" */
- 'S', 0, 'T', 0, 'M', 0, '3', 0, '2', 0, ' ', 0, 'V', 0, 'i', 0,
- 'r', 0, 't', 0, 'u', 0, 'a', 0, 'l', 0, ' ', 0, 'C', 0, 'O', 0,
- 'M', 0, ' ', 0, 'P', 0, 'o', 0, 'r', 0, 't', 0, ' ', 0, ' ', 0
- };
-
-uint8_t Virtual_Com_Port_StringSerial[VIRTUAL_COM_PORT_SIZ_STRING_SERIAL] =
- {
- VIRTUAL_COM_PORT_SIZ_STRING_SERIAL, /* bLength */
- USB_STRING_DESCRIPTOR_TYPE, /* bDescriptorType */
- 'S', 0, 'T', 0, 'M', 0, '3', 0, '2', 0
- };
-
-/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/usb_desc.h b/usb_desc.h
deleted file mode 100644
--- a/usb_desc.h
+++ /dev/null
@@ -1,66 +0,0 @@
-/**
- ******************************************************************************
- * @file usb_desc.h
- * @author MCD Application Team
- * @version V4.0.0
- * @date 21-January-2013
- * @brief Descriptor Header for Virtual COM Port Device
- ******************************************************************************
- * @attention
- *
- * © COPYRIGHT 2013 STMicroelectronics
- *
- * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
- * You may not use this file except in compliance with the License.
- * You may obtain a copy of the License at:
- *
- * http://www.st.com/software_license_agreement_liberty_v2
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- *
- ******************************************************************************
- */
-
-
-/* Define to prevent recursive inclusion -------------------------------------*/
-#ifndef __USB_DESC_H
-#define __USB_DESC_H
-
-/* Includes ------------------------------------------------------------------*/
-/* Exported types ------------------------------------------------------------*/
-/* Exported constants --------------------------------------------------------*/
-/* Exported macro ------------------------------------------------------------*/
-/* Exported define -----------------------------------------------------------*/
-#define USB_DEVICE_DESCRIPTOR_TYPE 0x01
-#define USB_CONFIGURATION_DESCRIPTOR_TYPE 0x02
-#define USB_STRING_DESCRIPTOR_TYPE 0x03
-#define USB_INTERFACE_DESCRIPTOR_TYPE 0x04
-#define USB_ENDPOINT_DESCRIPTOR_TYPE 0x05
-
-#define VIRTUAL_COM_PORT_DATA_SIZE 64
-#define VIRTUAL_COM_PORT_INT_SIZE 8
-
-#define VIRTUAL_COM_PORT_SIZ_DEVICE_DESC 18
-#define VIRTUAL_COM_PORT_SIZ_CONFIG_DESC 67
-#define VIRTUAL_COM_PORT_SIZ_STRING_LANGID 4
-#define VIRTUAL_COM_PORT_SIZ_STRING_VENDOR 38
-#define VIRTUAL_COM_PORT_SIZ_STRING_PRODUCT 50
-#define VIRTUAL_COM_PORT_SIZ_STRING_SERIAL 26
-
-#define STANDARD_ENDPOINT_DESC_SIZE 0x09
-
-/* Exported functions ------------------------------------------------------- */
-extern const uint8_t Virtual_Com_Port_DeviceDescriptor[VIRTUAL_COM_PORT_SIZ_DEVICE_DESC];
-extern const uint8_t Virtual_Com_Port_ConfigDescriptor[VIRTUAL_COM_PORT_SIZ_CONFIG_DESC];
-
-extern const uint8_t Virtual_Com_Port_StringLangID[VIRTUAL_COM_PORT_SIZ_STRING_LANGID];
-extern const uint8_t Virtual_Com_Port_StringVendor[VIRTUAL_COM_PORT_SIZ_STRING_VENDOR];
-extern const uint8_t Virtual_Com_Port_StringProduct[VIRTUAL_COM_PORT_SIZ_STRING_PRODUCT];
-extern uint8_t Virtual_Com_Port_StringSerial[VIRTUAL_COM_PORT_SIZ_STRING_SERIAL];
-
-#endif /* __USB_DESC_H */
-/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/usb_endp.c b/usb_endp.c
deleted file mode 100644
--- a/usb_endp.c
+++ /dev/null
@@ -1,78 +0,0 @@
-/**
- ******************************************************************************
- * @file usb_endp.c
- * @author MCD Application Team
- * @version V4.0.0
- * @date 21-January-2013
- * @brief Endpoint routines
- ******************************************************************************
- * @attention
- *
- * © COPYRIGHT 2013 STMicroelectronics
- *
- * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
- * You may not use this file except in compliance with the License.
- * You may obtain a copy of the License at:
- *
- * http://www.st.com/software_license_agreement_liberty_v2
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- *
- ******************************************************************************
- */
-
-
-/* Includes ------------------------------------------------------------------*/
-#include "usb_lib.h"
-#include "usb_desc.h"
-#include "usb_mem.h"
-#include "hw_config.h"
-#include "usb_istr.h"
-#include "usb_pwr.h"
-
-/* Private typedef -----------------------------------------------------------*/
-/* Private define ------------------------------------------------------------*/
-
-/* Interval between sending IN packets in frame number (1 frame = 1ms) */
-#define VCOMPORT_IN_FRAME_INTERVAL 5
-/* Private macro -------------------------------------------------------------*/
-/* Private variables ---------------------------------------------------------*/
-extern __IO uint32_t packet_sent;
-extern __IO uint32_t packet_receive;
-extern __IO uint8_t Receive_Buffer[64];
-uint32_t Receive_length;
-/* Private function prototypes -----------------------------------------------*/
-/* Private functions ---------------------------------------------------------*/
-
-/*******************************************************************************
-* Function Name : EP1_IN_Callback
-* Description :
-* Input : None.
-* Output : None.
-* Return : None.
-*******************************************************************************/
-
-void EP1_IN_Callback (void)
-{
- packet_sent = 1;
-}
-
-/*******************************************************************************
-* Function Name : EP3_OUT_Callback
-* Description :
-* Input : None.
-* Output : None.
-* Return : None.
-*******************************************************************************/
-void EP3_OUT_Callback(void)
-{
- packet_receive = 1;
- Receive_length = GetEPRxCount(ENDP3);
- PMAToUserBufferCopy((unsigned char*)Receive_Buffer, ENDP3_RXADDR, Receive_length);
-}
-
-/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/usb_istr.c b/usb_istr.c
deleted file mode 100644
--- a/usb_istr.c
+++ /dev/null
@@ -1,232 +0,0 @@
-/**
- ******************************************************************************
- * @file usb_istr.c
- * @author MCD Application Team
- * @version V4.0.0
- * @date 21-January-2013
- * @brief ISTR events interrupt service routines
- ******************************************************************************
- * @attention
- *
- * © COPYRIGHT 2013 STMicroelectronics
- *
- * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
- * You may not use this file except in compliance with the License.
- * You may obtain a copy of the License at:
- *
- * http://www.st.com/software_license_agreement_liberty_v2
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- *
- ******************************************************************************
- */
-
-
-/* Includes ------------------------------------------------------------------*/
-#include "usb_lib.h"
-#include "usb_prop.h"
-#include "usb_pwr.h"
-#include "usb_istr.h"
-
-/* Private typedef -----------------------------------------------------------*/
-/* Private define ------------------------------------------------------------*/
-/* Private macro -------------------------------------------------------------*/
-/* Private variables ---------------------------------------------------------*/
-__IO uint16_t wIstr; /* ISTR register last read value */
-__IO uint8_t bIntPackSOF = 0; /* SOFs received between 2 consecutive packets */
-__IO uint32_t esof_counter =0; /* expected SOF counter */
-__IO uint32_t wCNTR=0;
-
-/* Extern variables ----------------------------------------------------------*/
-/* Private function prototypes -----------------------------------------------*/
-/* Private functions ---------------------------------------------------------*/
-/* function pointers to non-control endpoints service routines */
-void (*pEpInt_IN[7])(void) =
- {
- EP1_IN_Callback,
- EP2_IN_Callback,
- EP3_IN_Callback,
- EP4_IN_Callback,
- EP5_IN_Callback,
- EP6_IN_Callback,
- EP7_IN_Callback,
- };
-
-void (*pEpInt_OUT[7])(void) =
- {
- EP1_OUT_Callback,
- EP2_OUT_Callback,
- EP3_OUT_Callback,
- EP4_OUT_Callback,
- EP5_OUT_Callback,
- EP6_OUT_Callback,
- EP7_OUT_Callback,
- };
-
-/*******************************************************************************
-* Function Name : USB_Istr
-* Description : ISTR events interrupt service routine
-* Input :
-* Output :
-* Return :
-*******************************************************************************/
-void USB_Istr(void)
-{
- uint32_t i=0;
- __IO uint32_t EP[8];
-
- wIstr = _GetISTR();
-
-#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_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_ESOF)
- if (wIstr & ISTR_ESOF & wInterrupt_Mask)
- {
- /* clear ESOF flag in ISTR */
- _SetISTR((uint16_t)CLR_ESOF);
-
- if ((_GetFNR()&FNR_RXDP)!=0)
- {
- /* increment ESOF counter */
- esof_counter ++;
-
- /* test if we enter in ESOF more than 3 times with FSUSP =0 and RXDP =1=>> possible missing SUSP flag*/
- if ((esof_counter >3)&&((_GetCNTR()&CNTR_FSUSP)==0))
- {
- /* this a sequence to apply a force RESET*/
-
- /*Store CNTR value */
- wCNTR = _GetCNTR();
-
- /*Store endpoints registers status */
- for (i=0;i<8;i++) EP[i] = _GetENDPOINT(i);
-
- /*apply FRES */
- wCNTR|=CNTR_FRES;
- _SetCNTR(wCNTR);
-
- /*clear FRES*/
- wCNTR&=~CNTR_FRES;
- _SetCNTR(wCNTR);
-
- /*poll for RESET flag in ISTR*/
- while((_GetISTR()&ISTR_RESET) == 0);
- /* clear RESET flag in ISTR */
- _SetISTR((uint16_t)CLR_RESET);
-
- /*restore Enpoints*/
- for (i=0;i<8;i++)
- _SetENDPOINT(i, EP[i]);
-
- esof_counter = 0;
- }
- }
- else
- {
- esof_counter = 0;
- }
-
- /* resume handling timing is made with ESOFs */
- Resume(RESUME_ESOF); /* request without change of the machine state */
-
-#ifdef ESOF_CALLBACK
- ESOF_Callback();
-#endif
- }
-#endif
-} /* USB_Istr */
-
-
-/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/usb_istr.h b/usb_istr.h
deleted file mode 100644
--- a/usb_istr.h
+++ /dev/null
@@ -1,94 +0,0 @@
-/**
- ******************************************************************************
- * @file usb_istr.h
- * @author MCD Application Team
- * @version V4.0.0
- * @date 21-January-2013
- * @brief This file includes the peripherals header files in the user application.
- ******************************************************************************
- * @attention
- *
- * © COPYRIGHT 2013 STMicroelectronics
- *
- * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
- * You may not use this file except in compliance with the License.
- * You may obtain a copy of the License at:
- *
- * http://www.st.com/software_license_agreement_liberty_v2
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- *
- ******************************************************************************
- */
-
-
-/* Define to prevent recursive inclusion -------------------------------------*/
-#ifndef __USB_ISTR_H
-#define __USB_ISTR_H
-
-/* Includes ------------------------------------------------------------------*/
-#include "usb_conf.h"
-
-/* Exported types ------------------------------------------------------------*/
-/* Exported constants --------------------------------------------------------*/
-/* Exported macro ------------------------------------------------------------*/
-/* Exported functions ------------------------------------------------------- */
-
- void USB_Istr(void);
-
-/* function prototypes Automatically built defining related macros */
-
-void EP1_IN_Callback(void);
-void EP2_IN_Callback(void);
-void EP3_IN_Callback(void);
-void EP4_IN_Callback(void);
-void EP5_IN_Callback(void);
-void EP6_IN_Callback(void);
-void EP7_IN_Callback(void);
-
-void EP1_OUT_Callback(void);
-void EP2_OUT_Callback(void);
-void EP3_OUT_Callback(void);
-void EP4_OUT_Callback(void);
-void EP5_OUT_Callback(void);
-void EP6_OUT_Callback(void);
-void EP7_OUT_Callback(void);
-
-#ifdef CTR_CALLBACK
-void CTR_Callback(void);
-#endif
-
-#ifdef DOVR_CALLBACK
-void DOVR_Callback(void);
-#endif
-
-#ifdef ERR_CALLBACK
-void ERR_Callback(void);
-#endif
-
-#ifdef WKUP_CALLBACK
-void WKUP_Callback(void);
-#endif
-
-#ifdef SUSP_CALLBACK
-void SUSP_Callback(void);
-#endif
-
-#ifdef RESET_CALLBACK
-void RESET_Callback(void);
-#endif
-
-#ifdef SOF_CALLBACK
-void SOF_Callback(void);
-#endif
-
-#ifdef ESOF_CALLBACK
-void ESOF_Callback(void);
-#endif
-#endif /*__USB_ISTR_H*/
-
-/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/usb_prop.c b/usb_prop.c
deleted file mode 100644
--- a/usb_prop.c
+++ /dev/null
@@ -1,414 +0,0 @@
-/**
- ******************************************************************************
- * @file usb_prop.c
- * @author MCD Application Team
- * @version V4.0.0
- * @date 21-January-2013
- * @brief All processing related to Virtual Com Port Demo
- ******************************************************************************
- * @attention
- *
- * © COPYRIGHT 2013 STMicroelectronics
- *
- * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
- * You may not use this file except in compliance with the License.
- * You may obtain a copy of the License at:
- *
- * http://www.st.com/software_license_agreement_liberty_v2
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- *
- ******************************************************************************
- */
-
-
-/* Includes ------------------------------------------------------------------*/
-#include "usb_lib.h"
-#include "usb_conf.h"
-#include "usb_prop.h"
-#include "usb_desc.h"
-#include "usb_pwr.h"
-#include "hw_config.h"
-
-/* Private typedef -----------------------------------------------------------*/
-/* Private define ------------------------------------------------------------*/
-/* Private macro -------------------------------------------------------------*/
-/* Private variables ---------------------------------------------------------*/
-uint8_t Request = 0;
-
-LINE_CODING linecoding =
- {
- 115200, /* baud rate*/
- 0x00, /* stop bits-1*/
- 0x00, /* parity - none*/
- 0x08 /* no. of bits 8*/
- };
-
-/* -------------------------------------------------------------------------- */
-/* Structures initializations */
-/* -------------------------------------------------------------------------- */
-
-DEVICE Device_Table =
- {
- EP_NUM,
- 1
- };
-
-DEVICE_PROP Device_Property =
- {
- Virtual_Com_Port_init,
- Virtual_Com_Port_Reset,
- Virtual_Com_Port_Status_In,
- Virtual_Com_Port_Status_Out,
- Virtual_Com_Port_Data_Setup,
- Virtual_Com_Port_NoData_Setup,
- Virtual_Com_Port_Get_Interface_Setting,
- Virtual_Com_Port_GetDeviceDescriptor,
- Virtual_Com_Port_GetConfigDescriptor,
- Virtual_Com_Port_GetStringDescriptor,
- 0,
- 0x40 /*MAX PACKET SIZE*/
- };
-
-USER_STANDARD_REQUESTS User_Standard_Requests =
- {
- Virtual_Com_Port_GetConfiguration,
- Virtual_Com_Port_SetConfiguration,
- Virtual_Com_Port_GetInterface,
- Virtual_Com_Port_SetInterface,
- Virtual_Com_Port_GetStatus,
- Virtual_Com_Port_ClearFeature,
- Virtual_Com_Port_SetEndPointFeature,
- Virtual_Com_Port_SetDeviceFeature,
- Virtual_Com_Port_SetDeviceAddress
- };
-
-ONE_DESCRIPTOR Device_Descriptor =
- {
- (uint8_t*)Virtual_Com_Port_DeviceDescriptor,
- VIRTUAL_COM_PORT_SIZ_DEVICE_DESC
- };
-
-ONE_DESCRIPTOR Config_Descriptor =
- {
- (uint8_t*)Virtual_Com_Port_ConfigDescriptor,
- VIRTUAL_COM_PORT_SIZ_CONFIG_DESC
- };
-
-ONE_DESCRIPTOR String_Descriptor[4] =
- {
- {(uint8_t*)Virtual_Com_Port_StringLangID, VIRTUAL_COM_PORT_SIZ_STRING_LANGID},
- {(uint8_t*)Virtual_Com_Port_StringVendor, VIRTUAL_COM_PORT_SIZ_STRING_VENDOR},
- {(uint8_t*)Virtual_Com_Port_StringProduct, VIRTUAL_COM_PORT_SIZ_STRING_PRODUCT},
- {(uint8_t*)Virtual_Com_Port_StringSerial, VIRTUAL_COM_PORT_SIZ_STRING_SERIAL}
- };
-
-/* Extern variables ----------------------------------------------------------*/
-/* Private function prototypes -----------------------------------------------*/
-/* Extern function prototypes ------------------------------------------------*/
-/* Private functions ---------------------------------------------------------*/
-/*******************************************************************************
-* Function Name : Virtual_Com_Port_init.
-* Description : Virtual COM Port Mouse init routine.
-* Input : None.
-* Output : None.
-* Return : None.
-*******************************************************************************/
-void Virtual_Com_Port_init(void)
-{
-
- /* Update the serial number string descriptor with the data from the unique
- ID*/
- Get_SerialNum();
-
- pInformation->Current_Configuration = 0;
-
- /* Connect the device */
- PowerOn();
-
- /* Perform basic device initialization operations */
- USB_SIL_Init();
-
- bDeviceState = UNCONNECTED;
-}
-
-/*******************************************************************************
-* Function Name : Virtual_Com_Port_Reset
-* Description : Virtual_Com_Port Mouse reset routine
-* Input : None.
-* Output : None.
-* Return : None.
-*******************************************************************************/
-void Virtual_Com_Port_Reset(void)
-{
- /* Set Virtual_Com_Port DEVICE as not configured */
- pInformation->Current_Configuration = 0;
-
- /* Current Feature initialization */
- pInformation->Current_Feature = Virtual_Com_Port_ConfigDescriptor[7];
-
- /* Set Virtual_Com_Port DEVICE with the default Interface*/
- pInformation->Current_Interface = 0;
-
- SetBTABLE(BTABLE_ADDRESS);
-
- /* Initialize Endpoint 0 */
- SetEPType(ENDP0, EP_CONTROL);
- SetEPTxStatus(ENDP0, EP_TX_STALL);
- SetEPRxAddr(ENDP0, ENDP0_RXADDR);
- SetEPTxAddr(ENDP0, ENDP0_TXADDR);
- Clear_Status_Out(ENDP0);
- SetEPRxCount(ENDP0, Device_Property.MaxPacketSize);
- SetEPRxValid(ENDP0);
-
- /* Initialize Endpoint 1 */
- SetEPType(ENDP1, EP_BULK);
- SetEPTxAddr(ENDP1, ENDP1_TXADDR);
- SetEPTxStatus(ENDP1, EP_TX_NAK);
- SetEPRxStatus(ENDP1, EP_RX_DIS);
-
- /* Initialize Endpoint 2 */
- SetEPType(ENDP2, EP_INTERRUPT);
- SetEPTxAddr(ENDP2, ENDP2_TXADDR);
- SetEPRxStatus(ENDP2, EP_RX_DIS);
- SetEPTxStatus(ENDP2, EP_TX_NAK);
-
- /* Initialize Endpoint 3 */
- SetEPType(ENDP3, EP_BULK);
- SetEPRxAddr(ENDP3, ENDP3_RXADDR);
- SetEPRxCount(ENDP3, VIRTUAL_COM_PORT_DATA_SIZE);
- SetEPRxStatus(ENDP3, EP_RX_VALID);
- SetEPTxStatus(ENDP3, EP_TX_DIS);
-
- /* Set this device to response on default address */
- SetDeviceAddress(0);
-
- bDeviceState = ATTACHED;
-}
-
-/*******************************************************************************
-* Function Name : Virtual_Com_Port_SetConfiguration.
-* Description : Update the device state to configured.
-* Input : None.
-* Output : None.
-* Return : None.
-*******************************************************************************/
-void Virtual_Com_Port_SetConfiguration(void)
-{
- DEVICE_INFO *pInfo = &Device_Info;
-
- if (pInfo->Current_Configuration != 0)
- {
- /* Device configured */
- bDeviceState = CONFIGURED;
- }
-}
-
-/*******************************************************************************
-* Function Name : Virtual_Com_Port_SetConfiguration.
-* Description : Update the device state to addressed.
-* Input : None.
-* Output : None.
-* Return : None.
-*******************************************************************************/
-void Virtual_Com_Port_SetDeviceAddress (void)
-{
- bDeviceState = ADDRESSED;
-}
-
-/*******************************************************************************
-* Function Name : Virtual_Com_Port_Status_In.
-* Description : Virtual COM Port Status In Routine.
-* Input : None.
-* Output : None.
-* Return : None.
-*******************************************************************************/
-void Virtual_Com_Port_Status_In(void)
-{
- if (Request == SET_LINE_CODING)
- {
- Request = 0;
- }
-}
-
-/*******************************************************************************
-* Function Name : Virtual_Com_Port_Status_Out
-* Description : Virtual COM Port Status OUT Routine.
-* Input : None.
-* Output : None.
-* Return : None.
-*******************************************************************************/
-void Virtual_Com_Port_Status_Out(void)
-{}
-
-/*******************************************************************************
-* Function Name : Virtual_Com_Port_Data_Setup
-* Description : handle the data class specific requests
-* Input : Request Nb.
-* Output : None.
-* Return : USB_UNSUPPORT or USB_SUCCESS.
-*******************************************************************************/
-RESULT Virtual_Com_Port_Data_Setup(uint8_t RequestNo)
-{
- uint8_t *(*CopyRoutine)(uint16_t);
-
- CopyRoutine = NULL;
-
- if (RequestNo == GET_LINE_CODING)
- {
- if (Type_Recipient == (CLASS_REQUEST | INTERFACE_RECIPIENT))
- {
- CopyRoutine = Virtual_Com_Port_GetLineCoding;
- }
- }
- else if (RequestNo == SET_LINE_CODING)
- {
- if (Type_Recipient == (CLASS_REQUEST | INTERFACE_RECIPIENT))
- {
- CopyRoutine = Virtual_Com_Port_SetLineCoding;
- }
- Request = SET_LINE_CODING;
- }
-
- if (CopyRoutine == NULL)
- {
- return USB_UNSUPPORT;
- }
-
- pInformation->Ctrl_Info.CopyData = CopyRoutine;
- pInformation->Ctrl_Info.Usb_wOffset = 0;
- (*CopyRoutine)(0);
- return USB_SUCCESS;
-}
-
-/*******************************************************************************
-* Function Name : Virtual_Com_Port_NoData_Setup.
-* Description : handle the no data class specific requests.
-* Input : Request Nb.
-* Output : None.
-* Return : USB_UNSUPPORT or USB_SUCCESS.
-*******************************************************************************/
-RESULT Virtual_Com_Port_NoData_Setup(uint8_t RequestNo)
-{
-
- if (Type_Recipient == (CLASS_REQUEST | INTERFACE_RECIPIENT))
- {
- if (RequestNo == SET_COMM_FEATURE)
- {
- return USB_SUCCESS;
- }
- else if (RequestNo == SET_CONTROL_LINE_STATE)
- {
- return USB_SUCCESS;
- }
- }
-
- return USB_UNSUPPORT;
-}
-
-/*******************************************************************************
-* Function Name : Virtual_Com_Port_GetDeviceDescriptor.
-* Description : Gets the device descriptor.
-* Input : Length.
-* Output : None.
-* Return : The address of the device descriptor.
-*******************************************************************************/
-uint8_t *Virtual_Com_Port_GetDeviceDescriptor(uint16_t Length)
-{
- return Standard_GetDescriptorData(Length, &Device_Descriptor);
-}
-
-/*******************************************************************************
-* Function Name : Virtual_Com_Port_GetConfigDescriptor.
-* Description : get the configuration descriptor.
-* Input : Length.
-* Output : None.
-* Return : The address of the configuration descriptor.
-*******************************************************************************/
-uint8_t *Virtual_Com_Port_GetConfigDescriptor(uint16_t Length)
-{
- return Standard_GetDescriptorData(Length, &Config_Descriptor);
-}
-
-/*******************************************************************************
-* Function Name : Virtual_Com_Port_GetStringDescriptor
-* Description : Gets the string descriptors according to the needed index
-* Input : Length.
-* Output : None.
-* Return : The address of the string descriptors.
-*******************************************************************************/
-uint8_t *Virtual_Com_Port_GetStringDescriptor(uint16_t Length)
-{
- uint8_t wValue0 = pInformation->USBwValue0;
- if (wValue0 > 4)
- {
- return NULL;
- }
- else
- {
- return Standard_GetDescriptorData(Length, &String_Descriptor[wValue0]);
- }
-}
-
-/*******************************************************************************
-* Function Name : Virtual_Com_Port_Get_Interface_Setting.
-* Description : test the interface and the alternate setting according to the
-* supported one.
-* Input1 : uint8_t: Interface : interface number.
-* Input2 : uint8_t: AlternateSetting : Alternate Setting number.
-* Output : None.
-* Return : The address of the string descriptors.
-*******************************************************************************/
-RESULT Virtual_Com_Port_Get_Interface_Setting(uint8_t Interface, uint8_t AlternateSetting)
-{
- if (AlternateSetting > 0)
- {
- return USB_UNSUPPORT;
- }
- else if (Interface > 1)
- {
- return USB_UNSUPPORT;
- }
- return USB_SUCCESS;
-}
-
-/*******************************************************************************
-* Function Name : Virtual_Com_Port_GetLineCoding.
-* Description : send the linecoding structure to the PC host.
-* Input : Length.
-* Output : None.
-* Return : Linecoding structure base address.
-*******************************************************************************/
-uint8_t *Virtual_Com_Port_GetLineCoding(uint16_t Length)
-{
- if (Length == 0)
- {
- pInformation->Ctrl_Info.Usb_wLength = sizeof(linecoding);
- return NULL;
- }
- return(uint8_t *)&linecoding;
-}
-
-/*******************************************************************************
-* Function Name : Virtual_Com_Port_SetLineCoding.
-* Description : Set the linecoding structure fields.
-* Input : Length.
-* Output : None.
-* Return : Linecoding structure base address.
-*******************************************************************************/
-uint8_t *Virtual_Com_Port_SetLineCoding(uint16_t Length)
-{
- if (Length == 0)
- {
- pInformation->Ctrl_Info.Usb_wLength = sizeof(linecoding);
- return NULL;
- }
- return(uint8_t *)&linecoding;
-}
-
-/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
-
diff --git a/usb_prop.h b/usb_prop.h
deleted file mode 100644
--- a/usb_prop.h
+++ /dev/null
@@ -1,87 +0,0 @@
-/**
- ******************************************************************************
- * @file usb_prop.h
- * @author MCD Application Team
- * @version V4.0.0
- * @date 21-January-2013
- * @brief All processing related to Virtual COM Port Demo (Endpoint 0)
- ******************************************************************************
- * @attention
- *
- * © COPYRIGHT 2013 STMicroelectronics
- *
- * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
- * You may not use this file except in compliance with the License.
- * You may obtain a copy of the License at:
- *
- * http://www.st.com/software_license_agreement_liberty_v2
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- *
- ******************************************************************************
- */
-
-
-/* Define to prevent recursive inclusion -------------------------------------*/
-#ifndef __usb_prop_H
-#define __usb_prop_H
-
-/* Includes ------------------------------------------------------------------*/
-/* Exported types ------------------------------------------------------------*/
-typedef struct
-{
- uint32_t bitrate;
- uint8_t format;
- uint8_t paritytype;
- uint8_t datatype;
-}LINE_CODING;
-
-/* Exported constants --------------------------------------------------------*/
-/* Exported macro ------------------------------------------------------------*/
-/* Exported define -----------------------------------------------------------*/
-
-#define Virtual_Com_Port_GetConfiguration NOP_Process
-//#define Virtual_Com_Port_SetConfiguration NOP_Process
-#define Virtual_Com_Port_GetInterface NOP_Process
-#define Virtual_Com_Port_SetInterface NOP_Process
-#define Virtual_Com_Port_GetStatus NOP_Process
-#define Virtual_Com_Port_ClearFeature NOP_Process
-#define Virtual_Com_Port_SetEndPointFeature NOP_Process
-#define Virtual_Com_Port_SetDeviceFeature NOP_Process
-//#define Virtual_Com_Port_SetDeviceAddress NOP_Process
-
-#define SEND_ENCAPSULATED_COMMAND 0x00
-#define GET_ENCAPSULATED_RESPONSE 0x01
-#define SET_COMM_FEATURE 0x02
-#define GET_COMM_FEATURE 0x03
-#define CLEAR_COMM_FEATURE 0x04
-#define SET_LINE_CODING 0x20
-#define GET_LINE_CODING 0x21
-#define SET_CONTROL_LINE_STATE 0x22
-#define SEND_BREAK 0x23
-
-/* Exported functions ------------------------------------------------------- */
-void Virtual_Com_Port_init(void);
-void Virtual_Com_Port_Reset(void);
-void Virtual_Com_Port_SetConfiguration(void);
-void Virtual_Com_Port_SetDeviceAddress (void);
-void Virtual_Com_Port_Status_In (void);
-void Virtual_Com_Port_Status_Out (void);
-RESULT Virtual_Com_Port_Data_Setup(uint8_t);
-RESULT Virtual_Com_Port_NoData_Setup(uint8_t);
-RESULT Virtual_Com_Port_Get_Interface_Setting(uint8_t Interface, uint8_t AlternateSetting);
-uint8_t *Virtual_Com_Port_GetDeviceDescriptor(uint16_t );
-uint8_t *Virtual_Com_Port_GetConfigDescriptor(uint16_t);
-uint8_t *Virtual_Com_Port_GetStringDescriptor(uint16_t);
-
-uint8_t *Virtual_Com_Port_GetLineCoding(uint16_t Length);
-uint8_t *Virtual_Com_Port_SetLineCoding(uint16_t Length);
-
-#endif /* __usb_prop_H */
-
-/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
-
diff --git a/usb_pwr.c b/usb_pwr.c
deleted file mode 100644
--- a/usb_pwr.c
+++ /dev/null
@@ -1,318 +0,0 @@
-/**
- ******************************************************************************
- * @file usb_pwr.c
- * @author MCD Application Team
- * @version V4.0.0
- * @date 21-January-2013
- * @brief Connection/disconnection & power management
- ******************************************************************************
- * @attention
- *
- * © COPYRIGHT 2013 STMicroelectronics
- *
- * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
- * You may not use this file except in compliance with the License.
- * You may obtain a copy of the License at:
- *
- * http://www.st.com/software_license_agreement_liberty_v2
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- *
- ******************************************************************************
- */
-
-
-/* Includes ------------------------------------------------------------------*/
-#include "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****/
diff --git a/usb_pwr.h b/usb_pwr.h
deleted file mode 100644
--- a/usb_pwr.h
+++ /dev/null
@@ -1,72 +0,0 @@
-/**
- ******************************************************************************
- * @file usb_pwr.h
- * @author MCD Application Team
- * @version V4.0.0
- * @date 21-January-2013
- * @brief Connection/disconnection & power management header
- ******************************************************************************
- * @attention
- *
- * © COPYRIGHT 2013 STMicroelectronics
- *
- * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
- * You may not use this file except in compliance with the License.
- * You may obtain a copy of the License at:
- *
- * http://www.st.com/software_license_agreement_liberty_v2
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- *
- ******************************************************************************
- */
-
-
-/* Define to prevent recursive inclusion -------------------------------------*/
-#ifndef __USB_PWR_H
-#define __USB_PWR_H
-
-/* Includes ------------------------------------------------------------------*/
-/* Exported types ------------------------------------------------------------*/
-typedef enum _RESUME_STATE
-{
- RESUME_EXTERNAL,
- RESUME_INTERNAL,
- RESUME_LATER,
- RESUME_WAIT,
- RESUME_START,
- RESUME_ON,
- RESUME_OFF,
- RESUME_ESOF
-} RESUME_STATE;
-
-typedef enum _DEVICE_STATE
-{
- UNCONNECTED,
- ATTACHED,
- POWERED,
- SUSPENDED,
- ADDRESSED,
- CONFIGURED
-} DEVICE_STATE;
-
-/* Exported constants --------------------------------------------------------*/
-/* Exported macro ------------------------------------------------------------*/
-/* Exported functions ------------------------------------------------------- */
-void Suspend(void);
-void Resume_Init(void);
-void Resume(RESUME_STATE eResumeSetVal);
-RESULT PowerOn(void);
-RESULT PowerOff(void);
-
-/* External variables --------------------------------------------------------*/
-extern __IO uint32_t bDeviceState; /* USB device status */
-extern __IO bool fSuspendEnabled; /* true when suspend is possible */
-
-#endif /*__USB_PWR_H*/
-
-/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/