udi_cdc.c
Go to the documentation of this file.
1 
33 /*
34  * Support and FAQ: visit <a href="https://www.microchip.com/support/">Microchip Support</a>
35  */
36 
37 #include <FreeRTOS.h>
38 #include <task.h>
39 
40 #include "conf_usb.h"
41 #include "usb_protocol.h"
42 #include "usb_protocol_cdc.h"
43 #include "udd.h"
44 #include "udc.h"
45 #include "udi_cdc.h"
46 #include <string.h>
47 
48 #ifdef UDI_CDC_LOW_RATE
49 # ifdef USB_DEVICE_HS_SUPPORT
50 # define UDI_CDC_TX_BUFFERS (UDI_CDC_DATA_EPS_HS_SIZE)
51 # define UDI_CDC_RX_BUFFERS (UDI_CDC_DATA_EPS_HS_SIZE)
52 # else
53 # define UDI_CDC_TX_BUFFERS (UDI_CDC_DATA_EPS_FS_SIZE)
54 # define UDI_CDC_RX_BUFFERS (UDI_CDC_DATA_EPS_FS_SIZE)
55 # endif
56 #else
57 # ifdef USB_DEVICE_HS_SUPPORT
58 # define UDI_CDC_TX_BUFFERS (UDI_CDC_DATA_EPS_HS_SIZE)
59 # define UDI_CDC_RX_BUFFERS (UDI_CDC_DATA_EPS_HS_SIZE)
60 # else
61 # define UDI_CDC_TX_BUFFERS (5*UDI_CDC_DATA_EPS_FS_SIZE)
62 # define UDI_CDC_RX_BUFFERS (5*UDI_CDC_DATA_EPS_FS_SIZE)
63 # endif
64 #endif
65 
66 #ifndef UDI_CDC_TX_EMPTY_NOTIFY
67 # define UDI_CDC_TX_EMPTY_NOTIFY(port)
68 #endif
69 
78 bool udi_cdc_comm_enable(void);
79 void udi_cdc_comm_disable(void);
80 bool udi_cdc_comm_setup(void);
81 bool udi_cdc_data_enable(void);
82 void udi_cdc_data_disable(void);
83 bool udi_cdc_data_setup(void);
84 uint8_t udi_cdc_getsetting(void);
85 void udi_cdc_data_sof_notify(void);
88  .disable = udi_cdc_comm_disable,
89  .setup = udi_cdc_comm_setup,
90  .getsetting = udi_cdc_getsetting,
91 };
94  .disable = udi_cdc_data_disable,
95  .setup = udi_cdc_data_setup,
96  .getsetting = udi_cdc_getsetting,
97  .sof_notify = udi_cdc_data_sof_notify,
98 };
100 
113 
118 
124 static uint8_t udi_cdc_setup_to_port(void);
125 
131 static void udi_cdc_line_coding_received(void);
132 
140 static void udi_cdc_ctrl_state_change(uint8_t port, bool b_set, le16_t bit_mask);
141 
148 static void udi_cdc_ctrl_state_notify(uint8_t port, udd_ep_id_t ep);
149 
159 
161 
166 
176 static bool udi_cdc_rx_start(uint8_t port);
177 
187 
196 static void udi_cdc_data_sent(udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep);
197 
203 static void udi_cdc_tx_send(uint8_t port);
204 
206 
208 
213 COMPILER_WORD_ALIGNED
218 
220 static volatile uint8_t udi_cdc_nb_comm_enabled = 0;
222 
228 
230 static volatile uint8_t udi_cdc_nb_data_enabled = 0;
231 static volatile bool udi_cdc_data_running = false;
233 COMPILER_ALIGNED(32) static uint8_t udi_cdc_rx_buf[UDI_CDC_PORT_NB][2][UDI_CDC_RX_BUFFERS];
235 static volatile uint16_t udi_cdc_rx_buf_nb[UDI_CDC_PORT_NB][2];
237 static volatile uint8_t udi_cdc_rx_buf_sel[UDI_CDC_PORT_NB];
239 static volatile uint16_t udi_cdc_rx_pos[UDI_CDC_PORT_NB];
241 static volatile bool udi_cdc_rx_trans_ongoing[UDI_CDC_PORT_NB];
242 
244 #define UDI_CDC_TRANS_HALTED 2
245 
247 COMPILER_ALIGNED(32) static uint8_t udi_cdc_tx_buf[UDI_CDC_PORT_NB][2][UDI_CDC_TX_BUFFERS];
249 static uint16_t udi_cdc_tx_buf_nb[UDI_CDC_PORT_NB][2];
251 static volatile uint8_t udi_cdc_tx_buf_sel[UDI_CDC_PORT_NB];
253 static uint16_t udi_cdc_tx_sof_num[UDI_CDC_PORT_NB];
255 static volatile bool udi_cdc_tx_trans_ongoing[UDI_CDC_PORT_NB];
257 static volatile bool udi_cdc_tx_both_buf_to_send[UDI_CDC_PORT_NB];
258 
260 
261 bool udi_cdc_comm_enable(void)
262 {
263  uint8_t port;
264  uint8_t iface_comm_num;
265 
266 #if UDI_CDC_PORT_NB == 1 // To optimize code
267  port = 0;
269 #else
270  if (udi_cdc_nb_comm_enabled > UDI_CDC_PORT_NB) {
272  }
274 #endif
275 
276  // Initialize control signal management
277  udi_cdc_state[port] = CPU_TO_LE16(0);
278 
283  uid_cdc_state_msg[port].header.wValue = LE16(0);
284 
285  switch (port) {
286 #define UDI_CDC_PORT_TO_IFACE_COMM(index, unused) \
287  case index: \
288  iface_comm_num = UDI_CDC_COMM_IFACE_NUMBER_##index; \
289  break;
290  MREPEAT(UDI_CDC_PORT_NB, UDI_CDC_PORT_TO_IFACE_COMM, ~)
291 #undef UDI_CDC_PORT_TO_IFACE_COMM
292  default:
293  iface_comm_num = UDI_CDC_COMM_IFACE_NUMBER_0;
294  break;
295  }
296 
297  uid_cdc_state_msg[port].header.wIndex = LE16(iface_comm_num);
300 
301  udi_cdc_line_coding[port].dwDTERate = CPU_TO_LE32(UDI_CDC_DEFAULT_RATE);
302  udi_cdc_line_coding[port].bCharFormat = UDI_CDC_DEFAULT_STOPBITS;
303  udi_cdc_line_coding[port].bParityType = UDI_CDC_DEFAULT_PARITY;
304  udi_cdc_line_coding[port].bDataBits = UDI_CDC_DEFAULT_DATABITS;
305  // Call application callback
306  // to initialize memories or indicate that interface is enabled
307  UDI_CDC_SET_CODING_EXT(port,(&udi_cdc_line_coding[port]));
308  if (!UDI_CDC_ENABLE_EXT(port)) {
309  return false;
310  }
312  return true;
313 }
314 
316 {
317  uint8_t port;
318 
319 #if UDI_CDC_PORT_NB == 1 // To optimize code
320  port = 0;
322 #else
323  if (udi_cdc_nb_data_enabled > UDI_CDC_PORT_NB) {
325  }
327 #endif
328 
329  // Initialize TX management
330  udi_cdc_tx_trans_ongoing[port] = false;
331  udi_cdc_tx_both_buf_to_send[port] = false;
332  udi_cdc_tx_buf_sel[port] = 0;
333  udi_cdc_tx_buf_nb[port][0] = 0;
334  udi_cdc_tx_buf_nb[port][1] = 0;
335  udi_cdc_tx_sof_num[port] = 0;
336  udi_cdc_tx_send(port);
337 
338  // Initialize RX management
339  udi_cdc_rx_trans_ongoing[port] = false;
340  udi_cdc_rx_buf_sel[port] = 0;
341  udi_cdc_rx_buf_nb[port][0] = 0;
342  udi_cdc_rx_buf_nb[port][1] = 0;
343  udi_cdc_rx_pos[port] = 0;
344  if (!udi_cdc_rx_start(port)) {
345  return false;
346  }
348  if (udi_cdc_nb_data_enabled == UDI_CDC_PORT_NB) {
349  udi_cdc_data_running = true;
350  }
351  return true;
352 }
353 
355 {
358 }
359 
361 {
362  uint8_t port;
363 
367  UDI_CDC_DISABLE_EXT(port);
368  udi_cdc_data_running = false;
369 }
370 
372 {
373  uint8_t port = udi_cdc_setup_to_port();
374 
375  if (Udd_setup_is_in()) {
376  // GET Interface Requests
378  // Requests Class Interface Get
379  switch (udd_g_ctrlreq.req.bRequest) {
381  // Get configuration of CDC line
382  if (sizeof(usb_cdc_line_coding_t) !=
384  return false; // Error for USB host
386  (uint8_t *) &
387  udi_cdc_line_coding[port];
389  sizeof(usb_cdc_line_coding_t);
390  return true;
391  }
392  }
393  }
394  if (Udd_setup_is_out()) {
395  // SET Interface Requests
397  // Requests Class Interface Set
398  switch (udd_g_ctrlreq.req.bRequest) {
400  // Change configuration of CDC line
401  if (sizeof(usb_cdc_line_coding_t) !=
403  return false; // Error for USB host
407  (uint8_t *) &
408  udi_cdc_line_coding[port];
410  sizeof(usb_cdc_line_coding_t);
411  return true;
413  // According cdc spec 1.1 chapter 6.2.14
414  UDI_CDC_SET_DTR_EXT(port, (0 !=
417  UDI_CDC_SET_RTS_EXT(port, (0 !=
420  return true;
421  }
422  }
423  }
424  return false; // request Not supported
425 }
426 
428 {
429  return false; // request Not supported
430 }
431 
432 uint8_t udi_cdc_getsetting(void)
433 {
434  return 0; // CDC don't have multiple alternate setting
435 }
436 
438 {
439  static uint8_t port_notify = 0;
440 
441  // A call of udi_cdc_data_sof_notify() is done for each port
442  udi_cdc_tx_send(port_notify);
443 #if UDI_CDC_PORT_NB != 1 // To optimize code
444  port_notify++;
445  if (port_notify >= UDI_CDC_PORT_NB) {
446  port_notify = 0;
447  }
448 #endif
449 }
450 
451 
452 //-------------------------------------------------
453 //------- Internal routines to control serial line
454 
455 static uint8_t udi_cdc_setup_to_port(void)
456 {
457  uint8_t port;
458 
459  switch (udd_g_ctrlreq.req.wIndex & 0xFF) {
460 #define UDI_CDC_IFACE_COMM_TO_PORT(iface, unused) \
461  case UDI_CDC_COMM_IFACE_NUMBER_##iface: \
462  port = iface; \
463  break;
464  MREPEAT(UDI_CDC_PORT_NB, UDI_CDC_IFACE_COMM_TO_PORT, ~)
465 #undef UDI_CDC_IFACE_COMM_TO_PORT
466  default:
467  port = 0;
468  break;
469  }
470  return port;
471 }
472 
474 {
475  uint8_t port = udi_cdc_setup_to_port();
476  UNUSED(port);
477 
478  UDI_CDC_SET_CODING_EXT(port, (&udi_cdc_line_coding[port]));
479 }
480 
481 static void udi_cdc_ctrl_state_change(uint8_t port, bool b_set, le16_t bit_mask)
482 {
483  irqflags_t flags;
484  udd_ep_id_t ep_comm;
485 
486 #if UDI_CDC_PORT_NB == 1 // To optimize code
487  port = 0;
488 #endif
489 
490  // Update state
491  flags = cpu_irq_save(); // Protect udi_cdc_state
492  if (b_set) {
493  udi_cdc_state[port] |= bit_mask;
494  } else {
495  udi_cdc_state[port] &= ~(unsigned)bit_mask;
496  }
497  cpu_irq_restore(flags);
498 
499  // Send it if possible and state changed
500  switch (port) {
501 #define UDI_CDC_PORT_TO_COMM_EP(index, unused) \
502  case index: \
503  ep_comm = UDI_CDC_COMM_EP_##index; \
504  break;
505  MREPEAT(UDI_CDC_PORT_NB, UDI_CDC_PORT_TO_COMM_EP, ~)
506 #undef UDI_CDC_PORT_TO_COMM_EP
507  default:
508  ep_comm = UDI_CDC_COMM_EP_0;
509  break;
510  }
511  udi_cdc_ctrl_state_notify(port, ep_comm);
512 }
513 
514 
515 static void udi_cdc_ctrl_state_notify(uint8_t port, udd_ep_id_t ep)
516 {
517 #if UDI_CDC_PORT_NB == 1 // To optimize code
518  port = 0;
519 #endif
520 
521  // Send it if possible and state changed
523  && (udi_cdc_state[port] != uid_cdc_state_msg[port].value)) {
524  // Fill notification message
525  uid_cdc_state_msg[port].value = udi_cdc_state[port];
526  // Send notification message
528  udd_ep_run(ep,
529  false,
530  (uint8_t *) & uid_cdc_state_msg[port],
531  sizeof(uid_cdc_state_msg[0]),
533  }
534 }
535 
536 
538 {
539  uint8_t port;
540  UNUSED(n);
541  UNUSED(status);
542 
543  switch (ep) {
544 #define UDI_CDC_GET_PORT_FROM_COMM_EP(iface, unused) \
545  case UDI_CDC_COMM_EP_##iface: \
546  port = iface; \
547  break;
548  MREPEAT(UDI_CDC_PORT_NB, UDI_CDC_GET_PORT_FROM_COMM_EP, ~)
549 #undef UDI_CDC_GET_PORT_FROM_COMM_EP
550  default:
551  port = 0;
552  break;
553  }
554 
555  udi_cdc_serial_state_msg_ongoing[port] = false;
556 
557  // For the irregular signals like break, the incoming ring signal,
558  // or the overrun error state, this will reset their values to zero
559  // and again will not send another notification until their state changes.
568  // Send it if possible and state changed
569  udi_cdc_ctrl_state_notify(port, ep);
570 }
571 
572 
573 //-------------------------------------------------
574 //------- Internal routines to process data transfer
575 
576 
577 static bool udi_cdc_rx_start(uint8_t port)
578 {
579  irqflags_t flags;
580  uint8_t buf_sel_trans;
581  udd_ep_id_t ep;
582 
583 #if UDI_CDC_PORT_NB == 1 // To optimize code
584  port = 0;
585 #endif
586 
587  flags = cpu_irq_save();
588  buf_sel_trans = udi_cdc_rx_buf_sel[port];
589  if (udi_cdc_rx_trans_ongoing[port] ||
590  (udi_cdc_rx_pos[port] < udi_cdc_rx_buf_nb[port][buf_sel_trans])) {
591  // Transfer already on-going or current buffer no empty
592  cpu_irq_restore(flags);
593  return false;
594  }
595 
596  // Change current buffer
597  udi_cdc_rx_pos[port] = 0;
598  udi_cdc_rx_buf_sel[port] = (buf_sel_trans==0)?1:0;
599 
600  // Start transfer on RX
601  udi_cdc_rx_trans_ongoing[port] = true;
602  cpu_irq_restore(flags);
603 
604  if (udi_cdc_multi_is_rx_ready(port)) {
605  UDI_CDC_RX_NOTIFY(port);
606  }
607  // Send the buffer with enable of short packet
608  switch (port) {
609 #define UDI_CDC_PORT_TO_DATA_EP_OUT(index, unused) \
610  case index: \
611  ep = UDI_CDC_DATA_EP_OUT_##index; \
612  break;
613  MREPEAT(UDI_CDC_PORT_NB, UDI_CDC_PORT_TO_DATA_EP_OUT, ~)
614 #undef UDI_CDC_PORT_TO_DATA_EP_OUT
615  default:
617  break;
618  }
619  return udd_ep_run(ep,
620  true,
621  udi_cdc_rx_buf[port][buf_sel_trans],
622  UDI_CDC_RX_BUFFERS,
624 }
625 
626 
628 {
629  uint8_t buf_sel_trans;
630  uint8_t port;
631 
632  switch (ep) {
633 #define UDI_CDC_DATA_EP_OUT_TO_PORT(index, unused) \
634  case UDI_CDC_DATA_EP_OUT_##index: \
635  port = index; \
636  break;
637  MREPEAT(UDI_CDC_PORT_NB, UDI_CDC_DATA_EP_OUT_TO_PORT, ~)
638 #undef UDI_CDC_DATA_EP_OUT_TO_PORT
639  default:
640  port = 0;
641  break;
642  }
643 
644  if (UDD_EP_TRANSFER_OK != status) {
645  // Abort reception
646  return;
647  }
648  buf_sel_trans = (udi_cdc_rx_buf_sel[port]==0)?1:0;
649  if (!n) {
650  udd_ep_run( ep,
651  true,
652  udi_cdc_rx_buf[port][buf_sel_trans],
653  UDI_CDC_RX_BUFFERS,
655  return;
656  }
657  udi_cdc_rx_buf_nb[port][buf_sel_trans] = n;
658  udi_cdc_rx_trans_ongoing[port] = false;
659  udi_cdc_rx_start(port);
660 }
661 
662 
664 {
665  uint8_t port;
666  UNUSED(n);
667 
668  switch (ep) {
669 #define UDI_CDC_DATA_EP_IN_TO_PORT(index, unused) \
670  case UDI_CDC_DATA_EP_IN_##index: \
671  port = index; \
672  break;
673  MREPEAT(UDI_CDC_PORT_NB, UDI_CDC_DATA_EP_IN_TO_PORT, ~)
674 #undef UDI_CDC_DATA_EP_IN_TO_PORT
675  default:
676  port = 0;
677  break;
678  }
679 
680  if (UDD_EP_TRANSFER_OK != status) {
681  // Abort transfer
682  return;
683  }
684  udi_cdc_tx_buf_nb[port][(udi_cdc_tx_buf_sel[port]==0)?1:0] = 0;
685  udi_cdc_tx_both_buf_to_send[port] = false;
686  udi_cdc_tx_trans_ongoing[port] = false;
687 
688  if (n != 0) {
690  }
691  udi_cdc_tx_send(port);
692 }
693 
694 
695 static void udi_cdc_tx_send(uint8_t port)
696 {
697  irqflags_t flags;
698  uint8_t buf_sel_trans;
699  bool b_short_packet;
700  udd_ep_id_t ep;
701  static uint16_t sof_zlp_counter = 0;
702 
703 #if UDI_CDC_PORT_NB == 1 // To optimize code
704  port = 0;
705 #endif
706 
707  if (udi_cdc_tx_trans_ongoing[port]) {
708  return; // Already on going or wait next SOF to send next data
709  }
710  if (udd_is_high_speed()) {
711  if (udi_cdc_tx_sof_num[port] == udd_get_micro_frame_number()) {
712  return; // Wait next SOF to send next data
713  }
714  }else{
715  if (udi_cdc_tx_sof_num[port] == udd_get_frame_number()) {
716  return; // Wait next SOF to send next data
717  }
718  }
719 
720  flags = cpu_irq_save(); // to protect udi_cdc_tx_buf_sel
721  buf_sel_trans = udi_cdc_tx_buf_sel[port];
722  if (udi_cdc_tx_buf_nb[port][buf_sel_trans] == 0) {
723  sof_zlp_counter++;
724  if (((!udd_is_high_speed()) && (sof_zlp_counter < 100))
725  || (udd_is_high_speed() && (sof_zlp_counter < 800))) {
726  cpu_irq_restore(flags);
727  return;
728  }
729  }
730  sof_zlp_counter = 0;
731 
732  if (!udi_cdc_tx_both_buf_to_send[port]) {
733  // Send current Buffer
734  // and switch the current buffer
735  udi_cdc_tx_buf_sel[port] = (buf_sel_trans==0)?1:0;
736  }else{
737  // Send the other Buffer
738  // and no switch the current buffer
739  buf_sel_trans = (buf_sel_trans==0)?1:0;
740  }
741  udi_cdc_tx_trans_ongoing[port] = true;
742  cpu_irq_restore(flags);
743 
744  b_short_packet = (udi_cdc_tx_buf_nb[port][buf_sel_trans] != UDI_CDC_TX_BUFFERS);
745  if (b_short_packet) {
746  if (udd_is_high_speed()) {
747  udi_cdc_tx_sof_num[port] = udd_get_micro_frame_number();
748  }else{
749  udi_cdc_tx_sof_num[port] = udd_get_frame_number();
750  }
751  }else{
752  udi_cdc_tx_sof_num[port] = 0; // Force next transfer without wait SOF
753  }
754 
755  // Send the buffer with enable of short packet
756  switch (port) {
757 #define UDI_CDC_PORT_TO_DATA_EP_IN(index, unused) \
758  case index: \
759  ep = UDI_CDC_DATA_EP_IN_##index; \
760  break;
761  MREPEAT(UDI_CDC_PORT_NB, UDI_CDC_PORT_TO_DATA_EP_IN, ~)
762 #undef UDI_CDC_PORT_TO_DATA_EP_IN
763  default:
765  break;
766  }
767  udd_ep_run( ep,
768  b_short_packet,
769  udi_cdc_tx_buf[port][buf_sel_trans],
770  udi_cdc_tx_buf_nb[port][buf_sel_trans],
772 }
773 
774 
775 //---------------------------------------------
776 //------- Application interface
777 
778 
779 //------- Application interface
780 
781 void udi_cdc_ctrl_signal_dcd(bool b_set)
782 {
784 }
785 
786 void udi_cdc_ctrl_signal_dsr(bool b_set)
787 {
789 }
790 
792 {
794 }
795 
797 {
799 }
800 
802 {
804 }
805 
806 void udi_cdc_multi_ctrl_signal_dcd(uint8_t port, bool b_set)
807 {
809 }
810 
811 void udi_cdc_multi_ctrl_signal_dsr(uint8_t port, bool b_set)
812 {
814 }
815 
817 {
819 }
820 
822 {
824 }
825 
827 {
829 }
830 
832 {
833  irqflags_t flags;
834  uint16_t pos;
835  iram_size_t nb_received;
836 
837 #if UDI_CDC_PORT_NB == 1 // To optimize code
838  port = 0;
839 #endif
840  flags = cpu_irq_save();
841  pos = udi_cdc_rx_pos[port];
842  nb_received = udi_cdc_rx_buf_nb[port][udi_cdc_rx_buf_sel[port]] - pos;
843  cpu_irq_restore(flags);
844  return nb_received;
845 }
846 
848 {
850 }
851 
852 bool udi_cdc_multi_is_rx_ready(uint8_t port)
853 {
854  return (udi_cdc_multi_get_nb_received_data(port) > 0);
855 }
856 
858 {
859  return udi_cdc_multi_is_rx_ready(0);
860 }
861 
862 int udi_cdc_multi_getc(uint8_t port)
863 {
864  irqflags_t flags;
865  int rx_data = 0;
866  bool b_databit_9;
867  uint16_t pos;
868  uint8_t buf_sel;
869  bool again;
870 
871 #if UDI_CDC_PORT_NB == 1 // To optimize code
872  port = 0;
873 #endif
874 
875  b_databit_9 = (9 == udi_cdc_line_coding[port].bDataBits);
876 
877 udi_cdc_getc_process_one_byte:
878  // Check available data
879  flags = cpu_irq_save();
880  pos = udi_cdc_rx_pos[port];
881  buf_sel = udi_cdc_rx_buf_sel[port];
882  again = pos >= udi_cdc_rx_buf_nb[port][buf_sel];
883  cpu_irq_restore(flags);
884  while (again) {
885  if (!udi_cdc_data_running) {
886  return 0;
887  }
888  goto udi_cdc_getc_process_one_byte;
889  }
890 
891  // Read data
892  rx_data |= udi_cdc_rx_buf[port][buf_sel][pos];
893  udi_cdc_rx_pos[port] = pos+1;
894 
895  udi_cdc_rx_start(port);
896 
897  if (b_databit_9) {
898  // Receive MSB
899  b_databit_9 = false;
900  rx_data = rx_data << 8;
901  goto udi_cdc_getc_process_one_byte;
902  }
903  return rx_data;
904 }
905 
906 int udi_cdc_getc(void)
907 {
908  return udi_cdc_multi_getc(0);
909 }
910 
911 iram_size_t udi_cdc_multi_read_buf(uint8_t port, void* buf, iram_size_t size)
912 {
913  irqflags_t flags;
914  uint8_t *ptr_buf = (uint8_t *)buf;
915  iram_size_t copy_nb;
916  uint16_t pos;
917  uint8_t buf_sel;
918  bool again;
919 
920 #if UDI_CDC_PORT_NB == 1 // To optimize code
921  port = 0;
922 #endif
923 
924 udi_cdc_read_buf_loop_wait:
925  // Check available data
926  flags = cpu_irq_save();
927  pos = udi_cdc_rx_pos[port];
928  buf_sel = udi_cdc_rx_buf_sel[port];
929  again = pos >= udi_cdc_rx_buf_nb[port][buf_sel];
930  cpu_irq_restore(flags);
931  while (again) {
932  if (!udi_cdc_data_running) {
933  return size;
934  }
935  goto udi_cdc_read_buf_loop_wait;
936  }
937 
938  // Read data
939  copy_nb = udi_cdc_rx_buf_nb[port][buf_sel] - pos;
940  if (copy_nb>size) {
941  copy_nb = size;
942  }
943  memcpy(ptr_buf, &udi_cdc_rx_buf[port][buf_sel][pos], copy_nb);
944  udi_cdc_rx_pos[port] += copy_nb;
945  ptr_buf += copy_nb;
946  size -= copy_nb;
947  udi_cdc_rx_start(port);
948 
949  if (size) {
950  goto udi_cdc_read_buf_loop_wait;
951  }
952  return 0;
953 }
954 
955 static iram_size_t udi_cdc_multi_read_no_polling(uint8_t port, void* buf, iram_size_t size)
956 {
957  uint8_t *ptr_buf = (uint8_t *)buf;
958  iram_size_t nb_avail_data;
959  uint16_t pos;
960  uint8_t buf_sel;
961  irqflags_t flags;
962 
963 #if UDI_CDC_PORT_NB == 1 // To optimize code
964  port = 0;
965 #endif
966 
967  //Data interface not started... exit
968  if (!udi_cdc_data_running) {
969  return 0;
970  }
971 
972  //Get number of available data
973  // Check available data
974  flags = cpu_irq_save(); // to protect udi_cdc_rx_pos & udi_cdc_rx_buf_sel
975  pos = udi_cdc_rx_pos[port];
976  buf_sel = udi_cdc_rx_buf_sel[port];
977  nb_avail_data = udi_cdc_rx_buf_nb[port][buf_sel] - pos;
978  cpu_irq_restore(flags);
979  //If the buffer contains less than the requested number of data,
980  //adjust read size
981  if(nb_avail_data<size) {
982  size = nb_avail_data;
983  }
984  if(size>0) {
985  memcpy(ptr_buf, &udi_cdc_rx_buf[port][buf_sel][pos], size);
986  flags = cpu_irq_save(); // to protect udi_cdc_rx_pos
987  udi_cdc_rx_pos[port] += size;
988  cpu_irq_restore(flags);
989 
990  ptr_buf += size;
991  udi_cdc_rx_start(port);
992  }
993  return(size);
994 }
995 
997 {
998  return udi_cdc_multi_read_no_polling(0, buf, size);
999 }
1000 
1002 {
1003  return udi_cdc_multi_read_buf(0, buf, size);
1004 }
1005 
1007 {
1008  irqflags_t flags;
1009  iram_size_t buf_sel_nb, retval;
1010  uint8_t buf_sel;
1011 
1012 #if UDI_CDC_PORT_NB == 1 // To optimize code
1013  port = 0;
1014 #endif
1015 
1016  flags = cpu_irq_save();
1017  buf_sel = udi_cdc_tx_buf_sel[port];
1018  buf_sel_nb = udi_cdc_tx_buf_nb[port][buf_sel];
1019  if (buf_sel_nb == UDI_CDC_TX_BUFFERS) {
1020  if ((!udi_cdc_tx_trans_ongoing[port])
1021  && (!udi_cdc_tx_both_buf_to_send[port])) {
1022  /* One buffer is full, but the other buffer is not used.
1023  * (not used = transfer on-going)
1024  * then move to the other buffer to store data */
1025  udi_cdc_tx_both_buf_to_send[port] = true;
1026  udi_cdc_tx_buf_sel[port] = (buf_sel == 0)? 1 : 0;
1027  buf_sel_nb = 0;
1028  }
1029  }
1030  retval = UDI_CDC_TX_BUFFERS - buf_sel_nb;
1031  cpu_irq_restore(flags);
1032  return retval;
1033 }
1034 
1036 {
1038 }
1039 
1040 bool udi_cdc_multi_is_tx_ready(uint8_t port)
1041 {
1042  return (udi_cdc_multi_get_free_tx_buffer(port) != 0);
1043 }
1044 
1046 {
1047  return udi_cdc_multi_is_tx_ready(0);
1048 }
1049 
1050 int udi_cdc_multi_putc(uint8_t port, int value)
1051 {
1052  irqflags_t flags;
1053  bool b_databit_9;
1054  uint8_t buf_sel;
1055 
1056 #if UDI_CDC_PORT_NB == 1 // To optimize code
1057  port = 0;
1058 #endif
1059 
1060  b_databit_9 = (9 == udi_cdc_line_coding[port].bDataBits);
1061 
1062 udi_cdc_putc_process_one_byte:
1063  // Check available space
1064  if (!udi_cdc_multi_is_tx_ready(port)) {
1065  if (!udi_cdc_data_running) {
1066  return false;
1067  }
1068  goto udi_cdc_putc_process_one_byte;
1069  }
1070 
1071  // Write value
1072  flags = cpu_irq_save();
1073  buf_sel = udi_cdc_tx_buf_sel[port];
1074  udi_cdc_tx_buf[port][buf_sel][udi_cdc_tx_buf_nb[port][buf_sel]++] = value;
1075  cpu_irq_restore(flags);
1076 
1077  if (b_databit_9) {
1078  // Send MSB
1079  b_databit_9 = false;
1080  value = value >> 8;
1081  goto udi_cdc_putc_process_one_byte;
1082  }
1083  return true;
1084 }
1085 
1087 {
1088  return udi_cdc_multi_putc(0, value);
1089 }
1090 
1091 iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t size)
1092 {
1093  irqflags_t flags;
1094  uint8_t buf_sel;
1095  uint16_t buf_nb;
1096  iram_size_t copy_nb;
1097  uint8_t *ptr_buf = (uint8_t *)buf;
1098 #define WRITE_TIMEOUT 10
1099  int timeout = WRITE_TIMEOUT;
1100 
1101 #if UDI_CDC_PORT_NB == 1 // To optimize code
1102  port = 0;
1103 #endif
1104 
1105  if (9 == udi_cdc_line_coding[port].bDataBits) {
1106  size *=2;
1107  }
1108 
1109 udi_cdc_write_buf_loop_wait:
1110  // Check available space
1111  if (!udi_cdc_multi_is_tx_ready(port)) {
1112  if (!udi_cdc_data_running) {
1113  return size;
1114  }
1115  if(--timeout == 0)
1116  return size;
1117  vTaskDelay(1);
1118 
1119  goto udi_cdc_write_buf_loop_wait;
1120  }
1121 
1122  // Write values
1123  flags = cpu_irq_save();
1124  buf_sel = udi_cdc_tx_buf_sel[port];
1125  buf_nb = udi_cdc_tx_buf_nb[port][buf_sel];
1126  copy_nb = UDI_CDC_TX_BUFFERS - buf_nb;
1127  if (copy_nb > size) {
1128  copy_nb = size;
1129  }
1130  memcpy(&udi_cdc_tx_buf[port][buf_sel][buf_nb], ptr_buf, copy_nb);
1131  udi_cdc_tx_buf_nb[port][buf_sel] = buf_nb + copy_nb;
1132  cpu_irq_restore(flags);
1133 
1134  // Update buffer pointer
1135  ptr_buf = ptr_buf + copy_nb;
1136  size -= copy_nb;
1137 
1138  if (size) {
1139  timeout = WRITE_TIMEOUT;
1140  goto udi_cdc_write_buf_loop_wait;
1141  }
1142 
1143  return 0;
1144 }
1145 
1147 {
1148  return udi_cdc_multi_write_buf(0, buf, size);
1149 }
1150 
void udi_cdc_ctrl_signal_dsr(bool b_set)
Notify a state change of DSR signal.
Definition: udi_cdc.c:786
bool udi_cdc_data_enable(void)
Definition: udi_cdc.c:315
#define UDI_CDC_SET_RTS_EXT(port, set)
Definition: conf_usb.h:139
void udi_cdc_ctrl_signal_dcd(bool b_set)
Notify a state change of DCD signal.
Definition: udi_cdc.c:781
bool udi_cdc_comm_setup(void)
Definition: udi_cdc.c:371
static bool udi_cdc_rx_start(uint8_t port)
Enable the reception of data from the USB host.
Definition: udi_cdc.c:577
#define UDI_CDC_ENABLE_EXT(port)
Interface callback definition.
Definition: conf_usb.h:121
Common API for USB Device Drivers (UDD)
USB configuration file for CDC application.
void udi_cdc_data_sof_notify(void)
Definition: udi_cdc.c:437
#define UNUSED(v)
Marking v as a unused parameter or value.
Definition: compiler.h:86
#define UDI_CDC_SET_CODING_EXT(port, cfg)
Definition: conf_usb.h:134
#define UDI_CDC_TX_EMPTY_NOTIFY(port)
Definition: udi_cdc.c:67
void udi_cdc_comm_disable(void)
Definition: udi_cdc.c:354
void udi_cdc_data_disable(void)
Definition: udi_cdc.c:360
#define UDI_CDC_COMM_IFACE_NUMBER_0
Definition: udi_cdc_conf.h:125
static volatile uint8_t udi_cdc_nb_comm_enabled
Status of CDC COMM interfaces.
Definition: udi_cdc.c:220
#define USB_REQ_CDC_SET_CONTROL_LINE_STATE
#define UDI_CDC_RX_BUFFERS
Definition: udi_cdc.c:62
bool udi_cdc_is_tx_ready(void)
This function checks if a new character sent is possible The type int is used to support scanf redire...
Definition: udi_cdc.c:1045
#define CDC_SERIAL_STATE_BREAK
USB Device Communication Device Class (CDC) interface definitions.
Interface of the USB Device Controller (UDC)
static void udi_cdc_ctrl_state_change(uint8_t port, bool b_set, le16_t bit_mask)
Records new state.
Definition: udi_cdc.c:481
int udi_cdc_multi_putc(uint8_t port, int value)
Puts a byte on CDC line The type int is used to support printf redirection from compiler LIB...
Definition: udi_cdc.c:1050
udd_ep_status_t
Endpoint transfer status Returned in parameters of callback register via udd_ep_run routine...
Definition: udd.h:63
#define UDI_CDC_DATA_EP_OUT_0
Definition: udi_cdc_conf.h:102
#define UDI_CDC_PORT_TO_COMM_EP(index, unused)
USB protocol definitions.
#define CDC_SERIAL_STATE_DCD
void udi_cdc_signal_parity_error(void)
Notify a parity error.
Definition: udi_cdc.c:796
static irqflags_t cpu_irq_save(void)
Get and clear the global interrupt flags.
GeneratorWrapper< T > value(T &&value)
Definition: catch.hpp:3589
static COMPILER_WORD_ALIGNED usb_cdc_line_coding_t udi_cdc_line_coding[UDI_CDC_PORT_NB]
Definition: udi_cdc.c:214
#define UDI_CDC_RX_NOTIFY(port)
Definition: conf_usb.h:127
#define USB_REQ_DIR_IN
Device to host.
Definition: usb_protocol.h:79
#define UDI_CDC_PORT_NB
Definition: udi_cdc.h:49
static iram_size_t udi_cdc_multi_read_no_polling(uint8_t port, void *buf, iram_size_t size)
Definition: udi_cdc.c:955
#define Udd_setup_is_out()
Return true if the setup request udd_g_ctrlreq indicates OUT data transfer.
Definition: udd.h:100
void udi_cdc_signal_overrun(void)
Notify a overrun.
Definition: udi_cdc.c:801
#define UDI_CDC_DEFAULT_DATABITS
Definition: conf_usb.h:151
void(* callback)(void)
Callback called after reception of ZLP from setup request.
Definition: udd.h:87
uint8_t bDataBits
Definition: CDCRequests.h:144
#define Udd_setup_is_in()
Return true if the setup request udd_g_ctrlreq indicates IN data transfer.
Definition: udd.h:96
#define UDI_CDC_DATA_EP_IN_TO_PORT(index, unused)
#define UDI_CDC_PORT_TO_IFACE_COMM(index, unused)
void udi_cdc_multi_ctrl_signal_dsr(uint8_t port, bool b_set)
Notify a state change of DSR signal.
Definition: udi_cdc.c:811
iram_size_t udi_cdc_multi_read_buf(uint8_t port, void *buf, iram_size_t size)
Reads a RAM buffer on CDC line.
Definition: udi_cdc.c:911
void udi_cdc_multi_signal_parity_error(uint8_t port)
Notify a parity error.
Definition: udi_cdc.c:821
#define UDI_CDC_TX_BUFFERS
Definition: udi_cdc.c:61
#define CDC_SERIAL_STATE_FRAMING
iram_size_t udi_cdc_get_nb_received_data(void)
Gets the number of byte received.
Definition: udi_cdc.c:847
#define CDC_SERIAL_STATE_OVERRUN
bool udd_is_high_speed(void)
Test whether the USB Device Controller is running at high speed or not.
Definition: usbhs_device.c:950
#define USB_REQ_CDC_SET_LINE_CODING
iram_size_t udi_cdc_get_free_tx_buffer(void)
Gets the number of free byte in TX buffer.
Definition: udi_cdc.c:1035
UDC_DESC_STORAGE udi_api_t udi_api_cdc_comm
Global structure which contains standard UDI API for UDC.
Definition: udi_cdc.c:86
#define CDC_CTRL_SIGNAL_DTE_PRESENT
uint8_t * payload
Definition: udd.h:81
static void cpu_irq_restore(irqflags_t flags)
Restore global interrupt flags.
#define CDC_SERIAL_STATE_DSR
iram_size_t udi_cdc_write_buf(const void *buf, iram_size_t size)
Writes a RAM buffer on CDC line.
Definition: udi_cdc.c:1146
iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void *buf, iram_size_t size)
Writes a RAM buffer on CDC line.
Definition: udi_cdc.c:1091
bool udi_cdc_multi_is_tx_ready(uint8_t port)
This function checks if a new character sent is possible The type int is used to support scanf redire...
Definition: udi_cdc.c:1040
#define LE16(x)
Definition: compiler.h:890
#define WRITE_TIMEOUT
#define UDI_CDC_DATA_EP_OUT_TO_PORT(index, unused)
bool(* enable)(void)
Enable the interface.
Definition: udi.h:75
#define MREPEAT(count, macro, data)
Macro repeat.
Definition: mrepeat.h:65
static volatile le16_t udi_cdc_state[UDI_CDC_PORT_NB]
Definition: udi_cdc.c:216
UDC_DESC_STORAGE udi_api_t udi_api_cdc_data
Definition: udi_cdc.c:92
COMPILER_ALIGNED(32)
Buffer to receive data.
Definition: udi_cdc.c:233
#define UDI_CDC_DEFAULT_RATE
Default configuration of communication port.
Definition: conf_usb.h:148
bool udi_cdc_is_rx_ready(void)
This function checks if a character has been received on the CDC line.
Definition: udi_cdc.c:857
#define UDI_CDC_PORT_TO_DATA_EP_IN(index, unused)
iram_size_t udi_cdc_read_no_polling(void *buf, iram_size_t size)
Non polling reads of a up to &#39;size&#39; data from CDC line.
Definition: udi_cdc.c:996
#define UDI_CDC_DEFAULT_STOPBITS
Definition: conf_usb.h:149
#define CPU_TO_LE32(x)
Definition: compiler.h:905
#define UDI_CDC_GET_PORT_FROM_COMM_EP(iface, unused)
static void udi_cdc_line_coding_received(void)
Sends line coding to application.
Definition: udi_cdc.c:473
UDI API.
Definition: udi.h:64
#define UDI_CDC_IFACE_COMM_TO_PORT(iface, unused)
#define CDC_SERIAL_STATE_PARITY
#define CDC_SERIAL_STATE_RING
#define USB_REQ_CDC_NOTIFY_SERIAL_STATE
static volatile uint8_t udi_cdc_nb_data_enabled
Status of CDC DATA interfaces.
Definition: udi_cdc.c:230
#define UDI_CDC_COMM_EP_0
Definition: udi_cdc_conf.h:103
#define CPU_TO_LE16(x)
Definition: compiler.h:895
static uint8_t udi_cdc_setup_to_port(void)
Returns the port number corresponding at current setup request.
Definition: udi_cdc.c:455
#define USB_REQ_TYPE_CLASS
Class-specific request.
Definition: usb_protocol.h:86
uint8_t udd_ep_id_t
Endpoint identifier.
Definition: udd.h:59
#define UDI_CDC_DEFAULT_PARITY
Definition: conf_usb.h:150
int udi_cdc_getc(void)
Waits and gets a value on CDC line.
Definition: udi_cdc.c:906
static void udi_cdc_ctrl_state_notify(uint8_t port, udd_ep_id_t ep)
Check and eventually notify the USB host of new state.
Definition: udi_cdc.c:515
uint16_t le16_t
Definition: compiler.h:250
bool udi_cdc_multi_is_rx_ready(uint8_t port)
This function checks if a character has been received on the CDC line.
Definition: udi_cdc.c:852
iram_size_t udi_cdc_multi_get_nb_received_data(uint8_t port)
Gets the number of byte received.
Definition: udi_cdc.c:831
uint16_t udd_get_frame_number(void)
Returns the current start of frame number.
Definition: usbhs_device.c:974
uint16_t udd_get_micro_frame_number(void)
Returns the current micro start of frame number.
Definition: usbhs_device.c:979
uint32_t iram_size_t
Definition: compiler.h:260
#define Udd_setup_type()
Return the type of the SETUP request udd_g_ctrlreq.
Definition: udd.h:104
int udi_cdc_multi_getc(uint8_t port)
Waits and gets a value on CDC line.
Definition: udi_cdc.c:862
#define UDI_CDC_DATA_EP_IN_0
Definition: udi_cdc_conf.h:101
Hardware handshake support (cdc spec 1.1 chapter 6.3.5)
#define CDC_CTRL_SIGNAL_ACTIVATE_CARRIER
usb_setup_req_t req
Definition: udd.h:77
void udi_cdc_multi_ctrl_signal_dcd(uint8_t port, bool b_set)
Notify a state change of DCD signal.
Definition: udi_cdc.c:806
static bool udi_cdc_serial_state_msg_ongoing[UDI_CDC_PORT_NB]
Definition: udi_cdc.c:215
static COMPILER_WORD_ALIGNED usb_cdc_notify_serial_state_t uid_cdc_state_msg[UDI_CDC_PORT_NB]
Definition: udi_cdc.c:217
udd_ctrl_request_t udd_g_ctrlreq
Global variable to give and record information about setup request management.
Definition: usbhs_device.c:459
#define UDI_CDC_SET_DTR_EXT(port, set)
Definition: conf_usb.h:137
#define UDC_DESC_STORAGE
Defines the memory&#39;s location of USB descriptors.
Definition: udc_desc.h:70
static void udi_cdc_data_received(udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep)
Update rx buffer management with a new data Callback called after data reception on USB line...
Definition: udi_cdc.c:627
iram_size_t udi_cdc_multi_get_free_tx_buffer(uint8_t port)
Gets the number of free byte in TX buffer.
Definition: udi_cdc.c:1006
void vTaskDelay(const TickType_t xTicksToDelay) PRIVILEGED_FUNCTION
void udi_cdc_signal_framing_error(void)
Notify a framing error.
Definition: udi_cdc.c:791
uint8_t udi_cdc_getsetting(void)
Definition: udi_cdc.c:432
bool udi_cdc_data_setup(void)
Definition: udi_cdc.c:427
USB Communication Device Class (CDC) protocol definitions.
uint32_t irqflags_t
Type used for holding state of interrupt flag.
int udi_cdc_putc(int value)
Puts a byte on CDC line The type int is used to support printf redirection from compiler LIB...
Definition: udi_cdc.c:1086
iram_size_t udi_cdc_read_buf(void *buf, iram_size_t size)
Reads a RAM buffer on CDC line.
Definition: udi_cdc.c:1001
static volatile bool udi_cdc_data_running
Definition: udi_cdc.c:231
void udi_cdc_multi_signal_framing_error(uint8_t port)
Notify a framing error.
Definition: udi_cdc.c:816
uint16_t payload_size
Size of buffer to send or fill, and content the number of byte transfered.
Definition: udd.h:84
static void udi_cdc_tx_send(uint8_t port)
Send buffer on line or wait a SOF event.
Definition: udi_cdc.c:695
static void udi_cdc_data_sent(udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep)
Ack sent of tx buffer Callback called after data transfer on USB line.
Definition: udi_cdc.c:663
#define USB_REQ_CDC_GET_LINE_CODING
#define Assert(expr)
This macro is used to test fatal errors.
Definition: compiler.h:196
void udi_cdc_multi_signal_overrun(uint8_t port)
Notify a overrun.
Definition: udi_cdc.c:826
Line Coding structure.
#define UDI_CDC_PORT_TO_DATA_EP_OUT(index, unused)
#define UDI_CDC_DISABLE_EXT(port)
Definition: conf_usb.h:125
bool udi_cdc_comm_enable(void)
static void udi_cdc_serial_state_msg_sent(udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep)
Ack sent of serial state message Callback called after serial state message sent. ...
Definition: udi_cdc.c:537
#define USB_REQ_RECIP_INTERFACE
Recipient interface.
Definition: usb_protocol.h:94


inertial_sense_ros
Author(s):
autogenerated on Sun Feb 28 2021 03:17:58