Auto updated submodule references [07-02-2025]
[betaflight.git] / src / platform / STM32 / vcp / hw_config.c
blobf5af1b2fafd78a9e3706905298f6e03fc1414164
1 /**
2 ******************************************************************************
3 * @file hw_config.c
4 * @author MCD Application Team
5 * @version V4.0.0
6 * @date 21-January-2013
7 * @brief Hardware Configuration & Setup
8 ******************************************************************************
9 * @attention
11 * <h2><center>&copy; 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 ------------------------------------------------------------------*/
30 #include "stm32_it.h"
31 #include "platform.h"
32 #include "usb_lib.h"
33 #include "usb_prop.h"
34 #include "usb_desc.h"
35 #include "hw_config.h"
36 #include "usb_pwr.h"
38 #include <stdbool.h>
39 #include "drivers/system.h"
40 #include "drivers/usb_io.h"
41 #include "drivers/nvic.h"
43 #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 static void (*ctrlLineStateCb)(void *context, uint16_t ctrlLineState);
58 static void *ctrlLineStateCbContext;
59 static void (*baudRateCb)(void *context, uint32_t baud);
60 static void *baudRateCbContext;
62 /* Extern variables ----------------------------------------------------------*/
64 /* Private function prototypes -----------------------------------------------*/
65 /* Private functions ---------------------------------------------------------*/
66 /*******************************************************************************
67 * Function Name : Set_System
68 * Description : Configures Main system clocks & power
69 * Input : None.
70 * Return : None.
71 *******************************************************************************/
72 void Set_System(void)
74 #if !defined(STM32L1XX_MD) && !defined(STM32L1XX_HD) && !defined(STM32L1XX_MD_PLUS)
75 GPIO_InitTypeDef GPIO_InitStructure;
76 #endif /* STM32L1XX_MD && STM32L1XX_XD */
78 #if defined(USB_USE_EXTERNAL_PULLUP)
79 GPIO_InitTypeDef GPIO_InitStructure;
80 #endif /* USB_USE_EXTERNAL_PULLUP */
82 /*!< At this stage the microcontroller clock setting is already configured,
83 this is done through SystemInit() function which is called from startup
84 file (startup_stm32f10x_xx.s) before to branch to application main.
85 To reconfigure the default setting of SystemInit() function, refer to
86 system_stm32f10x.c file
88 #if defined(STM32L1XX_MD) || defined(STM32L1XX_HD)|| defined(STM32L1XX_MD_PLUS) || defined(STM32F37X) || defined(STM32F303xC)
89 /* Enable the SYSCFG module clock */
90 RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
91 #endif /* STM32L1XX_XD */
93 usbGenerateDisconnectPulse();
95 #if defined(STM32F37X) || defined(STM32F303xC)
97 /*Set PA11,12 as IN - USB_DM,DP*/
98 RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOA, ENABLE);
99 GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11 | GPIO_Pin_12;
100 GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
101 GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
102 GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
103 GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
104 GPIO_Init(GPIOA, &GPIO_InitStructure);
106 /*SET PA11,12 for USB: USB_DM,DP*/
107 GPIO_PinAFConfig(GPIOA, GPIO_PinSource11, GPIO_AF_14);
108 GPIO_PinAFConfig(GPIOA, GPIO_PinSource12, GPIO_AF_14);
110 #endif /* STM32F37X && STM32F303xC)*/
112 // Initialise callbacks
113 ctrlLineStateCb = NULL;
114 baudRateCb = NULL;
116 /* Configure the EXTI line 18 connected internally to the USB IP */
117 EXTI_ClearITPendingBit(EXTI_Line18);
118 EXTI_InitStructure.EXTI_Line = EXTI_Line18;
119 EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
120 EXTI_InitStructure.EXTI_LineCmd = ENABLE;
121 EXTI_Init(&EXTI_InitStructure);
124 /*******************************************************************************
125 * Function Name : Set_USBClock
126 * Description : Configures USB Clock input (48MHz)
127 * Input : None.
128 * Return : None.
129 *******************************************************************************/
130 void Set_USBClock(void)
132 /* Select USBCLK source */
133 RCC_USBCLKConfig(RCC_USBCLKSource_PLLCLK_1Div5);
135 /* Enable the USB clock */
136 RCC_APB1PeriphClockCmd(RCC_APB1Periph_USB, ENABLE);
139 /*******************************************************************************
140 * Function Name : Enter_LowPowerMode
141 * Description : Power-off system clocks and power while entering suspend mode
142 * Input : None.
143 * Return : None.
144 *******************************************************************************/
145 void Enter_LowPowerMode(void)
147 /* Set the device state to suspend */
148 bDeviceState = SUSPENDED;
151 /*******************************************************************************
152 * Function Name : Leave_LowPowerMode
153 * Description : Restores system clocks and power while exiting suspend mode
154 * Input : None.
155 * Return : None.
156 *******************************************************************************/
157 void Leave_LowPowerMode(void)
159 DEVICE_INFO *pInfo = &Device_Info;
161 /* Set the device state to the correct state */
162 if (pInfo->Current_Configuration != 0) {
163 /* Device configured */
164 bDeviceState = CONFIGURED;
165 } else {
166 bDeviceState = ATTACHED;
168 /*Enable SystemCoreClock*/
169 SystemInit();
172 /*******************************************************************************
173 * Function Name : USB_Interrupts_Config
174 * Description : Configures the USB interrupts
175 * Input : None.
176 * Return : None.
177 *******************************************************************************/
178 void USB_Interrupts_Config(void)
180 NVIC_InitTypeDef NVIC_InitStructure;
182 /* 2 bit for pre-emption priority, 2 bits for subpriority */
183 NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING); // is this really neccesary?
185 /* Enable the USB interrupt */
186 NVIC_InitStructure.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn;
187 NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_USB);
188 NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_USB);
189 NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
190 NVIC_Init(&NVIC_InitStructure);
192 /* Enable the USB Wake-up interrupt */
193 NVIC_InitStructure.NVIC_IRQChannel = USBWakeUp_IRQn;
194 NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_USB_WUP);
195 NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_USB_WUP);
196 NVIC_Init(&NVIC_InitStructure);
199 /*******************************************************************************
200 * Function Name : USB_Cable_Config
201 * Description : Software Connection/Disconnection of USB Cable
202 * Input : None.
203 * Return : Status
204 *******************************************************************************/
205 void USB_Cable_Config(FunctionalState NewState)
207 UNUSED(NewState);
210 /*******************************************************************************
211 * Function Name : Get_SerialNum.
212 * Description : Create the serial number string descriptor.
213 * Input : None.
214 * Output : None.
215 * Return : None.
216 *******************************************************************************/
217 void Get_SerialNum(void)
219 uint32_t Device_Serial0, Device_Serial1, Device_Serial2;
221 Device_Serial0 = *(uint32_t*)ID1;
222 Device_Serial1 = *(uint32_t*)ID2;
223 Device_Serial2 = *(uint32_t*)ID3;
225 Device_Serial0 += Device_Serial2;
227 if (Device_Serial0 != 0) {
228 IntToUnicode(Device_Serial0, &Virtual_Com_Port_StringSerial[2], 8);
229 IntToUnicode(Device_Serial1, &Virtual_Com_Port_StringSerial[18], 4);
233 /*******************************************************************************
234 * Function Name : HexToChar.
235 * Description : Convert Hex 32Bits value into char.
236 * Input : None.
237 * Output : None.
238 * Return : None.
239 *******************************************************************************/
240 static void IntToUnicode(uint32_t value, uint8_t *pbuf, uint8_t len)
242 uint8_t idx = 0;
244 for (idx = 0; idx < len; idx++) {
245 if (((value >> 28)) < 0xA) {
246 pbuf[2 * idx] = (value >> 28) + '0';
247 } else {
248 pbuf[2 * idx] = (value >> 28) + 'A' - 10;
251 value = value << 4;
253 pbuf[2 * idx + 1] = 0;
257 /*******************************************************************************
258 * Function Name : Send DATA .
259 * Description : send the data received from the STM32 to the PC through USB
260 * Input : None.
261 * Output : None.
262 * Return : None.
263 *******************************************************************************/
264 uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength)
266 /* Last transmission hasn't finished, abort */
267 if (packetSent) {
268 return 0;
271 // We can only put 64 bytes in the buffer
272 if (sendLength > 64 / 2) {
273 sendLength = 64 / 2;
276 // Try to load some bytes if we can
277 if (sendLength) {
278 UserToPMABufferCopy(ptrBuffer, ENDP1_TXADDR, sendLength);
279 SetEPTxCount(ENDP1, sendLength);
280 packetSent += sendLength;
281 SetEPTxValid(ENDP1);
284 return sendLength;
287 uint32_t CDC_Send_FreeBytes(void)
289 /* this driver is blocking, so the buffer is unlimited */
290 return 255;
293 /*******************************************************************************
294 * Function Name : Receive DATA .
295 * Description : receive the data from the PC to STM32 and send it through USB
296 * Input : None.
297 * Output : None.
298 * Return : None.
299 *******************************************************************************/
300 uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len)
302 static uint8_t offset = 0;
303 uint8_t i;
305 if (len > receiveLength) {
306 len = receiveLength;
309 for (i = 0; i < len; i++) {
310 recvBuf[i] = (uint8_t)(receiveBuffer[i + offset]);
313 receiveLength -= len;
314 offset += len;
316 /* re-enable the rx endpoint which we had set to receive 0 bytes */
317 if (receiveLength == 0) {
318 SetEPRxCount(ENDP3, 64);
319 SetEPRxStatus(ENDP3, EP_RX_VALID);
320 offset = 0;
323 return len;
326 uint32_t CDC_Receive_BytesAvailable(void)
328 return receiveLength;
331 /*******************************************************************************
332 * Function Name : usbIsConfigured.
333 * Description : Determines if USB VCP is configured or not
334 * Input : None.
335 * Output : None.
336 * Return : True if configured.
337 *******************************************************************************/
338 uint8_t usbIsConfigured(void)
340 return (bDeviceState == CONFIGURED);
343 /*******************************************************************************
344 * Function Name : usbIsConnected.
345 * Description : Determines if USB VCP is connected ot not
346 * Input : None.
347 * Output : None.
348 * Return : True if connected.
349 *******************************************************************************/
350 uint8_t usbIsConnected(void)
352 return (bDeviceState != UNCONNECTED);
355 /*******************************************************************************
356 * Function Name : CDC_BaudRate.
357 * Description : Get the current baud rate
358 * Input : None.
359 * Output : None.
360 * Return : Baud rate in bps
361 *******************************************************************************/
362 uint32_t CDC_BaudRate(void)
364 return Virtual_Com_Port_GetBaudRate();
367 /*******************************************************************************
368 * Function Name : CDC_SetBaudRateCb
369 * Description : Set a callback to call when baud rate changes
370 * Input : callback function and context.
371 * Output : None.
372 * Return : None.
373 *******************************************************************************/
374 void CDC_SetBaudRateCb(void (*cb)(void *context, uint32_t baud), void *context)
376 baudRateCbContext = context;
377 baudRateCb = cb;
380 /*******************************************************************************
381 * Function Name : CDC_SetCtrlLineStateCb
382 * Description : Set a callback to call when control line state changes
383 * Input : callback function and context.
384 * Output : None.
385 * Return : None.
386 *******************************************************************************/
387 void CDC_SetCtrlLineStateCb(void (*cb)(void *context, uint16_t ctrlLineState), void *context)
389 ctrlLineStateCbContext = context;
390 ctrlLineStateCb = cb;
393 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/