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) 53 # define UDI_CDC_TX_BUFFERS (UDI_CDC_DATA_EPS_FS_SIZE) 54 # define UDI_CDC_RX_BUFFERS (UDI_CDC_DATA_EPS_FS_SIZE) 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) 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) 66 #ifndef UDI_CDC_TX_EMPTY_NOTIFY 67 # define UDI_CDC_TX_EMPTY_NOTIFY(port) 213 COMPILER_WORD_ALIGNED
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];
244 #define UDI_CDC_TRANS_HALTED 2 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];
264 uint8_t iface_comm_num;
266 #if UDI_CDC_PORT_NB == 1 // To optimize code 286 #define UDI_CDC_PORT_TO_IFACE_COMM(index, unused) \ 288 iface_comm_num = UDI_CDC_COMM_IFACE_NUMBER_##index; \ 291 #undef UDI_CDC_PORT_TO_IFACE_COMM 319 #if UDI_CDC_PORT_NB == 1 // To optimize code 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;
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;
387 udi_cdc_line_coding[port];
408 udi_cdc_line_coding[port];
439 static uint8_t port_notify = 0;
443 #if UDI_CDC_PORT_NB != 1 // To optimize code 445 if (port_notify >= UDI_CDC_PORT_NB) {
460 #define UDI_CDC_IFACE_COMM_TO_PORT(iface, unused) \ 461 case UDI_CDC_COMM_IFACE_NUMBER_##iface: \ 465 #undef UDI_CDC_IFACE_COMM_TO_PORT 486 #if UDI_CDC_PORT_NB == 1 // To optimize code 501 #define UDI_CDC_PORT_TO_COMM_EP(index, unused) \ 503 ep_comm = UDI_CDC_COMM_EP_##index; \ 506 #undef UDI_CDC_PORT_TO_COMM_EP 517 #if UDI_CDC_PORT_NB == 1 // To optimize code 544 #define UDI_CDC_GET_PORT_FROM_COMM_EP(iface, unused) \ 545 case UDI_CDC_COMM_EP_##iface: \ 549 #undef UDI_CDC_GET_PORT_FROM_COMM_EP 580 uint8_t buf_sel_trans;
583 #if UDI_CDC_PORT_NB == 1 // To optimize code 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])) {
597 udi_cdc_rx_pos[port] = 0;
598 udi_cdc_rx_buf_sel[port] = (buf_sel_trans==0)?1:0;
601 udi_cdc_rx_trans_ongoing[port] =
true;
609 #define UDI_CDC_PORT_TO_DATA_EP_OUT(index, unused) \ 611 ep = UDI_CDC_DATA_EP_OUT_##index; \ 614 #undef UDI_CDC_PORT_TO_DATA_EP_OUT 619 return udd_ep_run(ep,
621 udi_cdc_rx_buf[port][buf_sel_trans],
629 uint8_t buf_sel_trans;
633 #define UDI_CDC_DATA_EP_OUT_TO_PORT(index, unused) \ 634 case UDI_CDC_DATA_EP_OUT_##index: \ 638 #undef UDI_CDC_DATA_EP_OUT_TO_PORT 648 buf_sel_trans = (udi_cdc_rx_buf_sel[port]==0)?1:0;
652 udi_cdc_rx_buf[port][buf_sel_trans],
657 udi_cdc_rx_buf_nb[port][buf_sel_trans] = n;
658 udi_cdc_rx_trans_ongoing[port] =
false;
669 #define UDI_CDC_DATA_EP_IN_TO_PORT(index, unused) \ 670 case UDI_CDC_DATA_EP_IN_##index: \ 674 #undef UDI_CDC_DATA_EP_IN_TO_PORT 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;
698 uint8_t buf_sel_trans;
701 static uint16_t sof_zlp_counter = 0;
703 #if UDI_CDC_PORT_NB == 1 // To optimize code 707 if (udi_cdc_tx_trans_ongoing[port]) {
721 buf_sel_trans = udi_cdc_tx_buf_sel[port];
722 if (udi_cdc_tx_buf_nb[port][buf_sel_trans] == 0) {
732 if (!udi_cdc_tx_both_buf_to_send[port]) {
735 udi_cdc_tx_buf_sel[port] = (buf_sel_trans==0)?1:0;
739 buf_sel_trans = (buf_sel_trans==0)?1:0;
741 udi_cdc_tx_trans_ongoing[port] =
true;
745 if (b_short_packet) {
752 udi_cdc_tx_sof_num[port] = 0;
757 #define UDI_CDC_PORT_TO_DATA_EP_IN(index, unused) \ 759 ep = UDI_CDC_DATA_EP_IN_##index; \ 762 #undef UDI_CDC_PORT_TO_DATA_EP_IN 769 udi_cdc_tx_buf[port][buf_sel_trans],
770 udi_cdc_tx_buf_nb[port][buf_sel_trans],
837 #if UDI_CDC_PORT_NB == 1 // To optimize code 841 pos = udi_cdc_rx_pos[port];
842 nb_received = udi_cdc_rx_buf_nb[port][udi_cdc_rx_buf_sel[port]] - pos;
871 #if UDI_CDC_PORT_NB == 1 // To optimize code 875 b_databit_9 = (9 == udi_cdc_line_coding[port].
bDataBits);
877 udi_cdc_getc_process_one_byte:
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];
888 goto udi_cdc_getc_process_one_byte;
892 rx_data |= udi_cdc_rx_buf[port][buf_sel][pos];
893 udi_cdc_rx_pos[port] = pos+1;
900 rx_data = rx_data << 8;
901 goto udi_cdc_getc_process_one_byte;
914 uint8_t *ptr_buf = (uint8_t *)buf;
920 #if UDI_CDC_PORT_NB == 1 // To optimize code 924 udi_cdc_read_buf_loop_wait:
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];
935 goto udi_cdc_read_buf_loop_wait;
939 copy_nb = udi_cdc_rx_buf_nb[port][buf_sel] - pos;
943 memcpy(ptr_buf, &udi_cdc_rx_buf[port][buf_sel][pos], copy_nb);
944 udi_cdc_rx_pos[port] += copy_nb;
950 goto udi_cdc_read_buf_loop_wait;
957 uint8_t *ptr_buf = (uint8_t *)buf;
963 #if UDI_CDC_PORT_NB == 1 // To optimize code 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;
981 if(nb_avail_data<size) {
982 size = nb_avail_data;
985 memcpy(ptr_buf, &udi_cdc_rx_buf[port][buf_sel][pos], size);
987 udi_cdc_rx_pos[port] += size;
1012 #if UDI_CDC_PORT_NB == 1 // To optimize code 1017 buf_sel = udi_cdc_tx_buf_sel[port];
1018 buf_sel_nb = udi_cdc_tx_buf_nb[port][buf_sel];
1020 if ((!udi_cdc_tx_trans_ongoing[port])
1021 && (!udi_cdc_tx_both_buf_to_send[port])) {
1025 udi_cdc_tx_both_buf_to_send[port] =
true;
1026 udi_cdc_tx_buf_sel[port] = (buf_sel == 0)? 1 : 0;
1056 #if UDI_CDC_PORT_NB == 1 // To optimize code 1060 b_databit_9 = (9 == udi_cdc_line_coding[port].
bDataBits);
1062 udi_cdc_putc_process_one_byte:
1068 goto udi_cdc_putc_process_one_byte;
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;
1079 b_databit_9 =
false;
1081 goto udi_cdc_putc_process_one_byte;
1097 uint8_t *ptr_buf = (uint8_t *)buf;
1098 #define WRITE_TIMEOUT 10 1101 #if UDI_CDC_PORT_NB == 1 // To optimize code 1105 if (9 == udi_cdc_line_coding[port].
bDataBits) {
1109 udi_cdc_write_buf_loop_wait:
1119 goto udi_cdc_write_buf_loop_wait;
1124 buf_sel = udi_cdc_tx_buf_sel[port];
1125 buf_nb = udi_cdc_tx_buf_nb[port][buf_sel];
1127 if (copy_nb > size) {
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;
1135 ptr_buf = ptr_buf + copy_nb;
1140 goto udi_cdc_write_buf_loop_wait;
void udi_cdc_ctrl_signal_dsr(bool b_set)
Notify a state change of DSR signal.
bool udi_cdc_data_enable(void)
#define UDI_CDC_SET_RTS_EXT(port, set)
void udi_cdc_ctrl_signal_dcd(bool b_set)
Notify a state change of DCD signal.
bool udi_cdc_comm_setup(void)
static bool udi_cdc_rx_start(uint8_t port)
Enable the reception of data from the USB host.
#define UDI_CDC_ENABLE_EXT(port)
Interface callback definition.
Common API for USB Device Drivers (UDD)
USB configuration file for CDC application.
void udi_cdc_data_sof_notify(void)
#define UNUSED(v)
Marking v as a unused parameter or value.
#define UDI_CDC_SET_CODING_EXT(port, cfg)
#define UDI_CDC_TX_EMPTY_NOTIFY(port)
void udi_cdc_comm_disable(void)
void udi_cdc_data_disable(void)
#define UDI_CDC_COMM_IFACE_NUMBER_0
static volatile uint8_t udi_cdc_nb_comm_enabled
Status of CDC COMM interfaces.
#define USB_REQ_CDC_SET_CONTROL_LINE_STATE
#define UDI_CDC_RX_BUFFERS
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...
#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.
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...
udd_ep_status_t
Endpoint transfer status Returned in parameters of callback register via udd_ep_run routine...
#define UDI_CDC_DATA_EP_OUT_0
#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.
static irqflags_t cpu_irq_save(void)
Get and clear the global interrupt flags.
GeneratorWrapper< T > value(T &&value)
static COMPILER_WORD_ALIGNED usb_cdc_line_coding_t udi_cdc_line_coding[UDI_CDC_PORT_NB]
#define UDI_CDC_RX_NOTIFY(port)
#define USB_REQ_DIR_IN
Device to host.
static iram_size_t udi_cdc_multi_read_no_polling(uint8_t port, void *buf, iram_size_t size)
#define Udd_setup_is_out()
Return true if the setup request udd_g_ctrlreq indicates OUT data transfer.
void udi_cdc_signal_overrun(void)
Notify a overrun.
#define UDI_CDC_DEFAULT_DATABITS
void(* callback)(void)
Callback called after reception of ZLP from setup request.
usb_cdc_notify_msg_t header
#define Udd_setup_is_in()
Return true if the setup request udd_g_ctrlreq indicates IN data transfer.
#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.
iram_size_t udi_cdc_multi_read_buf(uint8_t port, void *buf, iram_size_t size)
Reads a RAM buffer on CDC line.
void udi_cdc_multi_signal_parity_error(uint8_t port)
Notify a parity error.
#define UDI_CDC_TX_BUFFERS
#define CDC_SERIAL_STATE_FRAMING
iram_size_t udi_cdc_get_nb_received_data(void)
Gets the number of byte received.
#define CDC_SERIAL_STATE_OVERRUN
bool udd_is_high_speed(void)
Test whether the USB Device Controller is running at high speed or not.
#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.
UDC_DESC_STORAGE udi_api_t udi_api_cdc_comm
Global structure which contains standard UDI API for UDC.
#define CDC_CTRL_SIGNAL_DTE_PRESENT
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.
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.
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...
#define UDI_CDC_DATA_EP_OUT_TO_PORT(index, unused)
bool(* enable)(void)
Enable the interface.
#define MREPEAT(count, macro, data)
Macro repeat.
static volatile le16_t udi_cdc_state[UDI_CDC_PORT_NB]
UDC_DESC_STORAGE udi_api_t udi_api_cdc_data
COMPILER_ALIGNED(32)
Buffer to receive data.
#define UDI_CDC_DEFAULT_RATE
Default configuration of communication port.
bool udi_cdc_is_rx_ready(void)
This function checks if a character has been received on the CDC line.
#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 'size' data from CDC line.
#define UDI_CDC_DEFAULT_STOPBITS
#define UDI_CDC_GET_PORT_FROM_COMM_EP(iface, unused)
static void udi_cdc_line_coding_received(void)
Sends line coding to application.
#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.
#define UDI_CDC_COMM_EP_0
static uint8_t udi_cdc_setup_to_port(void)
Returns the port number corresponding at current setup request.
#define USB_REQ_TYPE_CLASS
Class-specific request.
uint8_t udd_ep_id_t
Endpoint identifier.
#define UDI_CDC_DEFAULT_PARITY
int udi_cdc_getc(void)
Waits and gets a value on CDC line.
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.
bool udi_cdc_multi_is_rx_ready(uint8_t port)
This function checks if a character has been received on the CDC line.
iram_size_t udi_cdc_multi_get_nb_received_data(uint8_t port)
Gets the number of byte received.
uint16_t udd_get_frame_number(void)
Returns the current start of frame number.
uint16_t udd_get_micro_frame_number(void)
Returns the current micro start of frame number.
#define Udd_setup_type()
Return the type of the SETUP request udd_g_ctrlreq.
int udi_cdc_multi_getc(uint8_t port)
Waits and gets a value on CDC line.
#define UDI_CDC_DATA_EP_IN_0
Hardware handshake support (cdc spec 1.1 chapter 6.3.5)
#define CDC_CTRL_SIGNAL_ACTIVATE_CARRIER
void udi_cdc_multi_ctrl_signal_dcd(uint8_t port, bool b_set)
Notify a state change of DCD signal.
static bool udi_cdc_serial_state_msg_ongoing[UDI_CDC_PORT_NB]
static COMPILER_WORD_ALIGNED usb_cdc_notify_serial_state_t uid_cdc_state_msg[UDI_CDC_PORT_NB]
udd_ctrl_request_t udd_g_ctrlreq
Global variable to give and record information about setup request management.
#define UDI_CDC_SET_DTR_EXT(port, set)
#define UDC_DESC_STORAGE
Defines the memory's location of USB descriptors.
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...
iram_size_t udi_cdc_multi_get_free_tx_buffer(uint8_t port)
Gets the number of free byte in TX buffer.
void vTaskDelay(const TickType_t xTicksToDelay) PRIVILEGED_FUNCTION
void udi_cdc_signal_framing_error(void)
Notify a framing error.
uint8_t udi_cdc_getsetting(void)
bool udi_cdc_data_setup(void)
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...
iram_size_t udi_cdc_read_buf(void *buf, iram_size_t size)
Reads a RAM buffer on CDC line.
static volatile bool udi_cdc_data_running
void udi_cdc_multi_signal_framing_error(uint8_t port)
Notify a framing error.
uint16_t payload_size
Size of buffer to send or fill, and content the number of byte transfered.
static void udi_cdc_tx_send(uint8_t port)
Send buffer on line or wait a SOF event.
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.
#define USB_REQ_CDC_GET_LINE_CODING
#define Assert(expr)
This macro is used to test fatal errors.
void udi_cdc_multi_signal_overrun(uint8_t port)
Notify a overrun.
#define UDI_CDC_PORT_TO_DATA_EP_OUT(index, unused)
#define UDI_CDC_DISABLE_EXT(port)
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. ...
#define USB_REQ_RECIP_INTERFACE
Recipient interface.