Merge pull request #11299 from daleckystepan/vtx-start-bit
[betaflight.git] / src / main / vcp_hal / usbd_cdc_interface.c
blobcda8f9fbe4ddb4b1b965f470eb489167109d6129
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 "build/atomic.h"
54 #include "usbd_conf.h"
55 #include "usbd_core.h"
56 #include "usbd_desc.h"
57 #include "usbd_cdc.h"
58 #include "usbd_cdc_interface.h"
59 #include "stdbool.h"
61 #include "drivers/nvic.h"
62 #include "drivers/serial_usb_vcp.h"
63 #include "drivers/time.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 // The CDC_Itf_TransmitCplt field was introduced in MiddleWare that comes with
108 // H7 V1.8.0.
109 // Other MCU can be add here as the MiddleWare version advances.
110 #ifdef STM32H7
111 static int8_t CDC_Itf_TransmitCplt(uint8_t *Buf, uint32_t *Len, uint8_t epnum);
112 #endif
114 static void TIM_Config(void);
115 static void Error_Handler(void);
117 USBD_CDC_ItfTypeDef USBD_CDC_fops =
119 CDC_Itf_Init,
120 CDC_Itf_DeInit,
121 CDC_Itf_Control,
122 CDC_Itf_Receive,
123 #ifdef STM32H7
124 CDC_Itf_TransmitCplt
125 #endif
129 void TIMx_IRQHandler(void)
131 HAL_TIM_IRQHandler(&TimHandle);
134 /* Private functions ---------------------------------------------------------*/
137 * @brief CDC_Itf_Init
138 * Initializes the CDC media low layer
139 * @param None
140 * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
142 static int8_t CDC_Itf_Init(void)
144 /*##-3- Configure the TIM Base generation #################################*/
145 TIM_Config();
147 /*##-4- Start the TIM Base generation in interrupt mode ####################*/
148 /* Start Channel1 */
149 if (HAL_TIM_Base_Start_IT(&TimHandle) != HAL_OK)
151 /* Starting Error */
152 Error_Handler();
155 /*##-5- Set Application Buffers ############################################*/
156 USBD_CDC_SetTxBuffer(&USBD_Device, (uint8_t *)UserTxBuffer, 0);
157 USBD_CDC_SetRxBuffer(&USBD_Device, (uint8_t *)UserRxBuffer);
159 ctrlLineStateCb = NULL;
160 baudRateCb = NULL;
162 return (USBD_OK);
166 * @brief CDC_Itf_DeInit
167 * DeInitializes the CDC media low layer
168 * @param None
169 * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
171 static int8_t CDC_Itf_DeInit(void)
174 return (USBD_OK);
178 * @brief CDC_Itf_Control
179 * Manage the CDC class requests
180 * @param Cmd: Command code
181 * @param Buf: Buffer containing command data (request parameters)
182 * @param Len: Number of data to be sent (in bytes)
183 * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
185 static int8_t CDC_Itf_Control (uint8_t cmd, uint8_t* pbuf, uint16_t length)
187 LINE_CODING* plc = (LINE_CODING*)pbuf;
189 switch (cmd)
191 case CDC_SEND_ENCAPSULATED_COMMAND:
192 /* Add your code here */
193 break;
195 case CDC_GET_ENCAPSULATED_RESPONSE:
196 /* Add your code here */
197 break;
199 case CDC_SET_COMM_FEATURE:
200 /* Add your code here */
201 break;
203 case CDC_GET_COMM_FEATURE:
204 /* Add your code here */
205 break;
207 case CDC_CLEAR_COMM_FEATURE:
208 /* Add your code here */
209 break;
211 case CDC_SET_LINE_CODING:
212 if (pbuf && (length == sizeof(*plc))) {
213 LineCoding.bitrate = plc->bitrate;
214 LineCoding.format = plc->format;
215 LineCoding.paritytype = plc->paritytype;
216 LineCoding.datatype = plc->datatype;
218 // If a callback is provided, tell the upper driver of changes in baud rate
219 if (baudRateCb) {
220 baudRateCb(baudRateCbContext, LineCoding.bitrate);
224 break;
226 case CDC_GET_LINE_CODING:
227 if (pbuf && (length == sizeof(*plc))) {
228 plc->bitrate = LineCoding.bitrate;
229 plc->format = LineCoding.format;
230 plc->paritytype = LineCoding.paritytype;
231 plc->datatype = LineCoding.datatype;
233 break;
235 case CDC_SET_CONTROL_LINE_STATE:
236 // If a callback is provided, tell the upper driver of changes in DTR/RTS state
237 if (pbuf && (length == sizeof(uint16_t))) {
238 if (ctrlLineStateCb) {
239 ctrlLineStateCb(ctrlLineStateCbContext, *((uint16_t *)pbuf));
242 break;
244 case CDC_SEND_BREAK:
245 /* Add your code here */
246 break;
248 default:
249 break;
252 return (USBD_OK);
256 * @brief TIM period elapsed callback
257 * @param htim: TIM handle
258 * @retval None
260 void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
262 if (htim->Instance != TIMusb) {
263 return;
266 uint32_t buffsize;
267 static uint32_t lastBuffsize = 0;
269 USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*)USBD_Device.pCDC_ClassData;
271 if (hcdc->TxState == 0) {
272 // endpoint has finished transmitting previous block
273 if (lastBuffsize) {
274 bool needZeroLengthPacket = lastBuffsize % 64 == 0;
276 // move the ring buffer tail based on the previous succesful transmission
277 UserTxBufPtrOut += lastBuffsize;
278 if (UserTxBufPtrOut == APP_TX_DATA_SIZE) {
279 UserTxBufPtrOut = 0;
281 lastBuffsize = 0;
283 if (needZeroLengthPacket) {
284 USBD_CDC_SetTxBuffer(&USBD_Device, (uint8_t*)&UserTxBuffer[UserTxBufPtrOut], 0);
285 return;
288 if (UserTxBufPtrOut != UserTxBufPtrIn) {
289 if (UserTxBufPtrOut > UserTxBufPtrIn) { /* Roll-back */
290 buffsize = APP_TX_DATA_SIZE - UserTxBufPtrOut;
291 } else {
292 buffsize = UserTxBufPtrIn - UserTxBufPtrOut;
294 if (buffsize > APP_TX_BLOCK_SIZE) {
295 buffsize = APP_TX_BLOCK_SIZE;
298 USBD_CDC_SetTxBuffer(&USBD_Device, (uint8_t*)&UserTxBuffer[UserTxBufPtrOut], buffsize);
300 if (USBD_CDC_TransmitPacket(&USBD_Device) == USBD_OK) {
301 lastBuffsize = buffsize;
308 * @brief CDC_Itf_DataRx
309 * Data received over USB OUT endpoint are sent over CDC interface
310 * through this function.
311 * @param Buf: Buffer of data to be transmitted
312 * @param Len: Number of data received (in bytes)
313 * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
315 static int8_t CDC_Itf_Receive(uint8_t* Buf, uint32_t *Len)
317 rxAvailable = *Len;
318 rxBuffPtr = Buf;
319 if (!rxAvailable) {
320 // Received an empty packet, trigger receiving the next packet.
321 // This will happen after a packet that's exactly 64 bytes is received.
322 // The USB protocol requires that an empty (0 byte) packet immediately follow.
323 USBD_CDC_ReceivePacket(&USBD_Device);
325 return (USBD_OK);
328 #ifdef STM32H7
329 static int8_t CDC_Itf_TransmitCplt(uint8_t *Buf, uint32_t *Len, uint8_t epnum)
331 UNUSED(Buf);
332 UNUSED(Len);
333 UNUSED(epnum);
335 return (USBD_OK);
337 #endif
340 * @brief TIM_Config: Configure TIMusb timer
341 * @param None.
342 * @retval None
344 static void TIM_Config(void)
346 /* Set TIMusb instance */
347 TimHandle.Instance = TIMusb;
349 /* Initialize TIMx peripheral as follow:
350 + Period = 10000 - 1
351 + Prescaler = ((SystemCoreClock/2)/10000) - 1
352 + ClockDivision = 0
353 + Counter direction = Up
355 TimHandle.Init.Period = (CDC_POLLING_INTERVAL*1000) - 1;
356 TimHandle.Init.Prescaler = (SystemCoreClock / 2 / (1000000)) - 1;
357 TimHandle.Init.ClockDivision = 0;
358 TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
359 if (HAL_TIM_Base_Init(&TimHandle) != HAL_OK)
361 /* Initialization Error */
362 Error_Handler();
365 /*##-6- Enable TIM peripherals Clock #######################################*/
366 TIMx_CLK_ENABLE();
368 /*##-7- Configure the NVIC for TIMx ########################################*/
369 /* Set Interrupt Group Priority */
370 HAL_NVIC_SetPriority(TIMx_IRQn, 6, 0);
372 /* Enable the TIMx global Interrupt */
373 HAL_NVIC_EnableIRQ(TIMx_IRQn);
377 * @brief This function is executed in case of error occurrence.
378 * @param None
379 * @retval None
381 static void Error_Handler(void)
383 /* Add your own code here */
386 uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len)
388 uint32_t count = 0;
389 if ( (rxBuffPtr != NULL))
391 while ((rxAvailable > 0) && count < len)
393 recvBuf[count] = rxBuffPtr[0];
394 rxBuffPtr++;
395 rxAvailable--;
396 count++;
397 if (rxAvailable < 1)
398 USBD_CDC_ReceivePacket(&USBD_Device);
401 return count;
404 uint32_t CDC_Receive_BytesAvailable(void)
406 return rxAvailable;
409 uint32_t CDC_Send_FreeBytes(void)
412 return the bytes free in the circular buffer
414 functionally equivalent to:
415 (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)
416 but without the impact of the condition check.
418 uint32_t freeBytes;
420 ATOMIC_BLOCK(NVIC_BUILD_PRIORITY(6, 0)) {
421 freeBytes = ((UserTxBufPtrOut - UserTxBufPtrIn) + (-((int)(UserTxBufPtrOut <= UserTxBufPtrIn)) & APP_TX_DATA_SIZE)) - 1;
424 return freeBytes;
428 * @brief CDC_Send_DATA
429 * CDC received data to be send over USB IN endpoint are managed in
430 * this function.
431 * @param ptrBuffer: Buffer of data to be sent
432 * @param sendLength: Number of data to be sent (in bytes)
433 * @retval Bytes sent
435 uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength)
437 for (uint32_t i = 0; i < sendLength; i++) {
438 while (CDC_Send_FreeBytes() == 0) {
439 // block until there is free space in the ring buffer
440 delay(1);
442 ATOMIC_BLOCK(NVIC_BUILD_PRIORITY(6, 0)) { // Paranoia
443 UserTxBuffer[UserTxBufPtrIn] = ptrBuffer[i];
444 UserTxBufPtrIn = (UserTxBufPtrIn + 1) % APP_TX_DATA_SIZE;
447 return sendLength;
451 /*******************************************************************************
452 * Function Name : usbIsConfigured.
453 * Description : Determines if USB VCP is configured or not
454 * Input : None.
455 * Output : None.
456 * Return : True if configured.
457 *******************************************************************************/
458 uint8_t usbIsConfigured(void)
460 return (USBD_Device.dev_state == USBD_STATE_CONFIGURED);
463 /*******************************************************************************
464 * Function Name : usbIsConnected.
465 * Description : Determines if USB VCP is connected ot not
466 * Input : None.
467 * Output : None.
468 * Return : True if connected.
469 *******************************************************************************/
470 uint8_t usbIsConnected(void)
472 return (USBD_Device.dev_state != USBD_STATE_DEFAULT);
475 /*******************************************************************************
476 * Function Name : CDC_BaudRate.
477 * Description : Get the current baud rate
478 * Input : None.
479 * Output : None.
480 * Return : Baud rate in bps
481 *******************************************************************************/
482 uint32_t CDC_BaudRate(void)
484 return LineCoding.bitrate;
487 /*******************************************************************************
488 * Function Name : CDC_SetBaudRateCb
489 * Description : Set a callback to call when baud rate changes
490 * Input : callback function and context.
491 * Output : None.
492 * Return : None.
493 *******************************************************************************/
494 void CDC_SetBaudRateCb(void (*cb)(void *context, uint32_t baud), void *context)
496 baudRateCbContext = context;
497 baudRateCb = cb;
500 /*******************************************************************************
501 * Function Name : CDC_SetCtrlLineStateCb
502 * Description : Set a callback to call when control line state changes
503 * Input : callback function and context.
504 * Output : None.
505 * Return : None.
506 *******************************************************************************/
507 void CDC_SetCtrlLineStateCb(void (*cb)(void *context, uint16_t ctrlLineState), void *context)
509 ctrlLineStateCbContext = context;
510 ctrlLineStateCb = cb;
513 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/