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/system.h"
40 #include "drivers/usb_io.h"
41 #include "drivers/nvic.h"
43 #include "common/utils.h"
46 /* Private typedef -----------------------------------------------------------*/
47 /* Private define ------------------------------------------------------------*/
48 /* Private macro -------------------------------------------------------------*/
49 /* Private variables ---------------------------------------------------------*/
50 ErrorStatus HSEStartUpStatus
;
51 EXTI_InitTypeDef EXTI_InitStructure
;
52 __IO
uint32_t packetSent
; // HJI
53 extern __IO
uint32_t receiveLength
; // HJI
55 uint8_t receiveBuffer
[64]; // HJI
56 uint32_t sendLength
; // HJI
57 static void IntToUnicode(uint32_t value
, uint8_t *pbuf
, uint8_t len
);
58 static void (*ctrlLineStateCb
)(void *context
, uint16_t ctrlLineState
);
59 static void *ctrlLineStateCbContext
;
60 static void (*baudRateCb
)(void *context
, uint32_t baud
);
61 static void *baudRateCbContext
;
63 /* Extern variables ----------------------------------------------------------*/
65 /* Private function prototypes -----------------------------------------------*/
66 /* Private functions ---------------------------------------------------------*/
67 /*******************************************************************************
68 * Function Name : Set_System
69 * Description : Configures Main system clocks & power
72 *******************************************************************************/
75 #if !defined(STM32L1XX_MD) && !defined(STM32L1XX_HD) && !defined(STM32L1XX_MD_PLUS)
76 GPIO_InitTypeDef GPIO_InitStructure
;
77 #endif /* STM32L1XX_MD && STM32L1XX_XD */
79 #if defined(USB_USE_EXTERNAL_PULLUP)
80 GPIO_InitTypeDef GPIO_InitStructure
;
81 #endif /* USB_USE_EXTERNAL_PULLUP */
83 /*!< At this stage the microcontroller clock setting is already configured,
84 this is done through SystemInit() function which is called from startup
85 file (startup_stm32f10x_xx.s) before to branch to application main.
86 To reconfigure the default setting of SystemInit() function, refer to
87 system_stm32f10x.c file
89 #if defined(STM32L1XX_MD) || defined(STM32L1XX_HD)|| defined(STM32L1XX_MD_PLUS) || defined(STM32F37X) || defined(STM32F303xC)
90 /* Enable the SYSCFG module clock */
91 RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG
, ENABLE
);
92 #endif /* STM32L1XX_XD */
94 usbGenerateDisconnectPulse();
96 #if defined(STM32F37X) || defined(STM32F303xC)
98 /*Set PA11,12 as IN - USB_DM,DP*/
99 RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOA
, ENABLE
);
100 GPIO_InitStructure
.GPIO_Pin
= GPIO_Pin_11
| GPIO_Pin_12
;
101 GPIO_InitStructure
.GPIO_Speed
= GPIO_Speed_50MHz
;
102 GPIO_InitStructure
.GPIO_Mode
= GPIO_Mode_AF
;
103 GPIO_InitStructure
.GPIO_OType
= GPIO_OType_PP
;
104 GPIO_InitStructure
.GPIO_PuPd
= GPIO_PuPd_NOPULL
;
105 GPIO_Init(GPIOA
, &GPIO_InitStructure
);
107 /*SET PA11,12 for USB: USB_DM,DP*/
108 GPIO_PinAFConfig(GPIOA
, GPIO_PinSource11
, GPIO_AF_14
);
109 GPIO_PinAFConfig(GPIOA
, GPIO_PinSource12
, GPIO_AF_14
);
111 #endif /* STM32F37X && STM32F303xC)*/
113 // Initialise callbacks
114 ctrlLineStateCb
= NULL
;
117 /* Configure the EXTI line 18 connected internally to the USB IP */
118 EXTI_ClearITPendingBit(EXTI_Line18
);
119 EXTI_InitStructure
.EXTI_Line
= EXTI_Line18
;
120 EXTI_InitStructure
.EXTI_Trigger
= EXTI_Trigger_Rising
;
121 EXTI_InitStructure
.EXTI_LineCmd
= ENABLE
;
122 EXTI_Init(&EXTI_InitStructure
);
125 /*******************************************************************************
126 * Function Name : Set_USBClock
127 * Description : Configures USB Clock input (48MHz)
130 *******************************************************************************/
131 void Set_USBClock(void)
133 /* Select USBCLK source */
134 RCC_USBCLKConfig(RCC_USBCLKSource_PLLCLK_1Div5
);
136 /* Enable the USB clock */
137 RCC_APB1PeriphClockCmd(RCC_APB1Periph_USB
, ENABLE
);
140 /*******************************************************************************
141 * Function Name : Enter_LowPowerMode
142 * Description : Power-off system clocks and power while entering suspend mode
145 *******************************************************************************/
146 void Enter_LowPowerMode(void)
148 /* Set the device state to suspend */
149 bDeviceState
= SUSPENDED
;
152 /*******************************************************************************
153 * Function Name : Leave_LowPowerMode
154 * Description : Restores system clocks and power while exiting suspend mode
157 *******************************************************************************/
158 void Leave_LowPowerMode(void)
160 DEVICE_INFO
*pInfo
= &Device_Info
;
162 /* Set the device state to the correct state */
163 if (pInfo
->Current_Configuration
!= 0) {
164 /* Device configured */
165 bDeviceState
= CONFIGURED
;
167 bDeviceState
= ATTACHED
;
169 /*Enable SystemCoreClock*/
173 /*******************************************************************************
174 * Function Name : USB_Interrupts_Config
175 * Description : Configures the USB interrupts
178 *******************************************************************************/
179 void USB_Interrupts_Config(void)
181 NVIC_InitTypeDef NVIC_InitStructure
;
183 /* 2 bit for pre-emption priority, 2 bits for subpriority */
184 NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING
); // is this really neccesary?
186 /* Enable the USB interrupt */
187 NVIC_InitStructure
.NVIC_IRQChannel
= USB_LP_CAN1_RX0_IRQn
;
188 NVIC_InitStructure
.NVIC_IRQChannelPreemptionPriority
= NVIC_PRIORITY_BASE(NVIC_PRIO_USB
);
189 NVIC_InitStructure
.NVIC_IRQChannelSubPriority
= NVIC_PRIORITY_SUB(NVIC_PRIO_USB
);
190 NVIC_InitStructure
.NVIC_IRQChannelCmd
= ENABLE
;
191 NVIC_Init(&NVIC_InitStructure
);
193 /* Enable the USB Wake-up interrupt */
194 NVIC_InitStructure
.NVIC_IRQChannel
= USBWakeUp_IRQn
;
195 NVIC_InitStructure
.NVIC_IRQChannelPreemptionPriority
= NVIC_PRIORITY_BASE(NVIC_PRIO_USB_WUP
);
196 NVIC_InitStructure
.NVIC_IRQChannelSubPriority
= NVIC_PRIORITY_SUB(NVIC_PRIO_USB_WUP
);
197 NVIC_Init(&NVIC_InitStructure
);
200 /*******************************************************************************
201 * Function Name : USB_Cable_Config
202 * Description : Software Connection/Disconnection of USB Cable
205 *******************************************************************************/
206 void USB_Cable_Config(FunctionalState NewState
)
211 /*******************************************************************************
212 * Function Name : Get_SerialNum.
213 * Description : Create the serial number string descriptor.
217 *******************************************************************************/
218 void Get_SerialNum(void)
220 uint32_t Device_Serial0
, Device_Serial1
, Device_Serial2
;
222 Device_Serial0
= *(uint32_t*)ID1
;
223 Device_Serial1
= *(uint32_t*)ID2
;
224 Device_Serial2
= *(uint32_t*)ID3
;
226 Device_Serial0
+= Device_Serial2
;
228 if (Device_Serial0
!= 0) {
229 IntToUnicode(Device_Serial0
, &Virtual_Com_Port_StringSerial
[2], 8);
230 IntToUnicode(Device_Serial1
, &Virtual_Com_Port_StringSerial
[18], 4);
234 /*******************************************************************************
235 * Function Name : HexToChar.
236 * Description : Convert Hex 32Bits value into char.
240 *******************************************************************************/
241 static void IntToUnicode(uint32_t value
, uint8_t *pbuf
, uint8_t len
)
245 for (idx
= 0; idx
< len
; idx
++) {
246 if (((value
>> 28)) < 0xA) {
247 pbuf
[2 * idx
] = (value
>> 28) + '0';
249 pbuf
[2 * idx
] = (value
>> 28) + 'A' - 10;
254 pbuf
[2 * idx
+ 1] = 0;
258 /*******************************************************************************
259 * Function Name : Send DATA .
260 * Description : send the data received from the STM32 to the PC through USB
264 *******************************************************************************/
265 uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer
, uint32_t sendLength
)
267 /* Last transmission hasn't finished, abort */
272 // We can only put 64 bytes in the buffer
273 if (sendLength
> 64 / 2) {
277 // Try to load some bytes if we can
279 UserToPMABufferCopy(ptrBuffer
, ENDP1_TXADDR
, sendLength
);
280 SetEPTxCount(ENDP1
, sendLength
);
281 packetSent
+= sendLength
;
288 uint32_t CDC_Send_FreeBytes(void)
290 /* this driver is blocking, so the buffer is unlimited */
294 /*******************************************************************************
295 * Function Name : Receive DATA .
296 * Description : receive the data from the PC to STM32 and send it through USB
300 *******************************************************************************/
301 uint32_t CDC_Receive_DATA(uint8_t* recvBuf
, uint32_t len
)
303 static uint8_t offset
= 0;
306 if (len
> receiveLength
) {
310 for (i
= 0; i
< len
; i
++) {
311 recvBuf
[i
] = (uint8_t)(receiveBuffer
[i
+ offset
]);
314 receiveLength
-= len
;
317 /* re-enable the rx endpoint which we had set to receive 0 bytes */
318 if (receiveLength
== 0) {
319 SetEPRxCount(ENDP3
, 64);
320 SetEPRxStatus(ENDP3
, EP_RX_VALID
);
327 uint32_t CDC_Receive_BytesAvailable(void)
329 return receiveLength
;
332 /*******************************************************************************
333 * Function Name : usbIsConfigured.
334 * Description : Determines if USB VCP is configured or not
337 * Return : True if configured.
338 *******************************************************************************/
339 uint8_t usbIsConfigured(void)
341 return (bDeviceState
== CONFIGURED
);
344 /*******************************************************************************
345 * Function Name : usbIsConnected.
346 * Description : Determines if USB VCP is connected ot not
349 * Return : True if connected.
350 *******************************************************************************/
351 uint8_t usbIsConnected(void)
353 return (bDeviceState
!= UNCONNECTED
);
357 /*******************************************************************************
358 * Function Name : CDC_BaudRate.
359 * Description : Get the current baud rate
362 * Return : Baud rate in bps
363 *******************************************************************************/
364 uint32_t CDC_BaudRate(void)
366 return Virtual_Com_Port_GetBaudRate();
369 /*******************************************************************************
370 * Function Name : CDC_SetBaudRateCb
371 * Description : Set a callback to call when baud rate changes
372 * Input : callback function and context.
375 *******************************************************************************/
376 void CDC_SetBaudRateCb(void (*cb
)(void *context
, uint32_t baud
), void *context
)
378 baudRateCbContext
= context
;
382 /*******************************************************************************
383 * Function Name : CDC_SetCtrlLineStateCb
384 * Description : Set a callback to call when control line state changes
385 * Input : callback function and context.
388 *******************************************************************************/
389 void CDC_SetCtrlLineStateCb(void (*cb
)(void *context
, uint16_t ctrlLineState
), void *context
)
391 ctrlLineStateCbContext
= context
;
392 ctrlLineStateCb
= cb
;
395 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/