2 ******************************************************************************
4 * @author MCD Application Team
6 * @date 21-January-2013
7 * @brief Hardware Configuration & Setup
8 ******************************************************************************
11 * <h2><center>© COPYRIGHT 2013 STMicroelectronics</center></h2>
13 * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
14 * You may not use this file except in compliance with the License.
15 * You may obtain a copy of the License at:
17 * http://www.st.com/software_license_agreement_liberty_v2
19 * Unless required by applicable law or agreed to in writing, software
20 * distributed under the License is distributed on an "AS IS" BASIS,
21 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
22 * See the License for the specific language governing permissions and
23 * limitations under the License.
25 ******************************************************************************
28 /* Includes ------------------------------------------------------------------*/
35 #include "hw_config.h"
39 #include "drivers/time.h"
40 #include "drivers/nvic.h"
42 #include "common/utils.h"
45 /* Private typedef -----------------------------------------------------------*/
46 /* Private define ------------------------------------------------------------*/
47 /* Private macro -------------------------------------------------------------*/
48 /* Private variables ---------------------------------------------------------*/
49 ErrorStatus HSEStartUpStatus
;
50 EXTI_InitTypeDef EXTI_InitStructure
;
51 __IO
uint32_t packetSent
; // HJI
52 extern __IO
uint32_t receiveLength
; // HJI
54 uint8_t receiveBuffer
[64]; // HJI
55 uint32_t sendLength
; // HJI
56 static void IntToUnicode(uint32_t value
, uint8_t *pbuf
, uint8_t len
);
57 /* Extern variables ----------------------------------------------------------*/
59 /* Private function prototypes -----------------------------------------------*/
60 /* Private functions ---------------------------------------------------------*/
61 /*******************************************************************************
62 * Function Name : Set_System
63 * Description : Configures Main system clocks & power
66 *******************************************************************************/
69 #if !defined(STM32L1XX_MD) && !defined(STM32L1XX_HD) && !defined(STM32L1XX_MD_PLUS)
70 GPIO_InitTypeDef GPIO_InitStructure
;
71 #endif /* STM32L1XX_MD && STM32L1XX_XD */
73 #if defined(USB_USE_EXTERNAL_PULLUP)
74 GPIO_InitTypeDef GPIO_InitStructure
;
75 #endif /* USB_USE_EXTERNAL_PULLUP */
77 /*!< At this stage the microcontroller clock setting is already configured,
78 this is done through SystemInit() function which is called from startup
79 file (startup_stm32f10x_xx.s) before to branch to application main.
80 To reconfigure the default setting of SystemInit() function, refer to
81 system_stm32f10x.c file
83 #if defined(STM32L1XX_MD) || defined(STM32L1XX_HD)|| defined(STM32L1XX_MD_PLUS) || defined(STM32F37X) || defined(STM32F303xC)
84 /* Enable the SYSCFG module clock */
85 RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG
, ENABLE
);
86 #endif /* STM32L1XX_XD */
88 /*Pull down PA12 to create USB Disconnect Pulse*/ // HJI
89 #if defined(STM32F303xC) // HJI
90 RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOA
, ENABLE
); // HJI
92 GPIO_InitStructure
.GPIO_Pin
= GPIO_Pin_12
; // HJI
93 GPIO_InitStructure
.GPIO_Speed
= GPIO_Speed_50MHz
; // HJI
94 GPIO_InitStructure
.GPIO_Mode
= GPIO_Mode_OUT
; // HJI
95 GPIO_InitStructure
.GPIO_OType
= GPIO_OType_OD
; // HJI
96 GPIO_InitStructure
.GPIO_PuPd
= GPIO_PuPd_NOPULL
; // HJI
98 RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA
, ENABLE
); // HJI
100 GPIO_InitStructure
.GPIO_Pin
= GPIO_Pin_12
; // HJI
101 GPIO_InitStructure
.GPIO_Speed
= GPIO_Speed_50MHz
; // HJI
102 GPIO_InitStructure
.GPIO_Mode
= GPIO_Mode_Out_OD
; // HJI
105 GPIO_Init(GPIOA
, &GPIO_InitStructure
); // HJI
107 GPIO_ResetBits(GPIOA
, GPIO_Pin_12
); // HJI
111 GPIO_SetBits(GPIOA
, GPIO_Pin_12
); // HJI
113 #if defined(STM32F37X) || defined(STM32F303xC)
115 /*Set PA11,12 as IN - USB_DM,DP*/
116 RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOA
, ENABLE
);
117 GPIO_InitStructure
.GPIO_Pin
= GPIO_Pin_11
| GPIO_Pin_12
;
118 GPIO_InitStructure
.GPIO_Speed
= GPIO_Speed_50MHz
;
119 GPIO_InitStructure
.GPIO_Mode
= GPIO_Mode_AF
;
120 GPIO_InitStructure
.GPIO_OType
= GPIO_OType_PP
;
121 GPIO_InitStructure
.GPIO_PuPd
= GPIO_PuPd_NOPULL
;
122 GPIO_Init(GPIOA
, &GPIO_InitStructure
);
124 /*SET PA11,12 for USB: USB_DM,DP*/
125 GPIO_PinAFConfig(GPIOA
, GPIO_PinSource11
, GPIO_AF_14
);
126 GPIO_PinAFConfig(GPIOA
, GPIO_PinSource12
, GPIO_AF_14
);
128 #endif /* STM32F37X && STM32F303xC)*/
130 /* Configure the EXTI line 18 connected internally to the USB IP */
131 EXTI_ClearITPendingBit(EXTI_Line18
);
132 EXTI_InitStructure
.EXTI_Line
= EXTI_Line18
;
133 EXTI_InitStructure
.EXTI_Trigger
= EXTI_Trigger_Rising
;
134 EXTI_InitStructure
.EXTI_LineCmd
= ENABLE
;
135 EXTI_Init(&EXTI_InitStructure
);
138 /*******************************************************************************
139 * Function Name : Set_USBClock
140 * Description : Configures USB Clock input (48MHz)
143 *******************************************************************************/
144 void Set_USBClock(void)
146 RCC_ClocksTypeDef RCC_Clocks
;
147 RCC_GetClocksFreq(&RCC_Clocks
);
149 /* Select USBCLK source */
150 RCC_USBCLKConfig(RCC_Clocks
.SYSCLK_Frequency
== 72000000 ? RCC_USBCLKSource_PLLCLK_1Div5
: RCC_USBCLKSource_PLLCLK_Div1
);
152 /* Enable the USB clock */
153 RCC_APB1PeriphClockCmd(RCC_APB1Periph_USB
, ENABLE
);
156 /*******************************************************************************
157 * Function Name : Enter_LowPowerMode
158 * Description : Power-off system clocks and power while entering suspend mode
161 *******************************************************************************/
162 void Enter_LowPowerMode(void)
164 /* Set the device state to suspend */
165 bDeviceState
= SUSPENDED
;
168 /*******************************************************************************
169 * Function Name : Leave_LowPowerMode
170 * Description : Restores system clocks and power while exiting suspend mode
173 *******************************************************************************/
174 void Leave_LowPowerMode(void)
176 DEVICE_INFO
*pInfo
= &Device_Info
;
178 /* Set the device state to the correct state */
179 if (pInfo
->Current_Configuration
!= 0) {
180 /* Device configured */
181 bDeviceState
= CONFIGURED
;
183 bDeviceState
= ATTACHED
;
185 /*Enable SystemCoreClock*/
189 /*******************************************************************************
190 * Function Name : USB_Interrupts_Config
191 * Description : Configures the USB interrupts
194 *******************************************************************************/
195 void USB_Interrupts_Config(void)
197 NVIC_SetPriority(USB_LP_CAN1_RX0_IRQn
, NVIC_PRIO_USB
);
198 NVIC_EnableIRQ(USB_LP_CAN1_RX0_IRQn
);
200 NVIC_SetPriority(USBWakeUp_IRQn
, NVIC_PRIO_USB
);
201 NVIC_EnableIRQ(USBWakeUp_IRQn
);
204 /*******************************************************************************
205 * Function Name : USB_Cable_Config
206 * Description : Software Connection/Disconnection of USB Cable
209 *******************************************************************************/
210 void USB_Cable_Config(FunctionalState NewState
)
215 /*******************************************************************************
216 * Function Name : Get_SerialNum.
217 * Description : Create the serial number string descriptor.
221 *******************************************************************************/
222 void Get_SerialNum(void)
224 uint32_t Device_Serial0
, Device_Serial1
, Device_Serial2
;
226 Device_Serial0
= *(uint32_t*)ID1
;
227 Device_Serial1
= *(uint32_t*)ID2
;
228 Device_Serial2
= *(uint32_t*)ID3
;
230 Device_Serial0
+= Device_Serial2
;
232 if (Device_Serial0
!= 0) {
233 IntToUnicode(Device_Serial0
, &Virtual_Com_Port_StringSerial
[2], 8);
234 IntToUnicode(Device_Serial1
, &Virtual_Com_Port_StringSerial
[18], 4);
238 /*******************************************************************************
239 * Function Name : HexToChar.
240 * Description : Convert Hex 32Bits value into char.
244 *******************************************************************************/
245 static void IntToUnicode(uint32_t value
, uint8_t *pbuf
, uint8_t len
)
249 for (idx
= 0; idx
< len
; idx
++) {
250 if (((value
>> 28)) < 0xA) {
251 pbuf
[2 * idx
] = (value
>> 28) + '0';
253 pbuf
[2 * idx
] = (value
>> 28) + 'A' - 10;
258 pbuf
[2 * idx
+ 1] = 0;
262 /*******************************************************************************
263 * Function Name : Send DATA .
264 * Description : send the data received from the STM32 to the PC through USB
268 *******************************************************************************/
269 uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer
, uint32_t sendLength
)
271 /* Last transmission hasn't finished, abort */
276 // We can only put 64 bytes in the buffer
277 if (sendLength
> 64 / 2) {
281 // Try to load some bytes if we can
283 UserToPMABufferCopy(ptrBuffer
, ENDP1_TXADDR
, sendLength
);
284 SetEPTxCount(ENDP1
, sendLength
);
285 packetSent
+= sendLength
;
292 uint32_t CDC_Send_FreeBytes(void)
294 /* this driver is blocking, so the buffer is unlimited */
298 /*******************************************************************************
299 * Function Name : Receive DATA .
300 * Description : receive the data from the PC to STM32 and send it through USB
304 *******************************************************************************/
305 uint32_t CDC_Receive_DATA(uint8_t* recvBuf
, uint32_t len
)
307 static uint8_t offset
= 0;
310 if (len
> receiveLength
) {
314 for (i
= 0; i
< len
; i
++) {
315 recvBuf
[i
] = (uint8_t)(receiveBuffer
[i
+ offset
]);
318 receiveLength
-= len
;
321 /* re-enable the rx endpoint which we had set to receive 0 bytes */
322 if (receiveLength
== 0) {
323 SetEPRxCount(ENDP3
, 64);
324 SetEPRxStatus(ENDP3
, EP_RX_VALID
);
331 uint32_t CDC_Receive_BytesAvailable(void)
333 return receiveLength
;
336 /*******************************************************************************
337 * Function Name : usbIsConfigured.
338 * Description : Determines if USB VCP is configured or not
341 * Return : True if configured.
342 *******************************************************************************/
343 uint8_t usbIsConfigured(void)
345 return (bDeviceState
== CONFIGURED
);
348 /*******************************************************************************
349 * Function Name : usbIsConnected.
350 * Description : Determines if USB VCP is connected ot not
353 * Return : True if connected.
354 *******************************************************************************/
355 uint8_t usbIsConnected(void)
357 return (bDeviceState
!= UNCONNECTED
);
361 /*******************************************************************************
362 * Function Name : CDC_BaudRate.
363 * Description : Get the current baud rate
366 * Return : Baud rate in bps
367 *******************************************************************************/
368 uint32_t CDC_BaudRate(void)
370 return Virtual_Com_Port_GetBaudRate();
373 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/