1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-20 23:05:19 +03:00

Make VTable functions static

jetiexbus.c: Use serialRxBytesWaiting instead of uartTotalRxBytesWaiting
This commit is contained in:
jflyper 2017-12-27 22:02:32 +09:00
parent 2207a98a7a
commit 18c29a2b6e
3 changed files with 8 additions and 16 deletions

View file

@ -41,14 +41,14 @@
#include "drivers/serial_uart.h" #include "drivers/serial_uart.h"
#include "drivers/serial_uart_impl.h" #include "drivers/serial_uart_impl.h"
void uartSetBaudRate(serialPort_t *instance, uint32_t baudRate) static void uartSetBaudRate(serialPort_t *instance, uint32_t baudRate)
{ {
uartPort_t *uartPort = (uartPort_t *)instance; uartPort_t *uartPort = (uartPort_t *)instance;
uartPort->port.baudRate = baudRate; uartPort->port.baudRate = baudRate;
uartReconfigure(uartPort); uartReconfigure(uartPort);
} }
void uartSetMode(serialPort_t *instance, portMode_e mode) static void uartSetMode(serialPort_t *instance, portMode_e mode)
{ {
uartPort_t *uartPort = (uartPort_t *)instance; uartPort_t *uartPort = (uartPort_t *)instance;
uartPort->port.mode = mode; uartPort->port.mode = mode;
@ -138,7 +138,7 @@ void uartTryStartTxDMA(uartPort_t *s)
} }
} }
uint32_t uartTotalRxBytesWaiting(const serialPort_t *instance) static uint32_t uartTotalRxBytesWaiting(const serialPort_t *instance)
{ {
const uartPort_t *s = (const uartPort_t*)instance; const uartPort_t *s = (const uartPort_t*)instance;
#ifdef STM32F4 #ifdef STM32F4
@ -162,7 +162,7 @@ uint32_t uartTotalRxBytesWaiting(const serialPort_t *instance)
} }
} }
uint32_t uartTotalTxBytesFree(const serialPort_t *instance) static uint32_t uartTotalTxBytesFree(const serialPort_t *instance)
{ {
const uartPort_t *s = (const uartPort_t*)instance; const uartPort_t *s = (const uartPort_t*)instance;
@ -205,7 +205,7 @@ uint32_t uartTotalTxBytesFree(const serialPort_t *instance)
return (s->port.txBufferSize - 1) - bytesUsed; return (s->port.txBufferSize - 1) - bytesUsed;
} }
bool isUartTransmitBufferEmpty(const serialPort_t *instance) static bool isUartTransmitBufferEmpty(const serialPort_t *instance)
{ {
const uartPort_t *s = (const uartPort_t *)instance; const uartPort_t *s = (const uartPort_t *)instance;
#ifdef STM32F4 #ifdef STM32F4
@ -218,7 +218,7 @@ bool isUartTransmitBufferEmpty(const serialPort_t *instance)
return s->port.txBufferTail == s->port.txBufferHead; return s->port.txBufferTail == s->port.txBufferHead;
} }
uint8_t uartRead(serialPort_t *instance) static uint8_t uartRead(serialPort_t *instance)
{ {
uint8_t ch; uint8_t ch;
uartPort_t *s = (uartPort_t *)instance; uartPort_t *s = (uartPort_t *)instance;
@ -243,7 +243,7 @@ uint8_t uartRead(serialPort_t *instance)
return ch; return ch;
} }
void uartWrite(serialPort_t *instance, uint8_t ch) static void uartWrite(serialPort_t *instance, uint8_t ch)
{ {
uartPort_t *s = (uartPort_t *)instance; uartPort_t *s = (uartPort_t *)instance;
s->port.txBuffer[s->port.txBufferHead] = ch; s->port.txBuffer[s->port.txBufferHead] = ch;

View file

@ -73,11 +73,3 @@ typedef struct uartPort_s {
void uartPinConfigure(const serialPinConfig_t *pSerialPinConfig); void uartPinConfigure(const serialPinConfig_t *pSerialPinConfig);
serialPort_t *uartOpen(UARTDevice_e device, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_e mode, portOptions_e options); serialPort_t *uartOpen(UARTDevice_e device, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_e mode, portOptions_e options);
// serialPort API
void uartWrite(serialPort_t *instance, uint8_t ch);
uint32_t uartTotalRxBytesWaiting(const serialPort_t *instance);
uint32_t uartTotalTxBytesFree(const serialPort_t *instance);
uint8_t uartRead(serialPort_t *instance);
void uartSetBaudRate(serialPort_t *s, uint32_t baudRate);
bool isUartTransmitBufferEmpty(const serialPort_t *s);

View file

@ -277,7 +277,7 @@ void handleJetiExBusTelemetry(void)
jetiExSensors[EX_TIME_DIFF].value = timeDiff; jetiExSensors[EX_TIME_DIFF].value = timeDiff;
// switch to TX mode // switch to TX mode
if (uartTotalRxBytesWaiting(jetiExBusPort) == 0) { if (serialRxBytesWaiting(jetiExBusPort) == 0) {
serialSetMode(jetiExBusPort, MODE_TX); serialSetMode(jetiExBusPort, MODE_TX);
jetiExBusTransceiveState = EXBUS_TRANS_TX; jetiExBusTransceiveState = EXBUS_TRANS_TX;
sendJetiExBusTelemetry(jetiExBusRequestFrame[EXBUS_HEADER_PACKET_ID]); sendJetiExBusTelemetry(jetiExBusRequestFrame[EXBUS_HEADER_PACKET_ID]);