[FLYWOOF411] add board documentation
[inav/snaewe.git] / src / main / vcp_hal / usbd_cdc_interface.c
blob82207670af3c127bd5f2974519b7fda780bd039b
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 ------------------------------------------------------------------*/
49 #include "stm32f7xx_hal.h"
50 #include "usbd_core.h"
51 #include "usbd_desc.h"
52 #include "usbd_cdc.h"
53 #include "usbd_cdc_interface.h"
54 #include "stdbool.h"
55 #include "drivers/time.h"
57 /* Private typedef -----------------------------------------------------------*/
58 /* Private define ------------------------------------------------------------*/
59 #define APP_RX_DATA_SIZE 4096
60 #define APP_TX_DATA_SIZE 4096
62 /* Private macro -------------------------------------------------------------*/
63 /* Private variables ---------------------------------------------------------*/
64 USBD_CDC_LineCodingTypeDef LineCoding =
66 115200, /* baud rate*/
67 0x00, /* stop bits-1*/
68 0x00, /* parity - none*/
69 0x08 /* nb. of bits 8*/
72 uint8_t UserRxBuffer[APP_RX_DATA_SIZE];/* Received Data over USB are stored in this buffer */
73 uint8_t UserTxBuffer[APP_TX_DATA_SIZE];/* Received Data over UART (CDC interface) are stored in this buffer */
74 uint32_t BuffLength;
75 uint32_t UserTxBufPtrIn = 0;/* Increment this pointer or roll it back to
76 start address when data are received over USART */
77 uint32_t UserTxBufPtrOut = 0; /* Increment this pointer or roll it back to
78 start address when data are sent over USB */
80 uint32_t rxAvailable = 0;
81 uint8_t* rxBuffPtr = NULL;
83 /* TIM handler declaration */
84 TIM_HandleTypeDef TimHandle;
85 /* USB handler declaration */
86 extern USBD_HandleTypeDef USBD_Device;
88 static void (*ctrlLineStateCb)(void *context, uint16_t ctrlLineState);
89 static void *ctrlLineStateCbContext;
90 static void (*baudRateCb)(void *context, uint32_t baud);
91 static void *baudRateCbContext;
93 /* Private function prototypes -----------------------------------------------*/
94 static int8_t CDC_Itf_Init(void);
95 static int8_t CDC_Itf_DeInit(void);
96 static int8_t CDC_Itf_Control(uint8_t cmd, uint8_t* pbuf, uint16_t length);
97 static int8_t CDC_Itf_Receive(uint8_t* pbuf, uint32_t *Len);
99 static void TIM_Config(void);
100 static void Error_Handler(void);
102 USBD_CDC_ItfTypeDef USBD_CDC_fops =
104 CDC_Itf_Init,
105 CDC_Itf_DeInit,
106 CDC_Itf_Control,
107 CDC_Itf_Receive
111 void TIMx_IRQHandler(void)
113 HAL_TIM_IRQHandler(&TimHandle);
116 /* Private functions ---------------------------------------------------------*/
119 * @brief CDC_Itf_Init
120 * Initializes the CDC media low layer
121 * @param None
122 * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
124 static int8_t CDC_Itf_Init(void)
126 /*##-3- Configure the TIM Base generation #################################*/
127 TIM_Config();
129 /*##-4- Start the TIM Base generation in interrupt mode ####################*/
130 /* Start Channel1 */
131 if (HAL_TIM_Base_Start_IT(&TimHandle) != HAL_OK)
133 /* Starting Error */
134 Error_Handler();
137 /*##-5- Set Application Buffers ############################################*/
138 USBD_CDC_SetTxBuffer(&USBD_Device, UserTxBuffer, 0);
139 USBD_CDC_SetRxBuffer(&USBD_Device, UserRxBuffer);
141 ctrlLineStateCb = NULL;
142 baudRateCb = NULL;
144 return (USBD_OK);
148 * @brief CDC_Itf_DeInit
149 * DeInitializes the CDC media low layer
150 * @param None
151 * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
153 static int8_t CDC_Itf_DeInit(void)
156 return (USBD_OK);
160 * @brief CDC_Itf_Control
161 * Manage the CDC class requests
162 * @param Cmd: Command code
163 * @param Buf: Buffer containing command data (request parameters)
164 * @param Len: Number of data to be sent (in bytes)
165 * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
167 static int8_t CDC_Itf_Control (uint8_t cmd, uint8_t* pbuf, uint16_t length)
169 LINE_CODING* plc = (LINE_CODING*)pbuf;
171 switch (cmd)
173 case CDC_SEND_ENCAPSULATED_COMMAND:
174 /* Add your code here */
175 break;
177 case CDC_GET_ENCAPSULATED_RESPONSE:
178 /* Add your code here */
179 break;
181 case CDC_SET_COMM_FEATURE:
182 /* Add your code here */
183 break;
185 case CDC_GET_COMM_FEATURE:
186 /* Add your code here */
187 break;
189 case CDC_CLEAR_COMM_FEATURE:
190 /* Add your code here */
191 break;
193 case CDC_SET_LINE_CODING:
194 if (pbuf && (length == sizeof (*plc))) {
195 LineCoding.bitrate = plc->bitrate;
196 LineCoding.format = plc->format;
197 LineCoding.paritytype = plc->paritytype;
198 LineCoding.datatype = plc->datatype;
200 // If a callback is provided, tell the upper driver of changes in baud rate
201 if (baudRateCb) {
202 baudRateCb(baudRateCbContext, LineCoding.bitrate);
206 break;
208 case CDC_GET_LINE_CODING:
209 if (pbuf && (length == sizeof (*plc))) {
210 plc->bitrate = LineCoding.bitrate;
211 plc->format = LineCoding.format;
212 plc->paritytype = LineCoding.paritytype;
213 plc->datatype = LineCoding.datatype;
215 break;
217 case CDC_SET_CONTROL_LINE_STATE:
218 // If a callback is provided, tell the upper driver of changes in DTR/RTS state
219 if (pbuf && (length == sizeof (uint16_t))) {
220 if (ctrlLineStateCb) {
221 ctrlLineStateCb(ctrlLineStateCbContext, *((uint16_t *)pbuf));
224 break;
226 case CDC_SEND_BREAK:
227 /* Add your code here */
228 break;
230 default:
231 break;
234 return (USBD_OK);
238 * @brief TIM period elapsed callback
239 * @param htim: TIM handle
240 * @retval None
242 void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
244 if (htim->Instance != TIMusb) return;
246 uint32_t buffptr;
247 uint32_t buffsize;
249 if (UserTxBufPtrOut != UserTxBufPtrIn)
251 if (UserTxBufPtrOut > UserTxBufPtrIn) /* Roll-back */
253 buffsize = APP_RX_DATA_SIZE - UserTxBufPtrOut;
255 else
257 buffsize = UserTxBufPtrIn - UserTxBufPtrOut;
260 buffptr = UserTxBufPtrOut;
262 USBD_CDC_SetTxBuffer(&USBD_Device, (uint8_t*)&UserTxBuffer[buffptr], buffsize);
264 if (USBD_CDC_TransmitPacket(&USBD_Device) == USBD_OK)
266 UserTxBufPtrOut += buffsize;
267 if (UserTxBufPtrOut == APP_TX_DATA_SIZE)
269 UserTxBufPtrOut = 0;
276 * @brief CDC_Itf_DataRx
277 * Data received over USB OUT endpoint are sent over CDC interface
278 * through this function.
279 * @param Buf: Buffer of data to be transmitted
280 * @param Len: Number of data received (in bytes)
281 * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
283 static int8_t CDC_Itf_Receive(uint8_t* Buf, uint32_t *Len)
285 rxAvailable = *Len;
286 rxBuffPtr = Buf;
287 if (!rxAvailable) {
288 // Received an empty packet, trigger receiving the next packet.
289 // This will happen after a packet that's exactly 64 bytes is received.
290 // The USB protocol requires that an empty (0 byte) packet immediately follow.
291 USBD_CDC_ReceivePacket(&USBD_Device);
293 return (USBD_OK);
297 * @brief TIM_Config: Configure TIMusb timer
298 * @param None.
299 * @retval None
301 static void TIM_Config(void)
303 /* Set TIMusb instance */
304 TimHandle.Instance = TIMusb;
306 /* Initialize TIMx peripheral as follow:
307 + Period = 10000 - 1
308 + Prescaler = ((SystemCoreClock/2)/10000) - 1
309 + ClockDivision = 0
310 + Counter direction = Up
312 TimHandle.Init.Period = (CDC_POLLING_INTERVAL*1000) - 1;
313 TimHandle.Init.Prescaler = (SystemCoreClock / 2 / (1000000)) - 1;
314 TimHandle.Init.ClockDivision = 0;
315 TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
316 if (HAL_TIM_Base_Init(&TimHandle) != HAL_OK)
318 /* Initialization Error */
319 Error_Handler();
322 /*##-6- Enable TIM peripherals Clock #######################################*/
323 TIMx_CLK_ENABLE();
325 /*##-7- Configure the NVIC for TIMx ########################################*/
326 /* Set Interrupt Group Priority */
327 HAL_NVIC_SetPriority(TIMx_IRQn, 6, 0);
329 /* Enable the TIMx global Interrupt */
330 HAL_NVIC_EnableIRQ(TIMx_IRQn);
334 * @brief This function is executed in case of error occurrence.
335 * @param None
336 * @retval None
338 static void Error_Handler(void)
340 /* Add your own code here */
343 uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len)
345 uint32_t count = 0;
346 if ( (rxBuffPtr != NULL))
348 while ((rxAvailable > 0) && count < len)
350 recvBuf[count] = rxBuffPtr[0];
351 rxBuffPtr++;
352 rxAvailable--;
353 count++;
354 if (rxAvailable < 1)
355 USBD_CDC_ReceivePacket(&USBD_Device);
358 return count;
361 uint32_t CDC_Receive_BytesAvailable(void)
363 return rxAvailable;
366 uint32_t CDC_Send_FreeBytes(void)
369 return the bytes free in the circular buffer
371 functionally equivalent to:
372 (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)
373 but without the impact of the condition check.
375 return ((UserTxBufPtrOut - UserTxBufPtrIn) + (-((int)(UserTxBufPtrOut <= UserTxBufPtrIn)) & APP_TX_DATA_SIZE)) - 1;
379 * @brief CDC_Send_DATA
380 * CDC received data to be send over USB IN endpoint are managed in
381 * this function.
382 * @param ptrBuffer: Buffer of data to be sent
383 * @param sendLength: Number of data to be sent (in bytes)
384 * @retval Bytes sent
386 uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength)
388 USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*)USBD_Device.pCDC_ClassData;
389 while (hcdc->TxState != 0);
391 for (uint32_t i = 0; i < sendLength; i++)
393 UserTxBuffer[UserTxBufPtrIn] = ptrBuffer[i];
394 UserTxBufPtrIn = (UserTxBufPtrIn + 1) % APP_TX_DATA_SIZE;
395 while (CDC_Send_FreeBytes() == 0) {
396 delay(1);
399 return sendLength;
403 /*******************************************************************************
404 * Function Name : usbIsConfigured.
405 * Description : Determines if USB VCP is configured or not
406 * Input : None.
407 * Output : None.
408 * Return : True if configured.
409 *******************************************************************************/
410 uint8_t usbIsConfigured(void)
412 return (USBD_Device.dev_state == USBD_STATE_CONFIGURED);
415 /*******************************************************************************
416 * Function Name : usbIsConnected.
417 * Description : Determines if USB VCP is connected ot not
418 * Input : None.
419 * Output : None.
420 * Return : True if connected.
421 *******************************************************************************/
422 uint8_t usbIsConnected(void)
424 return (USBD_Device.dev_state != USBD_STATE_DEFAULT);
427 /*******************************************************************************
428 * Function Name : CDC_BaudRate.
429 * Description : Get the current baud rate
430 * Input : None.
431 * Output : None.
432 * Return : Baud rate in bps
433 *******************************************************************************/
434 uint32_t CDC_BaudRate(void)
436 return LineCoding.bitrate;
439 /*******************************************************************************
440 * Function Name : CDC_SetBaudRateCb
441 * Description : Set a callback to call when baud rate changes
442 * Input : callback function and context.
443 * Output : None.
444 * Return : None.
445 *******************************************************************************/
446 void CDC_SetBaudRateCb(void (*cb)(void *context, uint32_t baud), void *context)
448 baudRateCbContext = context;
449 baudRateCb = cb;
452 /*******************************************************************************
453 * Function Name : CDC_SetCtrlLineStateCb
454 * Description : Set a callback to call when control line state changes
455 * Input : callback function and context.
456 * Output : None.
457 * Return : None.
458 *******************************************************************************/
459 void CDC_SetCtrlLineStateCb(void (*cb)(void *context, uint16_t ctrlLineState), void *context)
461 ctrlLineStateCbContext = context;
462 ctrlLineStateCb = cb;
465 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/