diff --git a/lib/main/STM32_USB_Device_Library/Class/cdc/inc/usbd_cdc_core.h b/lib/main/STM32_USB_Device_Library/Class/cdc/inc/usbd_cdc_core.h index d05ecf5f8e1..54acdd7a7c6 100644 --- a/lib/main/STM32_USB_Device_Library/Class/cdc/inc/usbd_cdc_core.h +++ b/lib/main/STM32_USB_Device_Library/Class/cdc/inc/usbd_cdc_core.h @@ -125,6 +125,7 @@ extern USBD_Class_cb_TypeDef USBD_CDC_cb; /** @defgroup USB_CORE_Exported_Functions * @{ */ +void USBD_CDC_ReceivePacket(void *pdev); /** * @} */ diff --git a/lib/main/STM32_USB_Device_Library/Class/cdc/src/usbd_cdc_core.c b/lib/main/STM32_USB_Device_Library/Class/cdc/src/usbd_cdc_core.c index a82ef08a2f0..2f3eca62e6e 100644 --- a/lib/main/STM32_USB_Device_Library/Class/cdc/src/usbd_cdc_core.c +++ b/lib/main/STM32_USB_Device_Library/Class/cdc/src/usbd_cdc_core.c @@ -674,7 +674,10 @@ uint8_t usbd_cdc_DataOut (void *pdev, uint8_t epnum) /* USB data will be immediately processed, this allow next USB traffic being NAKed till the end of the application Xfer */ - APP_FOPS.pIf_DataRx(USB_Rx_Buffer, USB_Rx_Cnt); + if (APP_FOPS.pIf_DataRx(USB_Rx_Buffer, USB_Rx_Cnt) != USBD_OK) + { + return USBD_OK; + } /* Prepare Out endpoint to receive next packet */ DCD_EP_PrepareRx(pdev, @@ -685,6 +688,14 @@ uint8_t usbd_cdc_DataOut (void *pdev, uint8_t epnum) return USBD_OK; } +void USBD_CDC_ReceivePacket(void *pdev) +{ + DCD_EP_PrepareRx(pdev, + CDC_OUT_EP, + (uint8_t*)(USB_Rx_Buffer), + CDC_DATA_OUT_PACKET_SIZE); +} + /** * @brief usbd_audio_SOF * Start Of Frame event management @@ -696,7 +707,7 @@ uint8_t usbd_cdc_SOF (void *pdev) { static uint32_t FrameCount = 0; - if (FrameCount++ == CDC_IN_FRAME_INTERVAL) + if (FrameCount++ >= CDC_IN_FRAME_INTERVAL) { /* Reset the frame counter */ FrameCount = 0; diff --git a/src/main/drivers/serial.c b/src/main/drivers/serial.c index dc625aaa354..091a7359e53 100644 --- a/src/main/drivers/serial.c +++ b/src/main/drivers/serial.c @@ -71,6 +71,15 @@ uint8_t serialRead(serialPort_t *instance) return instance->vTable->serialRead(instance); } +uint32_t serialReadBuf(serialPort_t *instance, uint8_t *data, uint32_t maxLen) +{ + uint32_t count = 0; + while (count < maxLen && serialRxBytesWaiting(instance)) { + data[count++] = instance->vTable->serialRead(instance); + } + return count; +} + void serialSetBaudRate(serialPort_t *instance, uint32_t baudRate) { instance->vTable->serialSetBaudRate(instance, baudRate); diff --git a/src/main/drivers/serial.h b/src/main/drivers/serial.h index 8e66b5f8445..6ca0a7d1ec2 100644 --- a/src/main/drivers/serial.h +++ b/src/main/drivers/serial.h @@ -113,6 +113,7 @@ uint32_t serialRxBytesWaiting(const serialPort_t *instance); uint32_t serialTxBytesFree(const serialPort_t *instance); void serialWriteBuf(serialPort_t *instance, const uint8_t *data, int count); uint8_t serialRead(serialPort_t *instance); +uint32_t serialReadBuf(serialPort_t *instance, uint8_t *data, uint32_t maxLen); void serialSetBaudRate(serialPort_t *instance, uint32_t baudRate); void serialSetMode(serialPort_t *instance, portMode_t mode); void serialSetOptions(serialPort_t *instance, portOptions_t options); diff --git a/src/main/drivers/serial_usb_vcp.c b/src/main/drivers/serial_usb_vcp.c index 7fdbad2a114..d36a4a78da8 100644 --- a/src/main/drivers/serial_usb_vcp.c +++ b/src/main/drivers/serial_usb_vcp.c @@ -256,4 +256,21 @@ uint32_t usbVcpGetBaudRate(serialPort_t *instance) return CDC_BaudRate(); } +portOptions_t usbVcpGetLineCoding(void) +{ + portOptions_t options = SERIAL_NOT_INVERTED; + + // stop bits: CDC format 0=1 stop, 2=2 stop (1.5 not supported) + if (CDC_StopBits() == 2) { + options |= SERIAL_STOPBITS_2; + } + + // parity: CDC 0=none, 2=even (odd parity not supported in INAV) + if (CDC_Parity() == 2) { + options |= SERIAL_PARITY_EVEN; + } + + return options; +} + #endif diff --git a/src/main/drivers/serial_usb_vcp.h b/src/main/drivers/serial_usb_vcp.h index 4557421b638..fd47022ceae 100644 --- a/src/main/drivers/serial_usb_vcp.h +++ b/src/main/drivers/serial_usb_vcp.h @@ -31,3 +31,4 @@ void usbVcpInitHardware(void); serialPort_t *usbVcpOpen(void); struct serialPort_s; uint32_t usbVcpGetBaudRate(struct serialPort_s *instance); +portOptions_t usbVcpGetLineCoding(void); diff --git a/src/main/drivers/serial_usb_vcp_at32f43x.c b/src/main/drivers/serial_usb_vcp_at32f43x.c index 96b283ec363..32fd67fdb75 100644 --- a/src/main/drivers/serial_usb_vcp_at32f43x.c +++ b/src/main/drivers/serial_usb_vcp_at32f43x.c @@ -495,7 +495,25 @@ uint32_t usbVcpGetBaudRate(serialPort_t *instance) UNUSED(instance); cdc_struct_type *pcdc = (cdc_struct_type *)otg_core_struct.dev.class_handler->pdata; return pcdc->linecoding.bitrate; - // return CDC_BaudRate(); + // return CDC_BaudRate(); +} + +portOptions_t usbVcpGetLineCoding(void) +{ + portOptions_t options = 0; + cdc_struct_type *pcdc = (cdc_struct_type *)otg_core_struct.dev.class_handler->pdata; + + // stop bits: CDC format 0=1 stop, 2=2 stop (1.5 not supported) + if (pcdc->linecoding.format == 2) { + options |= SERIAL_STOPBITS_2; + } + + // parity: CDC 0=none, 2=even (odd parity not supported in INAV) + if (pcdc->linecoding.parity == 2) { + options |= SERIAL_PARITY_EVEN; + } + + return options; } #endif diff --git a/src/main/io/serial.c b/src/main/io/serial.c index d6b82da02b8..d88f071e7cd 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -509,6 +509,85 @@ void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort) }; } +void escapeSequenceInit(escapeSequenceState_t *state) +{ + state->lastCharTime = 0; + state->lastPlusTime = 0; + state->count = 0; +} + +void escapeSequenceProcessChar(escapeSequenceState_t *state, uint8_t c, uint32_t now) +{ + if (c == '+') { + if (state->count == 0) { + // First '+': check for leading guard interval + if (now - state->lastCharTime >= 1000) { + state->count = 1; + state->lastPlusTime = now; + } + } else if (state->count < 3) { + // Subsequent '+': must arrive within 1 second of previous '+' + if (now - state->lastPlusTime < 1000) { + state->count++; + state->lastPlusTime = now; + } else { + state->count = 0; // too much time between pluses + } + } else { + // More than 3 pluses - not a valid escape sequence + state->count = 0; + } + } else { + // Non-'+' character resets sequence + state->count = 0; + } + state->lastCharTime = now; +} + +bool escapeSequenceCheckGuard(escapeSequenceState_t *state, uint32_t now) +{ + if (state->count == 3) { + if (now - state->lastPlusTime >= 1000) { + return true; + } + } + return false; +} + +static bool serialPassthroughTransfer(serialPort_t *src, serialPort_t *dst, serialConsumer *consumer, escapeSequenceState_t *escapeState, uint32_t now) +{ + uint8_t buf[64]; + uint32_t available = serialRxBytesWaiting(src); + uint32_t free = serialTxBytesFree(dst); + uint32_t count = (available < free) ? available : free; + if (count > sizeof(buf)) { + count = sizeof(buf); + } + + if (count > 0) { + LED0_ON; + serialBeginWrite(dst); + serialReadBuf(src, buf, count); + serialWriteBuf(dst, buf, count); + for (uint32_t i = 0; i < count; i++) { + consumer(buf[i]); + // Hayes escape sequence detection: [1s silence]+++[1s silence] + // https://en.wikipedia.org/wiki/Escape_sequence#Modem_control + if (escapeState) { + escapeSequenceProcessChar(escapeState, buf[i], now); + } + } + serialEndWrite(dst); + LED0_OFF; + } else { + if (escapeState) { + return escapeSequenceCheckGuard(escapeState, now); + } + } + + return false; +} + #if defined(USE_GPS) || defined(USE_SERIAL_PASSTHROUGH) // Default data consumer for serialPassThrough. static void nopConsumer(uint8_t data) @@ -535,32 +614,54 @@ void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer LED0_OFF; LED1_OFF; +#ifdef USE_VCP + // Track current encoding applied to right port for VCP mirroring + portOptions_t currentOptions = right->options; + uint32_t currentBaudRate = right->baudRate; + bool leftIsVcp = (left->identifier == SERIAL_PORT_USB_VCP); + uint32_t lastMirrorTime = 0; +#endif + + static escapeSequenceState_t escapeSequenceState; + escapeSequenceInit(&escapeSequenceState); + // Either port might be open in a mode other than MODE_RXTX. We rely on // serialRxBytesWaiting() to do the right thing for a TX only port. No // special handling is necessary OR performed. while (1) { - // TODO: maintain a timestamp of last data received. Use this to - // implement a guard interval and check for `+++` as an escape sequence - // to return to CLI command mode. - // https://en.wikipedia.org/wiki/Escape_sequence#Modem_control - if (serialRxBytesWaiting(left)) { - LED0_ON; - uint8_t c = serialRead(left); - // Make sure there is space in the tx buffer - while (!serialTxBytesFree(right)); - serialWrite(right, c); - leftC(c); - LED0_OFF; - } - if (serialRxBytesWaiting(right)) { - LED0_ON; - uint8_t c = serialRead(right); - // Make sure there is space in the tx buffer - while (!serialTxBytesFree(left)); - serialWrite(left, c); - rightC(c); - LED0_OFF; - } + uint32_t now = millis(); +#ifdef USE_VCP + // Mirror line coding from host PC to passthrough port (rate-limited to 15ms) + if (leftIsVcp) { + if (now - lastMirrorTime >= 15) { + lastMirrorTime = now; + uint32_t hostBaudRate = usbVcpGetBaudRate(left); + portOptions_t hostOptions = usbVcpGetLineCoding(); + + // apply baud rate change + if (hostBaudRate != currentBaudRate && hostBaudRate != 0) { + serialSetBaudRate(right, hostBaudRate); + currentBaudRate = hostBaudRate; + } + + // apply encoding change (parity/stop bits) + if (hostOptions != currentOptions) { + serialSetOptions(right, hostOptions); + currentOptions = hostOptions; + } + } + } +#endif + + // Left (USB) to right (UART) + if (serialPassthroughTransfer(left, right, leftC, &escapeSequenceState, now)) { + return; + } + + // Right (UART) to left (USB) + serialPassthroughTransfer(right, left, rightC, NULL, now); } } #endif + + diff --git a/src/main/io/serial.h b/src/main/io/serial.h index a746dc77177..3e41a4475f9 100644 --- a/src/main/io/serial.h +++ b/src/main/io/serial.h @@ -139,6 +139,18 @@ PG_DECLARE(serialConfig_t, serialConfig); typedef void serialConsumer(uint8_t); +// Hayes escape sequence detection state: [1s silence]+++[1s silence] +// https://en.wikipedia.org/wiki/Escape_sequence#Modem_control +typedef struct escapeSequenceState_s { + uint32_t lastCharTime; + uint32_t lastPlusTime; + uint8_t count; +} escapeSequenceState_t; + +void escapeSequenceInit(escapeSequenceState_t *state); +void escapeSequenceProcessChar(escapeSequenceState_t *state, uint8_t c, uint32_t now); +bool escapeSequenceCheckGuard(escapeSequenceState_t *state, uint32_t now); + // // configuration // diff --git a/src/main/vcp_hal/usbd_cdc_interface.c b/src/main/vcp_hal/usbd_cdc_interface.c index dbc093fb641..9cc674c2316 100644 --- a/src/main/vcp_hal/usbd_cdc_interface.c +++ b/src/main/vcp_hal/usbd_cdc_interface.c @@ -53,6 +53,7 @@ #include "usbd_cdc.h" #include "usbd_cdc_interface.h" #include "stdbool.h" +#include #include "drivers/time.h" #include "drivers/nvic.h" #include "build/atomic.h" @@ -61,6 +62,7 @@ /* Private define ------------------------------------------------------------*/ #define APP_RX_DATA_SIZE 4096 #define APP_TX_DATA_SIZE 4096 +#define USB_RX_STALL_THRESHOLD 128 // Must be >= max USB packet size (64) /* Private macro -------------------------------------------------------------*/ /* Private variables ---------------------------------------------------------*/ @@ -72,17 +74,27 @@ USBD_CDC_LineCodingTypeDef LineCoding = 0x08 /* nb. of bits 8*/ }; -uint8_t UserRxBuffer[APP_RX_DATA_SIZE];/* Received Data over USB are stored in this buffer */ +/* + APP RX is the circular buffer for data that is received from the USB device (host) + to the APP (flight controller). +*/ +uint8_t AppRxBuffer[APP_RX_DATA_SIZE]; +volatile uint32_t AppRxPtrIn = 0; +/* Increment this buffer position or roll it back to + start address when writing received data + in the buffer APP_Rx_Buffer. */ +volatile uint32_t AppRxPtrOut = 0; +static volatile bool packetReceiveStalled; + +uint8_t UsbRxBuffer[64]; /* Small buffer for USB hardware to write into */ + uint8_t UserTxBuffer[APP_TX_DATA_SIZE];/* Received Data over UART (CDC interface) are stored in this buffer */ uint32_t BuffLength; uint32_t UserTxBufPtrIn = 0;/* Increment this pointer or roll it back to - start address when data are received over USART */ + start address when data are received over USART */ uint32_t UserTxBufPtrOut = 0; /* Increment this pointer or roll it back to start address when data are sent over USB */ -uint32_t rxAvailable = 0; -uint8_t* rxBuffPtr = NULL; - /* TIM handler declaration */ TIM_HandleTypeDef TimHandle; /* USB handler declaration */ @@ -146,10 +158,18 @@ static int8_t CDC_Itf_Init(void) /*##-5- Set Application Buffers ############################################*/ USBD_CDC_SetTxBuffer(&USBD_Device, UserTxBuffer, 0); - USBD_CDC_SetRxBuffer(&USBD_Device, UserRxBuffer); + USBD_CDC_SetRxBuffer(&USBD_Device, UsbRxBuffer); ctrlLineStateCb = NULL; baudRateCb = NULL; + + // Reset RX flow control state + AppRxPtrIn = 0; + AppRxPtrOut = 0; + packetReceiveStalled = false; + + // Prepare to receive first packet + USBD_CDC_ReceivePacket(&USBD_Device); return (USBD_OK); } @@ -286,20 +306,45 @@ void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) * @brief CDC_Itf_DataRx * Data received over USB OUT endpoint are sent over CDC interface * through this function. - * @param Buf: Buffer of data to be transmitted + * + * @note + * This function will block any OUT packet reception on USB endpoint + * until exiting this function. If you exit this function before transfer + * is complete on CDC interface (ie. using DMA controller) it will result + * in receiving more data while previous ones are still not sent. + * + * @param Buf: Buffer of data to be received * @param Len: Number of data received (in bytes) * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL */ static int8_t CDC_Itf_Receive(uint8_t* Buf, uint32_t *Len) { - rxAvailable = *Len; - rxBuffPtr = Buf; - if (!rxAvailable) { - // Received an empty packet, trigger receiving the next packet. - // This will happen after a packet that's exactly 64 bytes is received. - // The USB protocol requires that an empty (0 byte) packet immediately follow. + // Copy received data to ring buffer, handling wrap-around + uint32_t len = *Len; + uint32_t ptrIn = AppRxPtrIn; + uint32_t tailRoom = APP_RX_DATA_SIZE - ptrIn; + + if (len <= tailRoom) { + // Data fits without wrapping + memcpy(&AppRxBuffer[ptrIn], Buf, len); + ptrIn = (ptrIn + len) % APP_RX_DATA_SIZE; + } else { + // Data wraps around - copy in two parts + memcpy(&AppRxBuffer[ptrIn], Buf, tailRoom); + memcpy(&AppRxBuffer[0], Buf + tailRoom, len - tailRoom); + ptrIn = len - tailRoom; + } + AppRxPtrIn = ptrIn; + + // Check if we have room for another packet; if not, stall + uint32_t free = (APP_RX_DATA_SIZE + AppRxPtrOut - ptrIn - 1) % APP_RX_DATA_SIZE; + if (free <= USB_RX_STALL_THRESHOLD) { + packetReceiveStalled = true; + return USBD_FAIL; // Don't arm next receive + } else { USBD_CDC_ReceivePacket(&USBD_Device); } + return (USBD_OK); } @@ -373,27 +418,52 @@ static void Error_Handler(void) /* Add your own code here */ } +/******************************************************************************* + * Function Name : Receive DATA . + * Description : Copy received USB data from the ring buffer to the application buffer + * Input : None. + * Output : None. + * Return : None. + *******************************************************************************/ uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len) { - uint32_t count = 0; - if ( (rxBuffPtr != NULL)) - { - while ((rxAvailable > 0) && count < len) - { - recvBuf[count] = rxBuffPtr[0]; - rxBuffPtr++; - rxAvailable--; - count++; - if (rxAvailable < 1) - USBD_CDC_ReceivePacket(&USBD_Device); + uint32_t available = (AppRxPtrIn + APP_RX_DATA_SIZE - AppRxPtrOut) % APP_RX_DATA_SIZE; + uint32_t count = (len < available) ? len : available; + uint32_t ptrOut = AppRxPtrOut; + uint32_t tailRoom = APP_RX_DATA_SIZE - ptrOut; + + if (count == 0) { + return 0; + } + + if (count <= tailRoom) { + // Data is contiguous + memcpy(recvBuf, &AppRxBuffer[ptrOut], count); + ptrOut = (ptrOut + count) % APP_RX_DATA_SIZE; + } else { + // Data wraps around + memcpy(recvBuf, &AppRxBuffer[ptrOut], tailRoom); + memcpy(recvBuf + tailRoom, &AppRxBuffer[0], count - tailRoom); + ptrOut = count - tailRoom; + } + AppRxPtrOut = ptrOut; + + // If stalled, check if we have room to resume receiving + if (packetReceiveStalled) { + uint32_t free = (APP_RX_DATA_SIZE + AppRxPtrOut - AppRxPtrIn - 1) % APP_RX_DATA_SIZE; + if (free > USB_RX_STALL_THRESHOLD) { + packetReceiveStalled = false; + USBD_CDC_ReceivePacket(&USBD_Device); } } + return count; } uint32_t CDC_Receive_BytesAvailable(void) { - return rxAvailable; + /* return the bytes available in the receive circular buffer */ + return (AppRxPtrIn + APP_RX_DATA_SIZE - AppRxPtrOut) % APP_RX_DATA_SIZE; } uint32_t CDC_Send_FreeBytes(void) @@ -473,6 +543,30 @@ uint32_t CDC_BaudRate(void) return LineCoding.bitrate; } +/******************************************************************************* + * Function Name : CDC_StopBits. + * Description : Get the current stop bits setting + * Input : None. + * Output : None. + * Return : Stop bits (0=1, 1=1.5, 2=2) + *******************************************************************************/ +uint8_t CDC_StopBits(void) +{ + return LineCoding.format; +} + +/******************************************************************************* + * Function Name : CDC_Parity. + * Description : Get the current parity setting + * Input : None. + * Output : None. + * Return : Parity (0=none, 1=odd, 2=even, 3=mark, 4=space) + *******************************************************************************/ +uint8_t CDC_Parity(void) +{ + return LineCoding.paritytype; +} + /******************************************************************************* * Function Name : CDC_SetBaudRateCb * Description : Set a callback to call when baud rate changes diff --git a/src/main/vcp_hal/usbd_cdc_interface.h b/src/main/vcp_hal/usbd_cdc_interface.h index c6025e68841..bd521eb32bf 100644 --- a/src/main/vcp_hal/usbd_cdc_interface.h +++ b/src/main/vcp_hal/usbd_cdc_interface.h @@ -86,6 +86,8 @@ uint32_t CDC_Receive_BytesAvailable(void); uint8_t usbIsConfigured(void); uint8_t usbIsConnected(void); uint32_t CDC_BaudRate(void); +uint8_t CDC_StopBits(void); +uint8_t CDC_Parity(void); void CDC_SetCtrlLineStateCb(void (*cb)(void *context, uint16_t ctrlLineState), void *context); void CDC_SetBaudRateCb(void (*cb)(void *context, uint32_t baud), void *context); diff --git a/src/main/vcpf4/usbd_cdc_vcp.c b/src/main/vcpf4/usbd_cdc_vcp.c index 15c1f7e39d9..f094c0af6d6 100644 --- a/src/main/vcpf4/usbd_cdc_vcp.c +++ b/src/main/vcpf4/usbd_cdc_vcp.c @@ -21,8 +21,10 @@ /* Includes ------------------------------------------------------------------*/ #include "usbd_cdc_vcp.h" +#include "usbd_cdc_core.h" #include "stm32f4xx_conf.h" #include +#include #include "drivers/time.h" #ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED @@ -45,14 +47,18 @@ extern volatile uint32_t APP_Rx_ptr_out; start address when writing received data in the buffer APP_Rx_Buffer. */ extern volatile uint32_t APP_Rx_ptr_in; +static volatile bool packetReceiveStalled; +#define USB_RX_STALL_THRESHOLD 128 // Must be >= max USB packet size (64) + +// runtime-configurable tx poll interval (default matches CDC_IN_FRAME_INTERVAL) /* APP TX is the circular buffer for data that is transmitted from the APP (host) to the USB device (flight controller). */ static uint8_t APP_Tx_Buffer[APP_TX_DATA_SIZE]; -static uint32_t APP_Tx_ptr_out = 0; -static uint32_t APP_Tx_ptr_in = 0; +static volatile uint32_t APP_Tx_ptr_out = 0; +static volatile uint32_t APP_Tx_ptr_in = 0; /* Private function prototypes -----------------------------------------------*/ static uint16_t VCP_Init(void); @@ -80,6 +86,12 @@ static uint16_t VCP_Init(void) bDeviceState = CONFIGURED; ctrlLineStateCb = NULL; baudRateCb = NULL; + + // Reset RX flow control state + APP_Tx_ptr_in = 0; + APP_Tx_ptr_out = 0; + packetReceiveStalled = false; + return USBD_OK; } @@ -218,7 +230,7 @@ static uint16_t VCP_DataTx(const uint8_t* Buf, uint32_t Len) /******************************************************************************* * Function Name : Receive DATA . - * Description : receive the data from the PC to STM32 and send it through USB + * Description : Copy received USB data from the ring buffer to the application buffer * Input : None. * Output : None. * Return : None. @@ -227,11 +239,22 @@ uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len) { uint32_t count = 0; + // Drain the ring buffer into the user buffer while (APP_Tx_ptr_out != APP_Tx_ptr_in && (count < len)) { recvBuf[count] = APP_Tx_Buffer[APP_Tx_ptr_out]; APP_Tx_ptr_out = (APP_Tx_ptr_out + 1) % APP_TX_DATA_SIZE; count++; } + + // If stalled, check if we have room to resume receiving + if (packetReceiveStalled) { + uint32_t free = (APP_TX_DATA_SIZE + APP_Tx_ptr_out - APP_Tx_ptr_in - 1) % APP_TX_DATA_SIZE; + if (free > USB_RX_STALL_THRESHOLD) { + packetReceiveStalled = false; + USBD_CDC_ReceivePacket(&USB_OTG_dev); + } + } + return count; } @@ -258,13 +281,27 @@ uint32_t CDC_Receive_BytesAvailable(void) */ static uint16_t VCP_DataRx(uint8_t* Buf, uint32_t Len) { - if (CDC_Receive_BytesAvailable() + Len > APP_TX_DATA_SIZE) { - return USBD_FAIL; + // Copy received data to ring buffer, handling wrap-around + uint32_t ptrIn = APP_Tx_ptr_in; + uint32_t tailRoom = APP_TX_DATA_SIZE - ptrIn; + + if (Len <= tailRoom) { + // Data fits without wrapping + memcpy(&APP_Tx_Buffer[ptrIn], Buf, Len); + ptrIn = (ptrIn + Len) % APP_TX_DATA_SIZE; + } else { + // Data wraps around - copy in two parts + memcpy(&APP_Tx_Buffer[ptrIn], Buf, tailRoom); + memcpy(&APP_Tx_Buffer[0], Buf + tailRoom, Len - tailRoom); + ptrIn = Len - tailRoom; } + APP_Tx_ptr_in = ptrIn; - for (uint32_t i = 0; i < Len; i++) { - APP_Tx_Buffer[APP_Tx_ptr_in] = Buf[i]; - APP_Tx_ptr_in = (APP_Tx_ptr_in + 1) % APP_TX_DATA_SIZE; + // Check if we have room for another packet; if not, stall + uint32_t free = (APP_TX_DATA_SIZE + APP_Tx_ptr_out - ptrIn - 1) % APP_TX_DATA_SIZE; + if (free <= USB_RX_STALL_THRESHOLD) { + packetReceiveStalled = true; + return USBD_FAIL; // Don't arm next receive } return USBD_OK; @@ -306,6 +343,30 @@ uint32_t CDC_BaudRate(void) return g_lc.bitrate; } +/******************************************************************************* + * Function Name : CDC_StopBits. + * Description : Get the current stop bits setting + * Input : None. + * Output : None. + * Return : Stop bits (0=1, 1=1.5, 2=2) + *******************************************************************************/ +uint8_t CDC_StopBits(void) +{ + return g_lc.format; +} + +/******************************************************************************* + * Function Name : CDC_Parity. + * Description : Get the current parity setting + * Input : None. + * Output : None. + * Return : Parity (0=none, 1=odd, 2=even, 3=mark, 4=space) + *******************************************************************************/ +uint8_t CDC_Parity(void) +{ + return g_lc.paritytype; +} + /******************************************************************************* * Function Name : CDC_SetBaudRateCb * Description : Set a callback to call when baud rate changes diff --git a/src/main/vcpf4/usbd_cdc_vcp.h b/src/main/vcpf4/usbd_cdc_vcp.h index fc27a6d98ee..fcd37639771 100644 --- a/src/main/vcpf4/usbd_cdc_vcp.h +++ b/src/main/vcpf4/usbd_cdc_vcp.h @@ -44,6 +44,8 @@ uint32_t CDC_Receive_BytesAvailable(void); uint8_t usbIsConfigured(void); // HJI uint8_t usbIsConnected(void); // HJI uint32_t CDC_BaudRate(void); +uint8_t CDC_StopBits(void); +uint8_t CDC_Parity(void); void CDC_SetCtrlLineStateCb(void (*cb)(void *context, uint16_t ctrlLineState), void *context); void CDC_SetBaudRateCb(void (*cb)(void *context, uint32_t baud), void *context);