Ability to see how many Tx bytes are free in serial port buffer
This commit is contained in:
parent
d0b940bf75
commit
6e504ca52a
|
@ -40,9 +40,14 @@ void serialWrite(serialPort_t *instance, uint8_t ch)
|
|||
instance->vTable->serialWrite(instance, ch);
|
||||
}
|
||||
|
||||
uint8_t serialTotalBytesWaiting(serialPort_t *instance)
|
||||
uint8_t serialRxBytesWaiting(serialPort_t *instance)
|
||||
{
|
||||
return instance->vTable->serialTotalBytesWaiting(instance);
|
||||
return instance->vTable->serialTotalRxWaiting(instance);
|
||||
}
|
||||
|
||||
uint8_t serialTxBytesFree(serialPort_t *instance)
|
||||
{
|
||||
return instance->vTable->serialTotalTxFree(instance);
|
||||
}
|
||||
|
||||
uint8_t serialRead(serialPort_t *instance)
|
||||
|
|
|
@ -62,7 +62,8 @@ typedef struct serialPort {
|
|||
struct serialPortVTable {
|
||||
void (*serialWrite)(serialPort_t *instance, uint8_t ch);
|
||||
|
||||
uint8_t (*serialTotalBytesWaiting)(serialPort_t *instance);
|
||||
uint8_t (*serialTotalRxWaiting)(serialPort_t *instance);
|
||||
uint8_t (*serialTotalTxFree)(serialPort_t *instance);
|
||||
|
||||
uint8_t (*serialRead)(serialPort_t *instance);
|
||||
|
||||
|
@ -75,7 +76,8 @@ struct serialPortVTable {
|
|||
};
|
||||
|
||||
void serialWrite(serialPort_t *instance, uint8_t ch);
|
||||
uint8_t serialTotalBytesWaiting(serialPort_t *instance);
|
||||
uint8_t serialRxBytesWaiting(serialPort_t *instance);
|
||||
uint8_t serialTxBytesFree(serialPort_t *instance);
|
||||
uint8_t serialRead(serialPort_t *instance);
|
||||
void serialSetBaudRate(serialPort_t *instance, uint32_t baudRate);
|
||||
void serialSetMode(serialPort_t *instance, portMode_t mode);
|
||||
|
|
|
@ -403,7 +403,7 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture)
|
|||
}
|
||||
}
|
||||
|
||||
uint8_t softSerialTotalBytesWaiting(serialPort_t *instance)
|
||||
uint8_t softSerialRxBytesWaiting(serialPort_t *instance)
|
||||
{
|
||||
if ((instance->mode & MODE_RX) == 0) {
|
||||
return 0;
|
||||
|
@ -414,6 +414,19 @@ uint8_t softSerialTotalBytesWaiting(serialPort_t *instance)
|
|||
return (s->port.rxBufferHead - s->port.rxBufferTail) & (s->port.rxBufferSize - 1);
|
||||
}
|
||||
|
||||
uint8_t softSerialTxBytesFree(serialPort_t *instance)
|
||||
{
|
||||
if ((instance->mode & MODE_TX) == 0) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
softSerial_t *s = (softSerial_t *)instance;
|
||||
|
||||
uint8_t bytesUsed = (s->port.txBufferHead - s->port.txBufferTail) & (s->port.txBufferSize - 1);
|
||||
|
||||
return (s->port.txBufferSize - 1) - bytesUsed;
|
||||
}
|
||||
|
||||
uint8_t softSerialReadByte(serialPort_t *instance)
|
||||
{
|
||||
uint8_t ch;
|
||||
|
@ -422,7 +435,7 @@ uint8_t softSerialReadByte(serialPort_t *instance)
|
|||
return 0;
|
||||
}
|
||||
|
||||
if (softSerialTotalBytesWaiting(instance) == 0) {
|
||||
if (softSerialRxBytesWaiting(instance) == 0) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -460,7 +473,8 @@ bool isSoftSerialTransmitBufferEmpty(serialPort_t *instance)
|
|||
const struct serialPortVTable softSerialVTable[] = {
|
||||
{
|
||||
softSerialWriteByte,
|
||||
softSerialTotalBytesWaiting,
|
||||
softSerialRxBytesWaiting,
|
||||
softSerialTxBytesFree,
|
||||
softSerialReadByte,
|
||||
softSerialSetBaudRate,
|
||||
isSoftSerialTransmitBufferEmpty,
|
||||
|
|
|
@ -28,7 +28,8 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
|
|||
|
||||
// serialPort API
|
||||
void softSerialWriteByte(serialPort_t *instance, uint8_t ch);
|
||||
uint8_t softSerialTotalBytesWaiting(serialPort_t *instance);
|
||||
uint8_t softSerialRxBytesWaiting(serialPort_t *instance);
|
||||
uint8_t softSerialTxBytesFree(serialPort_t *instance);
|
||||
uint8_t softSerialReadByte(serialPort_t *instance);
|
||||
void softSerialSetBaudRate(serialPort_t *s, uint32_t baudRate);
|
||||
bool isSoftSerialTransmitBufferEmpty(serialPort_t *s);
|
||||
|
|
|
@ -211,7 +211,7 @@ void uartStartTxDMA(uartPort_t *s)
|
|||
DMA_Cmd(s->txDMAChannel, ENABLE);
|
||||
}
|
||||
|
||||
uint8_t uartTotalBytesWaiting(serialPort_t *instance)
|
||||
uint8_t uartTotalRxBytesWaiting(serialPort_t *instance)
|
||||
{
|
||||
uartPort_t *s = (uartPort_t*)instance;
|
||||
if (s->rxDMAChannel) {
|
||||
|
@ -230,6 +230,41 @@ uint8_t uartTotalBytesWaiting(serialPort_t *instance)
|
|||
}
|
||||
}
|
||||
|
||||
uint8_t uartTotalTxBytesFree(serialPort_t *instance)
|
||||
{
|
||||
uartPort_t *s = (uartPort_t*)instance;
|
||||
|
||||
uint32_t bytesUsed;
|
||||
|
||||
if (s->port.txBufferHead >= s->port.txBufferTail) {
|
||||
bytesUsed = s->port.txBufferHead - s->port.txBufferTail;
|
||||
} else {
|
||||
bytesUsed = s->port.txBufferSize + s->port.txBufferHead - s->port.txBufferTail;
|
||||
}
|
||||
|
||||
if (s->txDMAChannel) {
|
||||
/*
|
||||
* When we queue up a DMA request, we advance the Tx buffer tail before the transfer finishes, so we must add
|
||||
* the remaining size of that in-progress transfer here instead:
|
||||
*/
|
||||
bytesUsed += s->txDMAChannel->CNDTR;
|
||||
|
||||
/*
|
||||
* If the Tx buffer is being written to very quickly, we might have advanced the head into the buffer
|
||||
* space occupied by the current DMA transfer. In that case the "bytesUsed" total will actually end up larger
|
||||
* than the total Tx buffer size, because we'll end up transmitting the same buffer region twice. (So we'll be
|
||||
* transmitting a garbage mixture of old and new bytes).
|
||||
*
|
||||
* Be kind to callers and pretend like our buffer can only ever be 100% full.
|
||||
*/
|
||||
if (bytesUsed >= s->port.txBufferSize - 1) {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
return (s->port.txBufferSize - 1) - bytesUsed;
|
||||
}
|
||||
|
||||
bool isUartTransmitBufferEmpty(serialPort_t *instance)
|
||||
{
|
||||
uartPort_t *s = (uartPort_t *)instance;
|
||||
|
@ -281,7 +316,8 @@ void uartWrite(serialPort_t *instance, uint8_t ch)
|
|||
const struct serialPortVTable uartVTable[] = {
|
||||
{
|
||||
uartWrite,
|
||||
uartTotalBytesWaiting,
|
||||
uartTotalRxBytesWaiting,
|
||||
uartTotalTxBytesFree,
|
||||
uartRead,
|
||||
uartSetBaudRate,
|
||||
isUartTransmitBufferEmpty,
|
||||
|
|
|
@ -19,6 +19,10 @@
|
|||
|
||||
// Since serial ports can be used for any function these buffer sizes should be equal
|
||||
// The two largest things that need to be sent are: 1, MSP responses, 2, UBLOX SVINFO packet.
|
||||
|
||||
// Size must be a power of two due to various optimizations which use 'and' instead of 'mod'
|
||||
// Various serial routines return the buffer occupied size as uint8_t which would need to be extended in order to
|
||||
// increase size further.
|
||||
#define UART1_RX_BUFFER_SIZE 256
|
||||
#define UART1_TX_BUFFER_SIZE 256
|
||||
#define UART2_RX_BUFFER_SIZE 256
|
||||
|
@ -48,7 +52,8 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
|
|||
|
||||
// serialPort API
|
||||
void uartWrite(serialPort_t *instance, uint8_t ch);
|
||||
uint8_t uartTotalBytesWaiting(serialPort_t *instance);
|
||||
uint8_t uartTotalRxBytesWaiting(serialPort_t *instance);
|
||||
uint8_t uartTotalTxBytesFree(serialPort_t *instance);
|
||||
uint8_t uartRead(serialPort_t *instance);
|
||||
void uartSetBaudRate(serialPort_t *s, uint32_t baudRate);
|
||||
bool isUartTransmitBufferEmpty(serialPort_t *s);
|
||||
|
|
|
@ -360,7 +360,7 @@ void gpsThread(void)
|
|||
{
|
||||
// read out available GPS bytes
|
||||
if (gpsPort) {
|
||||
while (serialTotalBytesWaiting(gpsPort))
|
||||
while (serialRxBytesWaiting(gpsPort))
|
||||
gpsNewData(serialRead(gpsPort));
|
||||
}
|
||||
|
||||
|
@ -1036,14 +1036,14 @@ void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort)
|
|||
#endif
|
||||
char c;
|
||||
while(1) {
|
||||
if (serialTotalBytesWaiting(gpsPort)) {
|
||||
if (serialRxBytesWaiting(gpsPort)) {
|
||||
LED0_ON;
|
||||
c = serialRead(gpsPort);
|
||||
gpsNewData(c);
|
||||
serialWrite(gpsPassthroughPort, c);
|
||||
LED0_OFF;
|
||||
}
|
||||
if (serialTotalBytesWaiting(gpsPassthroughPort)) {
|
||||
if (serialRxBytesWaiting(gpsPassthroughPort)) {
|
||||
LED1_ON;
|
||||
serialWrite(gpsPort, serialRead(gpsPassthroughPort));
|
||||
LED1_OFF;
|
||||
|
|
|
@ -2141,7 +2141,7 @@ void cliProcess(void)
|
|||
return;
|
||||
}
|
||||
|
||||
while (serialTotalBytesWaiting(cliPort)) {
|
||||
while (serialRxBytesWaiting(cliPort)) {
|
||||
uint8_t c = serialRead(cliPort);
|
||||
if (c == '\t' || c == '?') {
|
||||
// do tab completion
|
||||
|
|
|
@ -1807,7 +1807,7 @@ void mspProcess(void)
|
|||
|
||||
setCurrentPort(candidatePort);
|
||||
|
||||
while (serialTotalBytesWaiting(mspSerialPort)) {
|
||||
while (serialRxBytesWaiting(mspSerialPort)) {
|
||||
|
||||
uint8_t c = serialRead(mspSerialPort);
|
||||
bool consumed = mspProcessReceivedData(c);
|
||||
|
|
|
@ -514,7 +514,7 @@ void init(void)
|
|||
void processLoopback(void) {
|
||||
if (loopbackPort) {
|
||||
uint8_t bytesWaiting;
|
||||
while ((bytesWaiting = serialTotalBytesWaiting(loopbackPort))) {
|
||||
while ((bytesWaiting = serialRxBytesWaiting(loopbackPort))) {
|
||||
uint8_t b = serialRead(loopbackPort);
|
||||
serialWrite(loopbackPort, b);
|
||||
};
|
||||
|
|
|
@ -374,7 +374,7 @@ static void processBinaryModeRequest(uint8_t address) {
|
|||
|
||||
static void flushHottRxBuffer(void)
|
||||
{
|
||||
while (serialTotalBytesWaiting(hottPort) > 0) {
|
||||
while (serialRxBytesWaiting(hottPort) > 0) {
|
||||
serialRead(hottPort);
|
||||
}
|
||||
}
|
||||
|
@ -383,7 +383,7 @@ static void hottCheckSerialData(uint32_t currentMicros)
|
|||
{
|
||||
static bool lookingForRequest = true;
|
||||
|
||||
uint8_t bytesWaiting = serialTotalBytesWaiting(hottPort);
|
||||
uint8_t bytesWaiting = serialRxBytesWaiting(hottPort);
|
||||
|
||||
if (bytesWaiting <= 1) {
|
||||
return;
|
||||
|
|
|
@ -160,7 +160,7 @@ static void smartPortDataReceive(uint16_t c)
|
|||
static uint8_t lastChar;
|
||||
if (lastChar == FSSP_START_STOP) {
|
||||
smartPortState = SPSTATE_WORKING;
|
||||
if (c == FSSP_SENSOR_ID1 && (serialTotalBytesWaiting(smartPortSerialPort) == 0)) {
|
||||
if (c == FSSP_SENSOR_ID1 && (serialRxBytesWaiting(smartPortSerialPort) == 0)) {
|
||||
smartPortLastRequestTime = now;
|
||||
smartPortHasRequest = 1;
|
||||
// we only responde to these IDs
|
||||
|
@ -282,7 +282,7 @@ void handleSmartPortTelemetry(void)
|
|||
return;
|
||||
}
|
||||
|
||||
while (serialTotalBytesWaiting(smartPortSerialPort) > 0) {
|
||||
while (serialRxBytesWaiting(smartPortSerialPort) > 0) {
|
||||
uint8_t c = serialRead(smartPortSerialPort);
|
||||
smartPortDataReceive(c);
|
||||
}
|
||||
|
|
|
@ -177,7 +177,12 @@ uint32_t millis(void) {
|
|||
|
||||
uint32_t micros(void) { return 0; }
|
||||
|
||||
uint8_t serialTotalBytesWaiting(serialPort_t *instance) {
|
||||
uint8_t serialRxBytesWaiting(serialPort_t *instance) {
|
||||
UNUSED(instance);
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint8_t serialTxBytesFree(serialPort_t *instance) {
|
||||
UNUSED(instance);
|
||||
return 0;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue