mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 05:15:25 +03:00
VCP improvements to remove need for delay in serial_cli for F4 targets.
This commit is contained in:
parent
236fb5598a
commit
9c303d6669
14 changed files with 82 additions and 65 deletions
|
@ -61,7 +61,7 @@ uint32_t serialRxBytesWaiting(serialPort_t *instance)
|
|||
return instance->vTable->serialTotalRxWaiting(instance);
|
||||
}
|
||||
|
||||
uint8_t serialTxBytesFree(serialPort_t *instance)
|
||||
uint32_t serialTxBytesFree(serialPort_t *instance)
|
||||
{
|
||||
return instance->vTable->serialTotalTxFree(instance);
|
||||
}
|
||||
|
|
|
@ -63,7 +63,7 @@ struct serialPortVTable {
|
|||
void (*serialWrite)(serialPort_t *instance, uint8_t ch);
|
||||
|
||||
uint32_t (*serialTotalRxWaiting)(serialPort_t *instance);
|
||||
uint8_t (*serialTotalTxFree)(serialPort_t *instance);
|
||||
uint32_t (*serialTotalTxFree)(serialPort_t *instance);
|
||||
|
||||
uint8_t (*serialRead)(serialPort_t *instance);
|
||||
|
||||
|
@ -82,7 +82,7 @@ struct serialPortVTable {
|
|||
|
||||
void serialWrite(serialPort_t *instance, uint8_t ch);
|
||||
uint32_t serialRxBytesWaiting(serialPort_t *instance);
|
||||
uint8_t serialTxBytesFree(serialPort_t *instance);
|
||||
uint32_t serialTxBytesFree(serialPort_t *instance);
|
||||
void serialWriteBuf(serialPort_t *instance, uint8_t *data, int count);
|
||||
uint8_t serialRead(serialPort_t *instance);
|
||||
void serialSetBaudRate(serialPort_t *instance, uint32_t baudRate);
|
||||
|
|
|
@ -412,7 +412,7 @@ uint32_t softSerialRxBytesWaiting(serialPort_t *instance)
|
|||
return (s->port.rxBufferHead - s->port.rxBufferTail) & (s->port.rxBufferSize - 1);
|
||||
}
|
||||
|
||||
uint8_t softSerialTxBytesFree(serialPort_t *instance)
|
||||
uint32_t softSerialTxBytesFree(serialPort_t *instance)
|
||||
{
|
||||
if ((instance->mode & MODE_TX) == 0) {
|
||||
return 0;
|
||||
|
|
|
@ -29,7 +29,7 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
|
|||
// serialPort API
|
||||
void softSerialWriteByte(serialPort_t *instance, uint8_t ch);
|
||||
uint32_t softSerialRxBytesWaiting(serialPort_t *instance);
|
||||
uint8_t softSerialTxBytesFree(serialPort_t *instance);
|
||||
uint32_t softSerialTxBytesFree(serialPort_t *instance);
|
||||
uint8_t softSerialReadByte(serialPort_t *instance);
|
||||
void softSerialSetBaudRate(serialPort_t *s, uint32_t baudRate);
|
||||
bool isSoftSerialTransmitBufferEmpty(serialPort_t *s);
|
||||
|
|
|
@ -315,7 +315,7 @@ uint32_t uartTotalRxBytesWaiting(serialPort_t *instance)
|
|||
}
|
||||
}
|
||||
|
||||
uint8_t uartTotalTxBytesFree(serialPort_t *instance)
|
||||
uint32_t uartTotalTxBytesFree(serialPort_t *instance)
|
||||
{
|
||||
uartPort_t *s = (uartPort_t*)instance;
|
||||
|
||||
|
|
|
@ -66,7 +66,7 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
|
|||
// serialPort API
|
||||
void uartWrite(serialPort_t *instance, uint8_t ch);
|
||||
uint32_t uartTotalRxBytesWaiting(serialPort_t *instance);
|
||||
uint8_t uartTotalTxBytesFree(serialPort_t *instance);
|
||||
uint32_t uartTotalTxBytesFree(serialPort_t *instance);
|
||||
uint8_t uartRead(serialPort_t *instance);
|
||||
void uartSetBaudRate(serialPort_t *s, uint32_t baudRate);
|
||||
bool isUartTransmitBufferEmpty(serialPort_t *s);
|
||||
|
|
|
@ -69,7 +69,7 @@ static uint32_t usbVcpAvailable(serialPort_t *instance)
|
|||
{
|
||||
UNUSED(instance);
|
||||
|
||||
return receiveLength;
|
||||
return CDC_Receive_BytesAvailable();
|
||||
}
|
||||
|
||||
static uint8_t usbVcpRead(serialPort_t *instance)
|
||||
|
@ -150,10 +150,9 @@ static void usbVcpBeginWrite(serialPort_t *instance)
|
|||
port->buffering = true;
|
||||
}
|
||||
|
||||
uint8_t usbTxBytesFree()
|
||||
uint32_t usbTxBytesFree()
|
||||
{
|
||||
// Because we block upon transmit and don't buffer bytes, our "buffer" capacity is effectively unlimited.
|
||||
return 255;
|
||||
return CDC_Send_FreeBytes();
|
||||
}
|
||||
|
||||
static void usbVcpEndWrite(serialPort_t *instance)
|
||||
|
|
|
@ -2952,12 +2952,9 @@ static void cliDefaults(char *cmdline)
|
|||
|
||||
static void cliPrint(const char *str)
|
||||
{
|
||||
while (*str)
|
||||
while (*str) {
|
||||
bufWriterAppend(cliWriter, *str++);
|
||||
|
||||
#ifdef USE_SLOW_SERIAL_CLI
|
||||
delay(1);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
static void cliPutp(void *p, char ch)
|
||||
|
@ -2979,10 +2976,6 @@ static bool cliDumpPrintf(uint8_t dumpMask, bool equalsDefault, const char *form
|
|||
tfp_format(cliWriter, cliPutp, format, va);
|
||||
va_end(va);
|
||||
|
||||
#ifdef USE_SLOW_SERIAL_CLI
|
||||
delay(1);
|
||||
#endif
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -2995,10 +2988,6 @@ static void cliPrintf(const char *fmt, ...)
|
|||
va_start(va, fmt);
|
||||
tfp_format(cliWriter, cliPutp, fmt, va);
|
||||
va_end(va);
|
||||
|
||||
#ifdef USE_SLOW_SERIAL_CLI
|
||||
delay(1);
|
||||
#endif
|
||||
}
|
||||
|
||||
static void cliWrite(uint8_t ch)
|
||||
|
|
|
@ -27,7 +27,6 @@
|
|||
#define MAX_AUX_CHANNELS 99
|
||||
#define TASK_GYROPID_DESIRED_PERIOD 125
|
||||
#define SCHEDULER_DELAY_LIMIT 10
|
||||
#define USE_SLOW_SERIAL_CLI
|
||||
#define I2C3_OVERCLOCK true
|
||||
|
||||
#else /* when not an F4 */
|
||||
|
|
|
@ -305,6 +305,12 @@ uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength)
|
|||
return sendLength;
|
||||
}
|
||||
|
||||
uint32_t CDC_Send_FreeBytes(void)
|
||||
{
|
||||
/* this driver is blocking, so the buffer is unlimited */
|
||||
return 255;
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : Receive DATA .
|
||||
* Description : receive the data from the PC to STM32 and send it through USB
|
||||
|
@ -338,6 +344,11 @@ uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len)
|
|||
return len;
|
||||
}
|
||||
|
||||
uint32_t CDC_Receive_BytesAvailable(void)
|
||||
{
|
||||
return receiveLength;
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : usbIsConfigured.
|
||||
* Description : Determines if USB VCP is configured or not
|
||||
|
|
|
@ -56,13 +56,15 @@ void USB_Interrupts_Config(void);
|
|||
void USB_Cable_Config(FunctionalState NewState);
|
||||
void Get_SerialNum(void);
|
||||
uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength); // HJI
|
||||
uint32_t CDC_Send_FreeBytes(void);
|
||||
uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len); // HJI
|
||||
uint32_t CDC_Receive_BytesAvailable(void);
|
||||
|
||||
uint8_t usbIsConfigured(void); // HJI
|
||||
uint8_t usbIsConnected(void); // HJI
|
||||
uint32_t CDC_BaudRate(void);
|
||||
/* External variables --------------------------------------------------------*/
|
||||
|
||||
extern __IO uint32_t receiveLength; // HJI
|
||||
/* External variables --------------------------------------------------------*/
|
||||
extern __IO uint32_t packetSent; // HJI
|
||||
|
||||
#endif /*__HW_CONFIG_H*/
|
||||
|
|
|
@ -39,12 +39,10 @@ __IO uint32_t bDeviceState = UNCONNECTED; /* USB device status */
|
|||
/* This is the buffer for data received from the MCU to APP (i.e. MCU TX, APP RX) */
|
||||
extern uint8_t APP_Rx_Buffer[];
|
||||
extern uint32_t APP_Rx_ptr_out;
|
||||
|
||||
/* Increment this buffer position or roll it back to
|
||||
start address when writing received data
|
||||
in the buffer APP_Rx_Buffer. */
|
||||
extern uint32_t APP_Rx_ptr_in;
|
||||
__IO uint32_t receiveLength = 0;
|
||||
|
||||
/*
|
||||
APP TX is the circular buffer for data that is transmitted from the APP (host)
|
||||
|
@ -155,7 +153,7 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len)
|
|||
/*******************************************************************************
|
||||
* Function Name : Send DATA .
|
||||
* Description : send the data received from the STM32 to the PC through USB
|
||||
* Input : None.
|
||||
* Input : buffer to send, and the length of the buffer.
|
||||
* Output : None.
|
||||
* Return : None.
|
||||
*******************************************************************************/
|
||||
|
@ -165,10 +163,15 @@ uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength)
|
|||
return sendLength;
|
||||
}
|
||||
|
||||
uint32_t CDC_Send_FreeBytes(void)
|
||||
{
|
||||
/* return the bytes free in the circular buffer */
|
||||
return ((APP_Rx_ptr_out - APP_Rx_ptr_in) + (-((int)(APP_Rx_ptr_out <= APP_Rx_ptr_in)) & APP_RX_DATA_SIZE)) - 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief VCP_DataTx
|
||||
* CDC received data to be send over USB IN endpoint are managed in
|
||||
* this function.
|
||||
* CDC data to be sent to the Host (app) over USB
|
||||
* @param Buf: Buffer of data to be sent
|
||||
* @param Len: Number of data to be sent (in bytes)
|
||||
* @retval Result of the operation: USBD_OK if all operations are OK else VCP_FAIL
|
||||
|
@ -185,6 +188,8 @@ static uint16_t VCP_DataTx(uint8_t* Buf, uint32_t Len)
|
|||
for (uint32_t i = 0; i < Len; i++) {
|
||||
APP_Rx_Buffer[APP_Rx_ptr_in] = Buf[i];
|
||||
APP_Rx_ptr_in = (APP_Rx_ptr_in + 1) % APP_RX_DATA_SIZE;
|
||||
|
||||
while (!CDC_Send_FreeBytes());
|
||||
}
|
||||
|
||||
return USBD_OK;
|
||||
|
@ -205,16 +210,16 @@ uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len)
|
|||
recvBuf[count] = APP_Tx_Buffer[APP_Tx_ptr_out];
|
||||
APP_Tx_ptr_out = (APP_Tx_ptr_out + 1) % APP_TX_DATA_SIZE;
|
||||
count++;
|
||||
receiveLength--;
|
||||
}
|
||||
|
||||
if (!receiveLength) {
|
||||
receiveLength = APP_Tx_ptr_out != APP_Tx_ptr_in;
|
||||
}
|
||||
|
||||
return count;
|
||||
}
|
||||
|
||||
uint32_t CDC_Receive_BytesAvailable(void)
|
||||
{
|
||||
/* return the bytes available in the receive circular buffer */
|
||||
return APP_Tx_ptr_out > APP_Tx_ptr_in ? APP_TX_DATA_SIZE - APP_Tx_ptr_out + APP_Tx_ptr_in : APP_Tx_ptr_in - APP_Tx_ptr_out;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief VCP_DataRx
|
||||
* Data received over USB OUT endpoint are sent over CDC interface
|
||||
|
@ -232,9 +237,12 @@ uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len)
|
|||
*/
|
||||
static uint16_t VCP_DataRx(uint8_t* Buf, uint32_t Len)
|
||||
{
|
||||
if (CDC_Receive_BytesAvailable() + Len > APP_TX_DATA_SIZE) {
|
||||
return USBD_FAIL;
|
||||
}
|
||||
|
||||
__disable_irq();
|
||||
|
||||
receiveLength += Len;
|
||||
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;
|
||||
|
@ -242,9 +250,6 @@ static uint16_t VCP_DataRx(uint8_t* Buf, uint32_t Len)
|
|||
|
||||
__enable_irq();
|
||||
|
||||
if(receiveLength > APP_TX_DATA_SIZE)
|
||||
return USBD_FAIL;
|
||||
|
||||
return USBD_OK;
|
||||
}
|
||||
|
||||
|
|
|
@ -37,14 +37,15 @@
|
|||
__ALIGN_BEGIN USB_OTG_CORE_HANDLE USB_OTG_dev __ALIGN_END;
|
||||
|
||||
uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength); // HJI
|
||||
uint32_t CDC_Send_FreeBytes(void);
|
||||
uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len); // HJI
|
||||
uint32_t CDC_Receive_BytesAvailable(void);
|
||||
|
||||
uint8_t usbIsConfigured(void); // HJI
|
||||
uint8_t usbIsConnected(void); // HJI
|
||||
uint32_t CDC_BaudRate(void);
|
||||
|
||||
/* External variables --------------------------------------------------------*/
|
||||
|
||||
extern __IO uint32_t receiveLength; // HJI
|
||||
extern __IO uint32_t bDeviceState; /* USB device status */
|
||||
|
||||
typedef enum _DEVICE_STATE {
|
||||
|
|
|
@ -177,33 +177,38 @@ uint32_t millis(void) {
|
|||
|
||||
uint32_t micros(void) { return 0; }
|
||||
|
||||
uint8_t serialRxBytesWaiting(serialPort_t *instance) {
|
||||
uint32_t serialRxBytesWaiting(serialPort_t *instance)
|
||||
{
|
||||
UNUSED(instance);
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint8_t serialTxBytesFree(serialPort_t *instance) {
|
||||
uint32_t serialTxBytesFree(serialPort_t *instance)
|
||||
{
|
||||
UNUSED(instance);
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint8_t serialRead(serialPort_t *instance) {
|
||||
uint8_t serialRead(serialPort_t *instance)
|
||||
{
|
||||
UNUSED(instance);
|
||||
return 0;
|
||||
}
|
||||
|
||||
void serialWrite(serialPort_t *instance, uint8_t ch) {
|
||||
void serialWrite(serialPort_t *instance, uint8_t ch)
|
||||
{
|
||||
UNUSED(instance);
|
||||
UNUSED(ch);
|
||||
}
|
||||
|
||||
void serialSetMode(serialPort_t *instance, portMode_t mode) {
|
||||
void serialSetMode(serialPort_t *instance, portMode_t mode)
|
||||
{
|
||||
UNUSED(instance);
|
||||
UNUSED(mode);
|
||||
}
|
||||
|
||||
|
||||
serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, portOptions_t options) {
|
||||
serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
UNUSED(identifier);
|
||||
UNUSED(functionMask);
|
||||
UNUSED(baudRate);
|
||||
|
@ -214,30 +219,36 @@ serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFuncti
|
|||
return NULL;
|
||||
}
|
||||
|
||||
void closeSerialPort(serialPort_t *serialPort) {
|
||||
void closeSerialPort(serialPort_t *serialPort)
|
||||
{
|
||||
UNUSED(serialPort);
|
||||
}
|
||||
|
||||
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function) {
|
||||
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
|
||||
{
|
||||
UNUSED(function);
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
||||
bool sensors(uint32_t mask) {
|
||||
bool sensors(uint32_t mask)
|
||||
{
|
||||
UNUSED(mask);
|
||||
return false;
|
||||
}
|
||||
|
||||
bool telemetryDetermineEnabledState(portSharing_e) {
|
||||
bool telemetryDetermineEnabledState(portSharing_e)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
portSharing_e determinePortSharing(serialPortConfig_t *, serialPortFunction_e) {
|
||||
portSharing_e determinePortSharing(serialPortConfig_t *, serialPortFunction_e)
|
||||
{
|
||||
return PORTSHARING_NOT_SHARED;
|
||||
}
|
||||
|
||||
batteryState_e getBatteryState(void) {
|
||||
batteryState_e getBatteryState(void)
|
||||
{
|
||||
return BATTERY_OK;
|
||||
}
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue