Fix missing 'platform.h' includes in compilation units, and make them stay away.
[betaflight.git] / src / main / vcp_hal / usbd_cdc_interface.c
blob98e9640dad99c2d2f4eba7f2e3a91ab924dd7c2c
1 /**
2 ******************************************************************************
3 * @file USB_Device/CDC_Standalone/Src/usbd_cdc_interface.c
4 * @author MCD Application Team
5 * @version V1.0.0
6 * @date 22-April-2016
7 * @brief Source file for USBD CDC interface
8 ******************************************************************************
9 * @attention
11 * <h2><center>&copy; Copyright (c) 2016 STMicroelectronics International N.V.
12 * All rights reserved.</center></h2>
14 * Redistribution and use in source and binary forms, with or without
15 * modification, are permitted, provided that the following conditions are met:
17 * 1. Redistribution of source code must retain the above copyright notice,
18 * this list of conditions and the following disclaimer.
19 * 2. Redistributions in binary form must reproduce the above copyright notice,
20 * this list of conditions and the following disclaimer in the documentation
21 * and/or other materials provided with the distribution.
22 * 3. Neither the name of STMicroelectronics nor the names of other
23 * contributors to this software may be used to endorse or promote products
24 * derived from this software without specific written permission.
25 * 4. This software, including modifications and/or derivative works of this
26 * software, must execute solely and exclusively on microcontroller or
27 * microprocessor devices manufactured by or for STMicroelectronics.
28 * 5. Redistribution and use of this software other than as permitted under
29 * this license is void and will automatically terminate your rights under
30 * this license.
32 * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
33 * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
34 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
35 * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
36 * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
37 * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
38 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
39 * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
40 * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
41 * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
42 * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
43 * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
45 ******************************************************************************
48 /* Includes ------------------------------------------------------------------*/
50 #include "platform.h"
52 #include "drivers/serial_usb_vcp.h"
53 #include "drivers/time.h"
55 #include "stm32f7xx_hal.h"
56 #include "usbd_core.h"
57 #include "usbd_desc.h"
58 #include "usbd_cdc.h"
59 #include "usbd_cdc_interface.h"
60 #include "stdbool.h"
62 #include "drivers/nvic.h"
63 #include "build/atomic.h"
65 /* Private typedef -----------------------------------------------------------*/
66 /* Private define ------------------------------------------------------------*/
67 #define APP_RX_DATA_SIZE 2048
68 #define APP_TX_DATA_SIZE 2048
70 #define APP_TX_BLOCK_SIZE 512
72 /* Private macro -------------------------------------------------------------*/
73 /* Private variables ---------------------------------------------------------*/
74 USBD_CDC_LineCodingTypeDef LineCoding =
76 115200, /* baud rate*/
77 0x00, /* stop bits-1*/
78 0x00, /* parity - none*/
79 0x08 /* nb. of bits 8*/
82 volatile uint8_t UserRxBuffer[APP_RX_DATA_SIZE];/* Received Data over USB are stored in this buffer */
83 volatile uint8_t UserTxBuffer[APP_TX_DATA_SIZE];/* Received Data over UART (CDC interface) are stored in this buffer */
84 uint32_t BuffLength;
85 volatile uint32_t UserTxBufPtrIn = 0;/* Increment this pointer or roll it back to
86 start address when data are received over USART */
87 volatile uint32_t UserTxBufPtrOut = 0; /* Increment this pointer or roll it back to
88 start address when data are sent over USB */
90 uint32_t rxAvailable = 0;
91 uint8_t* rxBuffPtr = NULL;
93 /* TIM handler declaration */
94 TIM_HandleTypeDef TimHandle;
96 static void (*ctrlLineStateCb)(void *context, uint16_t ctrlLineState);
97 static void *ctrlLineStateCbContext;
98 static void (*baudRateCb)(void *context, uint32_t baud);
99 static void *baudRateCbContext;
101 /* Private function prototypes -----------------------------------------------*/
102 static int8_t CDC_Itf_Init(void);
103 static int8_t CDC_Itf_DeInit(void);
104 static int8_t CDC_Itf_Control(uint8_t cmd, uint8_t* pbuf, uint16_t length);
105 static int8_t CDC_Itf_Receive(uint8_t* pbuf, uint32_t *Len);
107 static void TIM_Config(void);
108 static void Error_Handler(void);
110 USBD_CDC_ItfTypeDef USBD_CDC_fops =
112 CDC_Itf_Init,
113 CDC_Itf_DeInit,
114 CDC_Itf_Control,
115 CDC_Itf_Receive
119 void TIMx_IRQHandler(void)
121 HAL_TIM_IRQHandler(&TimHandle);
124 /* Private functions ---------------------------------------------------------*/
127 * @brief CDC_Itf_Init
128 * Initializes the CDC media low layer
129 * @param None
130 * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
132 static int8_t CDC_Itf_Init(void)
134 /*##-3- Configure the TIM Base generation #################################*/
135 TIM_Config();
137 /*##-4- Start the TIM Base generation in interrupt mode ####################*/
138 /* Start Channel1 */
139 if (HAL_TIM_Base_Start_IT(&TimHandle) != HAL_OK)
141 /* Starting Error */
142 Error_Handler();
145 /*##-5- Set Application Buffers ############################################*/
146 USBD_CDC_SetTxBuffer(&USBD_Device, (uint8_t *)UserTxBuffer, 0);
147 USBD_CDC_SetRxBuffer(&USBD_Device, (uint8_t *)UserRxBuffer);
149 ctrlLineStateCb = NULL;
150 baudRateCb = NULL;
152 return (USBD_OK);
156 * @brief CDC_Itf_DeInit
157 * DeInitializes the CDC media low layer
158 * @param None
159 * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
161 static int8_t CDC_Itf_DeInit(void)
164 return (USBD_OK);
168 * @brief CDC_Itf_Control
169 * Manage the CDC class requests
170 * @param Cmd: Command code
171 * @param Buf: Buffer containing command data (request parameters)
172 * @param Len: Number of data to be sent (in bytes)
173 * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
175 static int8_t CDC_Itf_Control (uint8_t cmd, uint8_t* pbuf, uint16_t length)
177 LINE_CODING* plc = (LINE_CODING*)pbuf;
179 switch (cmd)
181 case CDC_SEND_ENCAPSULATED_COMMAND:
182 /* Add your code here */
183 break;
185 case CDC_GET_ENCAPSULATED_RESPONSE:
186 /* Add your code here */
187 break;
189 case CDC_SET_COMM_FEATURE:
190 /* Add your code here */
191 break;
193 case CDC_GET_COMM_FEATURE:
194 /* Add your code here */
195 break;
197 case CDC_CLEAR_COMM_FEATURE:
198 /* Add your code here */
199 break;
201 case CDC_SET_LINE_CODING:
202 if (pbuf && (length == sizeof (*plc))) {
203 LineCoding.bitrate = plc->bitrate;
204 LineCoding.format = plc->format;
205 LineCoding.paritytype = plc->paritytype;
206 LineCoding.datatype = plc->datatype;
208 // If a callback is provided, tell the upper driver of changes in baud rate
209 if (baudRateCb) {
210 baudRateCb(baudRateCbContext, LineCoding.bitrate);
214 break;
216 case CDC_GET_LINE_CODING:
217 if (pbuf && (length == sizeof (*plc))) {
218 plc->bitrate = LineCoding.bitrate;
219 plc->format = LineCoding.format;
220 plc->paritytype = LineCoding.paritytype;
221 plc->datatype = LineCoding.datatype;
223 break;
225 case CDC_SET_CONTROL_LINE_STATE:
226 // If a callback is provided, tell the upper driver of changes in DTR/RTS state
227 if (pbuf && (length == sizeof (uint16_t))) {
228 if (ctrlLineStateCb) {
229 ctrlLineStateCb(ctrlLineStateCbContext, *((uint16_t *)pbuf));
232 break;
234 case CDC_SEND_BREAK:
235 /* Add your code here */
236 break;
238 default:
239 break;
242 return (USBD_OK);
246 * @brief TIM period elapsed callback
247 * @param htim: TIM handle
248 * @retval None
250 void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
252 if (htim->Instance != TIMusb) {
253 return;
256 uint32_t buffsize;
257 static uint32_t lastBuffsize = 0;
259 USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*)USBD_Device.pCDC_ClassData;
261 if (hcdc->TxState == 0) {
262 // endpoint has finished transmitting previous block
263 if (lastBuffsize) {
264 // move the ring buffer tail based on the previous succesful transmission
265 UserTxBufPtrOut += lastBuffsize;
266 if (UserTxBufPtrOut == APP_TX_DATA_SIZE) {
267 UserTxBufPtrOut = 0;
269 lastBuffsize = 0;
271 if (UserTxBufPtrOut != UserTxBufPtrIn) {
272 if (UserTxBufPtrOut > UserTxBufPtrIn) { /* Roll-back */
273 buffsize = APP_TX_DATA_SIZE - UserTxBufPtrOut;
274 } else {
275 buffsize = UserTxBufPtrIn - UserTxBufPtrOut;
277 if (buffsize > APP_TX_BLOCK_SIZE) {
278 buffsize = APP_TX_BLOCK_SIZE;
281 USBD_CDC_SetTxBuffer(&USBD_Device, (uint8_t*)&UserTxBuffer[UserTxBufPtrOut], buffsize);
283 if (USBD_CDC_TransmitPacket(&USBD_Device) == USBD_OK) {
284 lastBuffsize = buffsize;
291 * @brief CDC_Itf_DataRx
292 * Data received over USB OUT endpoint are sent over CDC interface
293 * through this function.
294 * @param Buf: Buffer of data to be transmitted
295 * @param Len: Number of data received (in bytes)
296 * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
298 static int8_t CDC_Itf_Receive(uint8_t* Buf, uint32_t *Len)
300 rxAvailable = *Len;
301 rxBuffPtr = Buf;
302 return (USBD_OK);
306 * @brief TIM_Config: Configure TIMusb timer
307 * @param None.
308 * @retval None
310 static void TIM_Config(void)
312 /* Set TIMusb instance */
313 TimHandle.Instance = TIMusb;
315 /* Initialize TIMx peripheral as follow:
316 + Period = 10000 - 1
317 + Prescaler = ((SystemCoreClock/2)/10000) - 1
318 + ClockDivision = 0
319 + Counter direction = Up
321 TimHandle.Init.Period = (CDC_POLLING_INTERVAL*1000) - 1;
322 TimHandle.Init.Prescaler = (SystemCoreClock / 2 / (1000000)) - 1;
323 TimHandle.Init.ClockDivision = 0;
324 TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
325 if (HAL_TIM_Base_Init(&TimHandle) != HAL_OK)
327 /* Initialization Error */
328 Error_Handler();
331 /*##-6- Enable TIM peripherals Clock #######################################*/
332 TIMx_CLK_ENABLE();
334 /*##-7- Configure the NVIC for TIMx ########################################*/
335 /* Set Interrupt Group Priority */
336 HAL_NVIC_SetPriority(TIMx_IRQn, 6, 0);
338 /* Enable the TIMx global Interrupt */
339 HAL_NVIC_EnableIRQ(TIMx_IRQn);
343 * @brief This function is executed in case of error occurrence.
344 * @param None
345 * @retval None
347 static void Error_Handler(void)
349 /* Add your own code here */
352 uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len)
354 uint32_t count = 0;
355 if ( (rxBuffPtr != NULL))
357 while ((rxAvailable > 0) && count < len)
359 recvBuf[count] = rxBuffPtr[0];
360 rxBuffPtr++;
361 rxAvailable--;
362 count++;
363 if (rxAvailable < 1)
364 USBD_CDC_ReceivePacket(&USBD_Device);
367 return count;
370 uint32_t CDC_Receive_BytesAvailable(void)
372 return rxAvailable;
375 uint32_t CDC_Send_FreeBytes(void)
378 return the bytes free in the circular buffer
380 functionally equivalent to:
381 (APP_Rx_ptr_out > APP_Rx_ptr_in ? APP_Rx_ptr_out - APP_Rx_ptr_in : APP_RX_DATA_SIZE - APP_Rx_ptr_in + APP_Rx_ptr_in)
382 but without the impact of the condition check.
384 uint32_t freeBytes;
386 ATOMIC_BLOCK(NVIC_BUILD_PRIORITY(6, 0)) {
387 freeBytes = ((UserTxBufPtrOut - UserTxBufPtrIn) + (-((int)(UserTxBufPtrOut <= UserTxBufPtrIn)) & APP_TX_DATA_SIZE)) - 1;
390 return freeBytes;
394 * @brief CDC_Send_DATA
395 * CDC received data to be send over USB IN endpoint are managed in
396 * this function.
397 * @param ptrBuffer: Buffer of data to be sent
398 * @param sendLength: Number of data to be sent (in bytes)
399 * @retval Bytes sent
401 uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength)
403 for (uint32_t i = 0; i < sendLength; i++) {
404 while (CDC_Send_FreeBytes() == 0) {
405 // block until there is free space in the ring buffer
406 delay(1);
408 ATOMIC_BLOCK(NVIC_BUILD_PRIORITY(6, 0)) { // Paranoia
409 UserTxBuffer[UserTxBufPtrIn] = ptrBuffer[i];
410 UserTxBufPtrIn = (UserTxBufPtrIn + 1) % APP_TX_DATA_SIZE;
413 return sendLength;
417 /*******************************************************************************
418 * Function Name : usbIsConfigured.
419 * Description : Determines if USB VCP is configured or not
420 * Input : None.
421 * Output : None.
422 * Return : True if configured.
423 *******************************************************************************/
424 uint8_t usbIsConfigured(void)
426 return (USBD_Device.dev_state == USBD_STATE_CONFIGURED);
429 /*******************************************************************************
430 * Function Name : usbIsConnected.
431 * Description : Determines if USB VCP is connected ot not
432 * Input : None.
433 * Output : None.
434 * Return : True if connected.
435 *******************************************************************************/
436 uint8_t usbIsConnected(void)
438 return (USBD_Device.dev_state != USBD_STATE_DEFAULT);
441 /*******************************************************************************
442 * Function Name : CDC_BaudRate.
443 * Description : Get the current baud rate
444 * Input : None.
445 * Output : None.
446 * Return : Baud rate in bps
447 *******************************************************************************/
448 uint32_t CDC_BaudRate(void)
450 return LineCoding.bitrate;
453 /*******************************************************************************
454 * Function Name : CDC_SetBaudRateCb
455 * Description : Set a callback to call when baud rate changes
456 * Input : callback function and context.
457 * Output : None.
458 * Return : None.
459 *******************************************************************************/
460 void CDC_SetBaudRateCb(void (*cb)(void *context, uint32_t baud), void *context)
462 baudRateCbContext = context;
463 baudRateCb = cb;
466 /*******************************************************************************
467 * Function Name : CDC_SetCtrlLineStateCb
468 * Description : Set a callback to call when control line state changes
469 * Input : callback function and context.
470 * Output : None.
471 * Return : None.
472 *******************************************************************************/
473 void CDC_SetCtrlLineStateCb(void (*cb)(void *context, uint16_t ctrlLineState), void *context)
475 ctrlLineStateCbContext = context;
476 ctrlLineStateCb = cb;
479 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/