APM:Libraries
usb.c
Go to the documentation of this file.
1 /*
2 (c) 2017 night_ghost@ykoctpa.ru
3 
4 */
5 
6 #include <usb.h>
7 #include <hal.h>
8 #include <systick.h>
9 #include <exti.h>
10 #include <stdio.h>
11 #include <stdlib.h>
12 #include <string.h>
13 #include <boards.h>
14 
15 // bugfixes to ST USB stack - https://github.com/olegv142/stm32tivc_usb_cdc
16 // register description - http://mcu.goodboard.ru/viewtopic.php?id=40
17 
18 
19 /*
20  на поржать - https://kincajou.livejournal.com/4206484.html
21  товарисч копает USB :)
22 
23 */
24 
25 
26 //#define USB_DEBUG
27 
28 typedef uint8_t U8;
29 typedef uint32_t U32;
30 typedef uint16_t U16;
31 
32 
34 extern uint32_t USBD_OTG_ISR_Handler (const USB_OTG_CORE_HANDLE *pdev);
35 
37 
39 static volatile U8 VCP_DTRHIGH = 0;
40 static volatile U8 VCP_RTSHIGH = 0;
41 
47 };
48 
50 
52 //static const U16 txfifo_size = USB_TXFIFO_SIZE;
53 
54 static ring_buffer _rxfifo IN_CCM;
55 //static ring_buffer _txfifo;
56 
57 static ring_buffer *rxfifo = &_rxfifo; /* Rx FIFO */
58 //static ring_buffer *txfifo = &_txfifo; /* Rx FIFO */
59 
60 static uint8_t rx_buf[USB_RXFIFO_SIZE]; // USB can work via DMA so no CCM!
61 //static uint8_t tx_buf[USB_TXFIFO_SIZE];
62 
64 static U8 usb_ready;
65 
66 static U8 UsbTXBlock = 1;
67 
68 
69 LINE_CODING linecoding = // not const!
70  {
71  115200, /* baud rate*/
72  0x00, /* stop bits-1*/
73  0x00, /* parity - none*/
74  0x08 /* nb. of bits 8*/
75  };
76 
77 /* These are external variables imported from CDC core to be used for IN
78  transfer management. */
79 extern U8 APP_Rx_Buffer []; /* Write CDC received data in this buffer.
80  These data will be sent over USB IN endpoint
81  in the CDC core functions. */
82 extern U32 APP_Rx_ptr_in; /* Increment this pointer or roll it back to
83  start address when writing received data
84  in the buffer APP_Rx_Buffer. */
85 
86 /* Private function prototypes -----------------------------------------------*/
87 static U16 VCP_Init (void);
88 static U16 VCP_DeInit (void);
89 static U16 VCP_Ctrl (uint32_t Cmd, uint8_t* Buf, uint32_t Len);
90 static U16 VCP_DataTx (const uint8_t* Buf, uint32_t Len);
91 static U16 VCP_DataRx (uint8_t* Buf, uint32_t Len);
92 
93 // direct usage from usbd_cdc_core.c
95 {
96  VCP_Init,
97  VCP_DeInit,
98  VCP_Ctrl,
99  VCP_DataTx,
100  VCP_DataRx
101 };
102 
104 {
112 };
113 
114 
115 
116 static const USBD_DEVICE USR_CDC_desc =
117 {
125 
126 };
127 
128 /* USB Standard Device Descriptor */
130  {
131  0x12, /*bLength */
132  USB_DEVICE_DESCRIPTOR_TYPE, /*bDescriptorType*/
133  0x00, /*bcdUSB */
134  0x02,
135  0x00, /*bDeviceClass*/
136  0x00, /*bDeviceSubClass*/
137  0x00, /*bDeviceProtocol*/
138  USB_OTG_MAX_EP0_SIZE, /*bMaxPacketSize*/
139  LOBYTE(USBD_VID), /*idVendor*/
140  HIBYTE(USBD_VID), /*idVendor*/
141  LOBYTE(USBD_PID), /*idVendor*/
142  HIBYTE(USBD_PID), /*idVendor*/
143  0x00, /*bcdDevice rel. 2.00*/
144  0x02,
145  USBD_IDX_MFC_STR, /*Index of manufacturer string*/
146  USBD_IDX_PRODUCT_STR, /*Index of product string*/
147  USBD_IDX_SERIAL_STR, /*Index of serial number string*/
148  USBD_CFG_MAX_NUM /*bNumConfigurations*/
149  } ; /* USB_DeviceDescriptor */
150 
151 /* USB Standard Device Descriptor */
153 {
156  0x00,
157  0x02,
158  0x00,
159  0x00,
160  0x00,
161  0x40,
162  0x01,
163  0x00,
164 };
165 
166 
167 // handler for hardware ISR
169 {
170  USBD_OTG_ISR_Handler(&USB_OTG_dev);
171 }
172 
173 
174 /* USB Standard Device Descriptor */
176 {
181 };
182 
183 
184 static U8 usb_connected =0;
185 static U8 usb_opened =0;
186 
187 /* Return the device descriptor */
189 {
190  *length = sizeof(USBD_DeviceDesc);
191  return (U8 *)USBD_DeviceDesc;
192 }
193 
194 /* return the LangID string descriptor */
196 {
197  *length = sizeof(USBD_LangIDDesc);
198  return (U8 *)USBD_LangIDDesc;
199 }
200 
201 
202 
203 /* return the product string descriptor */
205 {
207 
208  return USBD_StrDesc;
209 }
210 
211 /* return the manufacturer string descriptor */
213 {
215  return USBD_StrDesc;
216 }
217 
218 /* return the serial number string descriptor */
220 {
222  return USBD_StrDesc;
223 }
224 
225 /* return the configuration string descriptor */
227 {
229  return USBD_StrDesc;
230 }
231 
232 
233 /* return the interface string descriptor */
235 {
237  return USBD_StrDesc;
238 }
239 
240 void USBD_USR_Init(void)
241 {
242  usb_connected = 0;
243  usb_opened = 0;
244 }
245 
246 void USBD_USR_DeviceReset(uint8_t speed )
247 {
248  switch (speed) {
249  case USB_OTG_SPEED_HIGH:
250  break;
251  case USB_OTG_SPEED_FULL:
252  break;
253  default:
254  break;
255  }
256 }
257 
259 {
260  usb_connected = 1;
261  usb_opened = 1; // just for case
262 }
263 
265 {
266  usb_connected = 0;
267  usb_opened = 0;
268 }
269 
270 
272 {
273  usb_connected = 1;
274  usb_opened = 1; // just for case
275 }
276 
277 
279 {
280  usb_connected = 1;
281  usb_opened = 1; // just for case
282 }
283 
284 
286 {
287  usb_connected = 0;
288  usb_opened = 0;
289 
290  extern void usb_mass_mal_USBdisconnect();
291  usb_mass_mal_USBdisconnect(); //reset connection state for mass-storage
292 }
293 
294 /*------------------------- usb_default_attr -------------------------------*/
295 
297 {
298  attr->preempt_prio = 0;
299  attr->sub_prio = 0;
300  attr->use_present_pin = 0;
301 // attr->description = NULL;
302 // attr->manufacturer = NULL;
303 // attr->serial_number = NULL;
304 // attr->configuration = NULL;
305 // attr->interface = NULL;
306 }
307 
308 /*--------------------------- usb_periphcfg -------------------------------*/
309 
310 void USB_OTG_BSP_Init(USB_OTG_CORE_HANDLE *pdev){ // callback for hardware init
311  return;
312 }
313 
314 int usb_periphcfg(FunctionalState state)
315 {
316  USB_OTG_BSP_DisableInterrupt(); // disable IRQ
317 
318  if (state == ENABLE) {
319 
320  RCC_AHB1PeriphClockCmd( RCC_AHB1Periph_GPIOA , ENABLE); // USB on GPIO_A
321 
322  /* Configure USB D-/D+ (DM/DP) pins */
323  GPIO_InitTypeDef GPIO_InitStructure;
324  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11 | GPIO_Pin_12; // sometimes touching of GPIO_Pin_12 causes interrupt which will not be served
325  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
326  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
327  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
328  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
329  GPIO_Init(GPIOA, &GPIO_InitStructure);
330 
331  gpio_set_af_mode(_GPIOA, GPIO_PinSource11, GPIO_AF_OTG1_FS);
332  gpio_set_af_mode(_GPIOA, GPIO_PinSource12, GPIO_AF_OTG1_FS);
333 
334 
335  RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
336  RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS, ENABLE) ;
337  } else {
340  // we should not disable sysfg clock..
341  }
342 
343  RCC_AHB2PeriphClockCmd(USB_CLOCK, state);
344 
345  return 1;
346 }
347 
348 /*--------------------------- usb_configure -------------------------------*/
349 
351 {
352  if (attr == NULL)
353  return 0;
354 
355  usb_setParams(attr);
356 
357  // USB Device Initialize
358  USBD_Init(&USB_OTG_dev, USB_OTG_FS_CORE_ID, &USR_CDC_desc, &USBD_CDC_cb, &USR_cb);
359 
360  usb_ready = 1;
361 
362  return 1;
363 }
364 
366 {
367  if (attr == NULL)
368  return;
369 
370  if (attr->use_present_pin) {
371  if (!IS_GPIO_ALL_PERIPH(attr->present_port->GPIOx) || !IS_GPIO_PIN_SOURCE(attr->present_pin))
372  return;
374  }
375 
376  preempt_prio = attr->preempt_prio;
377  sub_prio = attr->sub_prio;
378 }
379 
380 
381 
382 
384 {
385  enable_nvic_irq(OTG_FS_IRQn, preempt_prio);
386 }
387 
389 {
390  NVIC_DisableIRQ(OTG_FS_IRQn);
391 }
392 
393 void USB_OTG_BSP_mDelay (const uint32_t msec)
394 {
395  uint32_t start = hal_micros(), ms = msec;
396 
397  while (ms > 0) {
398  while ((hal_micros() - start) >= 1000) {
399  ms--;
400  if (ms == 0) break;
401  start += 1000;
402  }
403  }
404 }
405 
406 
407 
408 
409 
410 
411 
412 
413 
414 /* VCP_Init
415  * Initializes the Media on the STM32
416  * @param None
417  * @retval Result of the opeartion (USBD_OK in all cases)
418  */
419 static U16 VCP_Init(void)
420 {
421  rb_init(rxfifo, rxfifo_size, rx_buf);
422 // rb_init(txfifo, txfifo_size, tx_buf);
423  return USBD_OK;
424 }
425 
426 /* VCP_DeInit
427  * DeInitializes the Media on the STM32
428  * @param None
429  * @retval Result of the opeartion (USBD_OK in all cases)
430  */
431 static U16 VCP_DeInit(void)
432 {
433  return USBD_OK;
434 }
435 
436 
437 /* VCP_Ctrl
438  * Manage the CDC class requests
439  * @param Cmd: Command code
440  * @param Buf: Buffer containing command data (request parameters)
441  * @param Len: Number of data to be sent (in bytes)
442  * @retval Result of the opeartion (USBD_OK in all cases)
443  */
444 static U16 VCP_Ctrl (U32 Cmd, U8 *Buf, U32 Len)
445 {
446  switch (Cmd) {
448  /* Not needed for this driver */
449  break;
450 
452  /* Not needed for this driver */
453  break;
454 
455  case SET_COMM_FEATURE:
456  /* Not needed for this driver */
457  break;
458 
459  case GET_COMM_FEATURE:
460  /* Not needed for this driver */
461  break;
462 
463  case CLEAR_COMM_FEATURE:
464  /* Not needed for this driver */
465  break;
466 
467  case SET_LINE_CODING:
468  linecoding.bitrate = (uint32_t)(Buf[0] | (Buf[1] << 8) | (Buf[2] << 16) | (Buf[3] << 24));
469  linecoding.format = Buf[4];
470  linecoding.paritytype = Buf[5];
471  linecoding.datatype = Buf[6];
472  /* Set the new configuration */
473  break;
474 
475  case GET_LINE_CODING:
476  Buf[0] = (uint8_t)(linecoding.bitrate);
477  Buf[1] = (uint8_t)(linecoding.bitrate >> 8);
478  Buf[2] = (uint8_t)(linecoding.bitrate >> 16);
479  Buf[3] = (uint8_t)(linecoding.bitrate >> 24);
480  Buf[4] = linecoding.format;
481  Buf[5] = linecoding.paritytype;
482  Buf[6] = linecoding.datatype;
483  break;
484 
485 
486 #define USB_CDCACM_CONTROL_LINE_DTR (0x01)
487 #define USB_CDCACM_CONTROL_LINE_RTS (0x02)
488 
489 
491  linecoding.bitrate = (uint32_t)(Buf[0] | (Buf[1] << 8));
492 
495 
496 #ifdef DEBUG_BUILD
497 // { from Arduino32
498 // We need to see a negative edge on DTR before we start looking
499  // for the in-band magic reset byte sequence.
500  uint8_t dtr = VCP_DTRHIGH;
501  switch (reset_state) {
502  case DTR_UNSET:
503  reset_state = dtr ? DTR_HIGH : DTR_LOW;
504  break;
505  case DTR_HIGH:
506  reset_state = dtr ? DTR_HIGH : DTR_NEGEDGE;
507  break;
508  case DTR_NEGEDGE:
509  reset_state = dtr ? DTR_HIGH : DTR_LOW;
510  break;
511  case DTR_LOW:
512  reset_state = dtr ? DTR_HIGH : DTR_LOW;
513  break;
514  }
515 
516  // as Arduino - reset on DTR negative edge
517  if ((linecoding.bitrate == 1200) && (reset_state == DTR_NEGEDGE)) {
518  // iwdg_init(IWDG_PRE_4, 10);
519  NVIC_SystemReset();
520  while (1);
521  }
522 //}
523 #endif
524 
525  break;
526 
527  case SEND_BREAK:
528  /* Not needed for this driver */
529  break;
530 
531  default:
532  break;
533  }
534 
535  usb_opened = 1; // set active state only on VCP opening
536  usb_connected = 1; // just for case
537 
538  return USBD_OK;
539 }
540 
541 /* VCP_DataTx
542  * CDC received data to be send over USB IN endpoint are managed in
543  * this function.
544  * @param Buf: Buffer of data to be sent
545  * @param Len: Number of data to be sent (in bytes)
546  * @retval Result of the opeartion: USBD_OK if all operations are OK else VCP_FAIL
547  */
548 
549 void VCP_MarkWritten(unsigned sz)
550 {
551  noInterrupts();
553  interrupts();
554 }
555 
556 unsigned VCP_SpaceAvailContig(void)
557 {
558  noInterrupts();
560  interrupts();
561  return sz;
562 }
563 
564 unsigned VCP_PutContig(void const* buff, unsigned len)
565 {
566  unsigned avail = VCP_SpaceAvailContig();
567  unsigned sz = MIN_(avail, len);
568  if (sz) {
569  memcpy(VCP_SpacePtr(), buff, sz);
570  VCP_MarkWritten(sz);
571  }
572  return sz;
573 }
574 
575 unsigned VCP_SpaceAvail(void)
576 {
577  noInterrupts();
579  interrupts();
580  return sz;
581 }
582 
583 U16 VCP_DataTx(const U8 *buffer, U32 nbytes)
584 {
585 
586  unsigned sz = VCP_PutContig(buffer, nbytes);
587  if (sz && (nbytes -= sz))
588  sz += VCP_PutContig((uint8_t*)buffer + sz, nbytes);
589  return sz;
590 }
591 
592 
593 
594 /* VCP_DataRx
595  * Data received over USB OUT endpoint are sent over CDC interface
596  * through this function.
597  *
598  * Note
599  * This function will block any OUT packet reception on USB endpoint
600  * untill exiting this function. If you exit this function before transfer
601  * is complete on CDC interface (ie. using DMA controller) it will result
602  * in receiving more data while previous ones are still not sent.
603  *
604  * @param Buf: Buffer of data to be received
605  * @param Len: Number of data received (in bytes)
606  * @retval Result of the opeartion: USBD_OK if all operations are OK else VCP_FAIL
607  */
608 
609 unsigned VCP_DataAvail(void)
610 {
611  noInterrupts();
613  interrupts();
614  return sz;
615 }
616 
617 
618 void VCP_MarkRead(unsigned sz)
619 {
620  noInterrupts();
622  interrupts();
623 }
624 
625 unsigned VCP_GetContig(void* buff, unsigned max_len)
626 {
627  unsigned avail = VCP_DataAvailContig();
628  unsigned sz = MIN_(avail, max_len);
629  if (sz) {
630  memcpy(buff, VCP_DataPtr(), sz);
631  VCP_MarkRead(sz);
632  }
633  return sz;
634 }
635 
636 unsigned VCP_DataAvailContig(void)
637 {
638  noInterrupts();
640  interrupts();
641  return sz;
642 }
643 
644 static U16 VCP_DataRx(U8 *buffer, U32 nbytes)
645 {
646  usb_opened = 1; // data from other side
647 
648 #ifdef DEBUG_BUILD
649  if(VCP_DTRHIGH) {
650  if(nbytes >= 4) {
651  if(buffer[0] == '1' && buffer[1] == 'E' && buffer[2] == 'A' && buffer[3] == 'F') {
652  nbytes = 0;
653  if(is_bare_metal()) // bare metal build without bootloader should reboot to DFU on this reset
655 
656  NVIC_SystemReset();
657  }
658  }
659  }
660  VCP_DTRHIGH =0;
661 #endif
662  unsigned sz = VCP_GetContig(buffer, nbytes);
663  if (sz && (nbytes -= sz))
664  sz += VCP_GetContig((uint8_t*)buffer + sz, nbytes);
665  return sz;
666 }
667 
668 
669 
670 
671 
672 /*---------------------------- usb_open ---------------------------------*/
673 
674 int usb_open(void)
675 {
676  usb_periphcfg(ENABLE);
677 
678  usb_connected = 0;
679  preempt_prio = 0;
680  sub_prio = 0;
681  usb_ready = 0;
682 
683  return 1;
684 }
685 
686 /*---------------------------- usb_close --------------------------------*/
687 
688 int usb_close(void)
689 {
690  usb_periphcfg(DISABLE);
691 
692  if (usb_ready == 1) {
693  DCD_DevDisconnect(&USB_OTG_dev);
694  USBD_DeInit(&USB_OTG_dev);
695  USB_OTG_StopDevice(&USB_OTG_dev);
696  usb_ready = 0;
697  }
698 
699  if (usb_attr->use_present_pin){
701  }
702  return 1;
703 }
704 
706 {
707  if (usb_attr == NULL || (usb_attr && usb_attr->use_present_pin == 0))
708  return usb_connected;
709  else
710  return gpio_read_bit(usb_attr->present_port, usb_attr->present_pin);
711 }
712 
713 
714 /*---------------------------- usb_ioctl --------------------------------*/
715 
716 int usb_ioctl(int request, void *ctl)
717 {
718  switch(request) {
719  case I_USB_CLEAR:
720  if (!rxfifo) {
721  return 0;
722  }
723  rb_reset(rxfifo);
724  return 1;
725 
726  case I_USB_CONNECTED:
727  *((U8 *)ctl) = is_usb_connected(usb_attr);
728  break;
729 
730  case I_USB_GETATTR:
731  if (usb_attr) {
732  *((usb_attr_t **)ctl) = usb_attr;
733  } else {
734  return 0;
735  }
736  break;
737  case I_USB_SETATTR:
738  if (ctl == NULL) {
739  return 0;
740  }
741  usb_attr = (usb_attr_t *)ctl;
742  return usb_configure(usb_attr);
743  default:
744  return 0;
745  }
746  return 1;
747 }
748 
749 
750 // following functions can't be inline!
751 void USB_OTG_BSP_uDelay (const uint32_t usec) {
752  //stopwatch_delay_us(usec);
754 }
755 
756 int usb_write(const uint8_t *buf, unsigned int nbytes) {
757  return VCP_DataTx(buf, nbytes);
758 }
759 
760 int usb_read(void * buf, unsigned int nbytes){
761  return VCP_DataRx(buf, nbytes);
762 }
763 
764 uint32_t usb_data_available(void){
765  return VCP_DataAvail();
766 }
767 
768 bool usb_get_dtr(){
769  return VCP_DTRHIGH;
770 }
771 
772 void usb_reset_rx(){
773  rb_reset(rxfifo);
774 }
775 
776 void usb_reset_tx(){
777  APP_Rx_ptr_in = 0;
778 }
779 
780 uint16_t usb_tx_pending(void){
782 }
783 
784 uint16_t usb_tx_space(void){
785  return VCP_SpaceAvail();
786 }
787 
788 
789 void VCP_SetUSBTxBlocking(uint8_t Mode) {
790  UsbTXBlock = Mode;
791 }
792 //----------------------------------------------------------------------------
793 
794 uint8_t is_usb_opened() { return usb_opened; }
void usb_mass_mal_USBdisconnect()
void USBD_USR_Init(void)
Definition: usb.c:240
uint16_t usb_tx_pending(void)
Definition: usb.c:780
uint16_t usb_tx_space(void)
Definition: usb.c:784
Definition: usb.c:43
U8 * USBD_USR_DeviceDescriptor(U8 speed, U16 *length)
Definition: usb.c:188
static INLINE void noInterrupts()
Definition: exti.h:120
#define USB_LEN_DEV_QUALIFIER_DESC
Definition: usbd_def.h:53
int usb_configure(usb_attr_t *attr)
Definition: usb.c:350
#define USBD_MANUFACTURER_STRING
Definition: usb.h:34
#define GET_LINE_CODING
Definition: usbd_cdc_core.h:82
#define DM_PIN_PORT
Definition: usb.h:55
uint16_t present_pin
Definition: usb.h:79
#define I_USB_GETATTR
Definition: usb.h:89
void USB_OTG_StopDevice(USB_OTG_CORE_HANDLE *pdev)
Stop the device and clean up fifo&#39;s.
Definition: usb_core.c:2009
#define GET_ENCAPSULATED_RESPONSE
Definition: usbd_cdc_core.h:77
#define USB_DESC_TYPE_DEVICE_QUALIFIER
Definition: usbd_def.h:94
int usb_open(void)
Definition: usb.c:674
uint16_t U16
Definition: usb.c:30
uint32_t USBD_OTG_ISR_Handler(const USB_OTG_CORE_HANDLE *pdev)
void USBD_USR_DeviceConfigured(void)
Definition: usb.c:258
static volatile U8 VCP_RTSHIGH
Definition: usb.c:40
static INLINE void interrupts()
Definition: exti.h:106
int usb_ioctl(int request, void *ctl)
Definition: usb.c:716
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
void VCP_MarkWritten(unsigned sz)
Definition: usb.c:549
#define USBD_CFG_MAX_NUM
Definition: usbd_conf.h:38
U8 * USBD_USR_InterfaceStrDescriptor(U8 speed, U16 *length)
Definition: usb.c:234
static unsigned ring_space_contig(unsigned size, unsigned head, unsigned tail)
Definition: ring_buff.h:38
#define USBD_PID
Definition: usb.h:41
static const USBD_DEVICE USR_CDC_desc
Definition: usb.c:116
static U16 VCP_Init(void)
Definition: usb.c:419
#define USBD_SERIALNUMBER_FS_STRING
Definition: usb.h:36
LINE_CODING linecoding
Definition: usb.c:69
uint8_t format
Definition: usb.h:68
USBD_Class_cb_TypeDef const USBD_CDC_cb
void USB_OTG_BSP_Init(USB_OTG_CORE_HANDLE *pdev)
Definition: usb.c:310
void USB_OTG_BSP_DisableInterrupt()
Definition: usb.c:388
Definition: usb.h:74
void USB_OTG_BSP_uDelay(const uint32_t usec)
Definition: usb.c:751
void DCD_DevDisconnect(USB_OTG_CORE_HANDLE *pdev)
Disconnect device (disable internal pull-up)
Definition: usb_dcd.c:403
unsigned VCP_PutContig(void const *buff, unsigned len)
Definition: usb.c:564
void OTG_FS_IRQHandler(void)
Definition: usb.c:168
static unsigned ring_wrap(unsigned size, unsigned idx)
Definition: ring_buff.h:8
GPIO_TypeDef * GPIOx
Definition: gpio_hal.h:54
#define USBD_IDX_PRODUCT_STR
Definition: usbd_def.h:62
uint32_t bitrate
Definition: usb.h:67
uint32_t hal_micros()
Definition: Scheduler.cpp:1434
#define USBD_IDX_SERIAL_STR
Definition: usbd_def.h:63
uint32_t USB_Rx_buff_size
uint8_t paritytype
Definition: usb.h:69
#define USB_OTG_SPEED_FULL
Definition: usb_defines.h:62
#define MIN_(a, b)
Definition: min_max.h:3
U8 * USBD_USR_ConfigStrDescriptor(U8 speed, U16 *length)
Definition: usb.c:226
uint8_t U8
Definition: usb.c:28
#define USB_OTG_MAX_EP0_SIZE
Definition: usb_regs.h:71
U32 APP_Rx_ptr_in
void hal_delay_microseconds(uint16_t t)
Definition: Scheduler.cpp:1432
#define GET_COMM_FEATURE
Definition: usbd_cdc_core.h:79
void gpio_set_mode(const gpio_dev *const dev, uint8_t pin, gpio_pin_mode mode)
Definition: gpio_hal.c:125
int usb_close(void)
Definition: usb.c:688
static U16 VCP_DataTx(const uint8_t *Buf, uint32_t Len)
Definition: usb.c:583
#define USB_RXFIFO_SIZE
Definition: usb.h:44
uint8_t is_usb_connected(usb_attr_t *attr)
Definition: usb.c:705
#define USB_OTG_SPEED_HIGH
Definition: usb_defines.h:61
static U16 VCP_Ctrl(uint32_t Cmd, uint8_t *Buf, uint32_t Len)
Definition: usb.c:444
#define USB_CDCACM_CONTROL_LINE_RTS
#define I_USB_SETATTR
Definition: usb.h:90
static const U16 rxfifo_size
Definition: usb.c:51
static U8 preempt_prio
Definition: usb.c:63
static uint8_t * VCP_SpacePtr(void)
Definition: usb.h:187
const USBD_Usr_cb_TypeDef USR_cb
Definition: usb.c:103
__ALIGN_BEGIN USB_OTG_CORE_HANDLE USB_OTG_dev __ALIGN_END
Definition: usb.c:36
U8 * USBD_USR_LangIDStrDescriptor(U8 speed, U16 *length)
Definition: usb.c:195
#define SEND_ENCAPSULATED_COMMAND
Definition: usbd_cdc_core.h:76
#define DM_PIN_PIN
Definition: usb.h:56
uint8_t USBD_StrDesc[USB_MAX_STR_DESC_SIZ]
Definition: usbd_req.c:101
#define __ALIGN_BEGIN
Definition: usb_conf.h:198
static U8 usb_connected
Definition: usb.c:184
void USBD_USR_DeviceReset(uint8_t speed)
Definition: usb.c:246
#define USBD_PRODUCT_FS_STRING
Definition: usb.h:35
static uint8_t rx_buf[USB_RXFIFO_SIZE]
Definition: usb.c:60
#define SEND_BREAK
Definition: usbd_cdc_core.h:84
static void rb_init(ring_buffer *rb, uint16_t size, uint8_t *buf)
Definition: ring_buffer.h:73
void USBD_Init(USB_OTG_CORE_HANDLE *pdev, const USB_OTG_CORE_ID_TypeDef coreID, const USBD_DEVICE *pDevice, const USBD_Class_cb_TypeDef *class_cb, const USBD_Usr_cb_TypeDef *usr_cb)
USBD_Init Initailizes the device stack and load the class driver.
Definition: usbd_core.c:134
const CDC_IF_Prop_TypeDef VCP_fops
Definition: usb.c:94
static usb_attr_t * usb_attr
Definition: usb.c:38
#define USB_CLOCK
Definition: usb.h:51
USBD_Status USBD_DeInit(USB_OTG_CORE_HANDLE *pdev)
USBD_DeInit Re-Initialize th device library.
Definition: usbd_core.c:166
U8 APP_Rx_Buffer[]
#define USB_SIZ_DEVICE_DESC
Definition: usbd_desc.h:53
static unsigned ring_data_avail(unsigned size, unsigned head, unsigned tail)
Definition: ring_buff.h:14
void USB_OTG_BSP_mDelay(const uint32_t msec)
Definition: usb.c:393
void enable_nvic_irq(uint8_t irq, uint8_t prio)
Definition: nvic.c:8
void usb_reset_rx()
Definition: usb.c:772
void VCP_SetUSBTxBlocking(uint8_t Mode)
Definition: usb.c:789
static U8 sub_prio
Definition: usb.c:63
static ring_buffer _rxfifo IN_CCM
Definition: usb.c:54
#define DP_PIN_PIN
Definition: usb.h:58
static int state
Definition: Util.cpp:20
static ring_buffer * rxfifo
Definition: usb.c:57
#define USBD_LANGID_STRING
Definition: usb.h:42
const uint8_t USBD_LangIDDesc[USB_SIZ_STRING_LANGID]
Definition: usb.c:175
bool usb_get_dtr()
Definition: usb.c:768
static volatile U8 VCP_DTRHIGH
Definition: usb.c:39
void usb_reset_tx()
Definition: usb.c:776
static enum reset_state_t reset_state
Definition: usb.c:49
USB_OTG_CORE_HANDLE USB_OTG_dev
void USBD_USR_DeviceSuspended(void)
Definition: usb.c:264
static unsigned ring_space_avail(unsigned size, unsigned head, unsigned tail)
Definition: ring_buff.h:23
uint32_t USB_Rx_buff_tail
#define NULL
Definition: hal_types.h:59
#define CLEAR_COMM_FEATURE
Definition: usbd_cdc_core.h:80
const uint8_t USBD_DeviceDesc[USB_SIZ_DEVICE_DESC]
Definition: usb.c:129
uint32_t usb_data_available(void)
Definition: usb.c:764
unsigned VCP_GetContig(void *buff, unsigned max_len)
Definition: usb.c:625
uint8_t preempt_prio
Definition: usb.h:75
uint32_t USB_Tx_buff_tail
void VCP_MarkRead(unsigned sz)
Definition: usb.c:618
Board-specific pin information.
static uint8_t const * VCP_DataPtr(void)
Definition: usb.h:184
void USB_OTG_BSP_EnableInterrupt(USB_OTG_CORE_HANDLE *pdev)
Definition: usb.c:383
unsigned VCP_SpaceAvailContig(void)
Definition: usb.c:556
#define USB_TX_BUFF_SIZE
unsigned VCP_SpaceAvail(void)
Definition: usb.c:575
#define USBD_VID
Definition: usb.h:40
Definition: usb.c:44
#define SET_LINE_CODING
Definition: usbd_cdc_core.h:81
#define USBD_CONFIGURATION_FS_STRING
Definition: usb.h:37
U8 * USBD_USR_ProductStrDescriptor(U8 speed, U16 *length)
Definition: usb.c:204
#define DP_PIN_PORT
Definition: usb.h:57
const gpio_dev * present_port
Definition: usb.h:78
static U8 usb_ready
Definition: usb.c:64
static INLINE uint8_t gpio_read_bit(const gpio_dev *const dev, uint8_t pin)
Definition: gpio_hal.h:130
#define USBD_INTERFACE_FS_STRING
Definition: usb.h:38
#define SET_CONTROL_LINE_STATE
Definition: usbd_cdc_core.h:83
const uint8_t USBD_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC]
Definition: usb.c:152
#define I_USB_CONNECTED
Definition: usb.h:88
uint8_t is_usb_opened()
Definition: usb.c:794
uint8_t sub_prio
Definition: usb.h:76
void board_set_rtc_register(uint32_t sig, uint16_t reg)
Definition: boards.cpp:141
static U16 VCP_DataRx(uint8_t *Buf, uint32_t Len)
Definition: usb.c:644
#define I_USB_CLEAR
Definition: usb.h:87
static void gpio_set_af_mode(const gpio_dev *const dev, uint8_t pin, uint8_t mode)
Definition: gpio_hal.h:102
uint8_t datatype
Definition: usb.h:70
#define DFU_RTC_SIGNATURE
Definition: boards.h:292
#define USB_DEVICE_DESCRIPTOR_TYPE
Definition: usbd_cdc_core.h:57
void USBD_USR_DeviceConnected(void)
Definition: usb.c:278
#define HIBYTE(x)
Definition: usbd_def.h:126
#define LOBYTE(x)
Definition: usbd_def.h:125
const gpio_dev *const _GPIOA
Definition: gpio_hal.c:23
#define USB_SIZ_STRING_LANGID
Definition: usbd_desc.h:54
unsigned VCP_DataAvail(void)
Definition: usb.c:609
static U8 usb_opened
Definition: usb.c:185
U8 * USBD_USR_SerialStrDescriptor(U8 speed, U16 *length)
Definition: usb.c:219
void USBD_GetString(const uint8_t *desc, uint8_t *unicode, uint16_t *len)
USBD_GetString Convert Ascii string into unicode one.
Definition: usbd_req.c:819
static void rb_reset(ring_buffer *rb)
Discard all items from a ring buffer.
Definition: ring_buffer.h:186
Definition: usb.c:46
static U16 VCP_DeInit(void)
Definition: usb.c:431
unsigned VCP_DataAvailContig(void)
Definition: usb.c:636
uint32_t USB_Rx_buff_head
#define RTC_SIGNATURE_REG
Definition: boards.h:312
static unsigned ring_data_contig(unsigned size, unsigned head, unsigned tail)
Definition: ring_buff.h:29
int usb_periphcfg(FunctionalState state)
Definition: usb.c:314
#define USBD_IDX_MFC_STR
Definition: usbd_def.h:61
void usb_default_attr(usb_attr_t *attr)
Definition: usb.c:296
void USBD_USR_DeviceDisconnected(void)
Definition: usb.c:285
#define SET_COMM_FEATURE
Definition: usbd_cdc_core.h:78
void reset_usb_opened()
Definition: usb.c:795
#define USB_DESC_TYPE_STRING
Definition: usbd_def.h:91
#define USB_CDCACM_CONTROL_LINE_DTR
static bool is_bare_metal()
Definition: boards.h:149
static U8 UsbTXBlock
Definition: usb.c:66
void USBD_USR_DeviceResumed(void)
Definition: usb.c:271
uint32_t U32
Definition: usb.c:29
reset_state_t
Definition: usb.c:42
U8 * USBD_USR_ManufacturerStrDescriptor(U8 speed, U16 *length)
Definition: usb.c:212
int usb_read(void *buf, unsigned int nbytes)
Definition: usb.c:760
uint8_t use_present_pin
Definition: usb.h:77
int usb_write(const uint8_t *buf, unsigned int nbytes)
Definition: usb.c:756
uint32_t USB_Tx_buff_head
void usb_setParams(usb_attr_t *attr)
Definition: usb.c:365