Replacing calls to isUartTransmitEmpty with isSoftSerialTransmitBufferEmpty. Replacing remaing calls to uartWrite with serialWrite. Adding isSoftSerialTransmitBufferEmpty to the serial API. Adding serialSet/GetBaudRate to the serial API. Since softSerial does not implement serialSetBaudRate some GPS serial initialisation code has been updated.
At this point it is probably possible to switch around all the ports and use a software serial implementation if desired.
This commit is contained in:
parent
2ff881aa69
commit
b92c3fa192
|
@ -8,3 +8,8 @@ void serialPrint(serialPort_t *instance, const char *str)
|
|||
serialWrite(instance, ch);
|
||||
}
|
||||
}
|
||||
|
||||
inline uint32_t serialGetBaudRate(serialPort_t *instance)
|
||||
{
|
||||
return instance->baudRate;
|
||||
}
|
|
@ -28,8 +28,15 @@ typedef struct serialPort {
|
|||
|
||||
struct serialPortVTable {
|
||||
void (*serialWrite)(serialPort_t *instance, uint8_t ch);
|
||||
|
||||
uint8_t (*serialTotalBytesWaiting)(serialPort_t *instance);
|
||||
|
||||
uint8_t (*serialRead)(serialPort_t *instance);
|
||||
|
||||
// Specified baud rate may not be allowed by an implementation, use serialGetBaudRate to determine actual baud rate in use.
|
||||
void (*serialSetBaudRate)(serialPort_t *instance, uint32_t baudRate);
|
||||
|
||||
bool (*isSerialTransmitBufferEmpty)(serialPort_t *instance);
|
||||
};
|
||||
|
||||
static inline void serialWrite(serialPort_t *instance, uint8_t ch)
|
||||
|
@ -47,4 +54,16 @@ static inline uint8_t serialRead(serialPort_t *instance)
|
|||
return instance->vTable->serialRead(instance);
|
||||
}
|
||||
|
||||
static inline void serialSetBaudRate(serialPort_t *instance, uint32_t baudRate)
|
||||
{
|
||||
instance->vTable->serialSetBaudRate(instance, baudRate);
|
||||
}
|
||||
|
||||
static inline bool isSerialTransmitBufferEmpty(serialPort_t *instance)
|
||||
{
|
||||
return instance->vTable->isSerialTransmitBufferEmpty(instance);
|
||||
}
|
||||
|
||||
void serialPrint(serialPort_t *instance, const char *str);
|
||||
uint32_t serialGetBaudRate(serialPort_t *instance);
|
||||
|
||||
|
|
|
@ -212,7 +212,7 @@ void processTxState(softSerial_t *softSerial)
|
|||
|
||||
if (!softSerial->isTransmittingData) {
|
||||
|
||||
if (softSerial->port.txBufferHead == softSerial->port.txBufferTail) {
|
||||
if (isSoftSerialTransmitBufferEmpty((serialPort_t *)softSerial)) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -299,10 +299,24 @@ void softSerialWriteByte(serialPort_t *s, uint8_t ch)
|
|||
|
||||
}
|
||||
|
||||
void softSerialSetBaudRate(serialPort_t *s, uint32_t baudRate)
|
||||
{
|
||||
// not implemented.
|
||||
}
|
||||
|
||||
bool isSoftSerialTransmitBufferEmpty(serialPort_t *instance)
|
||||
{
|
||||
return instance->txBufferHead == instance->txBufferTail;
|
||||
}
|
||||
|
||||
|
||||
const struct serialPortVTable softSerialVTable[] = {
|
||||
{
|
||||
softSerialWriteByte,
|
||||
softSerialTotalBytesWaiting,
|
||||
softSerialReadByte
|
||||
softSerialReadByte,
|
||||
softSerialSetBaudRate,
|
||||
isSoftSerialTransmitBufferEmpty
|
||||
}
|
||||
};
|
||||
|
||||
|
|
|
@ -31,14 +31,17 @@ typedef struct softSerial_s {
|
|||
|
||||
} softSerial_t;
|
||||
|
||||
extern timerHardware_t* serialTimerHardware;
|
||||
extern softSerial_t softSerialPorts[];
|
||||
|
||||
extern const struct serialPortVTable softSerialVTable[];
|
||||
|
||||
void setupSoftSerial1(uint32_t baud);
|
||||
|
||||
uint8_t softSerialReadByte(serialPort_t *instance);
|
||||
uint8_t softSerialTotalBytesWaiting(serialPort_t *instance);
|
||||
|
||||
// serialPort API
|
||||
void softSerialWriteByte(serialPort_t *instance, uint8_t ch);
|
||||
uint8_t softSerialTotalBytesWaiting(serialPort_t *instance);
|
||||
uint8_t softSerialReadByte(serialPort_t *instance);
|
||||
void softSerialSetBaudRate(serialPort_t *s, uint32_t baudRate);
|
||||
bool isSoftSerialTransmitBufferEmpty(serialPort_t *s);
|
||||
|
||||
extern timerHardware_t* serialTimerHardware;
|
||||
extern softSerial_t softSerialPorts[];
|
||||
|
|
|
@ -177,9 +177,10 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
|
|||
return (serialPort_t *)s;
|
||||
}
|
||||
|
||||
void uartChangeBaud(uartPort_t *s, uint32_t baudRate)
|
||||
void uartSetBaudRate(serialPort_t *instance, uint32_t baudRate)
|
||||
{
|
||||
USART_InitTypeDef USART_InitStructure;
|
||||
uartPort_t *s = (uartPort_t *)instance;
|
||||
|
||||
USART_InitStructure.USART_BaudRate = baudRate;
|
||||
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
|
||||
|
@ -220,9 +221,10 @@ uint8_t uartTotalBytesWaiting(serialPort_t *instance)
|
|||
return s->port.rxBufferTail != s->port.rxBufferHead;
|
||||
}
|
||||
|
||||
// BUGBUG TODO TODO FIXME
|
||||
bool isUartTransmitEmpty(uartPort_t *s)
|
||||
// BUGBUG TODO TODO FIXME - What is the bug?
|
||||
bool isUartTransmitBufferEmpty(serialPort_t *instance)
|
||||
{
|
||||
uartPort_t *s = (uartPort_t *)instance;
|
||||
if (s->txDMAChannel)
|
||||
return s->txDMAEmpty;
|
||||
else
|
||||
|
@ -264,7 +266,9 @@ const struct serialPortVTable uartVTable[] = {
|
|||
{
|
||||
uartWrite,
|
||||
uartTotalBytesWaiting,
|
||||
uartRead
|
||||
uartRead,
|
||||
uartSetBaudRate,
|
||||
isUartTransmitBufferEmpty
|
||||
}
|
||||
};
|
||||
|
||||
|
|
|
@ -29,8 +29,10 @@ typedef struct {
|
|||
extern const struct serialPortVTable uartVTable[];
|
||||
|
||||
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode);
|
||||
void uartChangeBaud(uartPort_t *s, uint32_t baudRate);
|
||||
uint8_t uartTotalBytesWaiting(serialPort_t *instance);
|
||||
bool isUartTransmitEmpty(uartPort_t *s);
|
||||
uint8_t uartRead(serialPort_t *instance);
|
||||
|
||||
// serialPort API
|
||||
void uartWrite(serialPort_t *instance, uint8_t ch);
|
||||
uint8_t uartTotalBytesWaiting(serialPort_t *instance);
|
||||
uint8_t uartRead(serialPort_t *instance);
|
||||
void uartSetBaudRate(serialPort_t *s, uint32_t baudRate);
|
||||
bool isUartTransmitBufferEmpty(serialPort_t *s);
|
||||
|
|
19
src/gps.c
19
src/gps.c
|
@ -10,6 +10,9 @@ const uint32_t init_speed[5] = { 9600, 19200, 38400, 57600, 115200 };
|
|||
static void GPS_NewData(uint16_t c);
|
||||
static void gpsPrint(const char *str);
|
||||
|
||||
#define UBX_INIT_STRING_INDEX 0
|
||||
#define MTK_INIT_STRING_INDEX 4
|
||||
|
||||
static const char * const gpsInitStrings[] = {
|
||||
"$PUBX,41,1,0003,0001,19200,0*23\r\n", // UBX0..3
|
||||
"$PUBX,41,1,0003,0001,38400,0*26\r\n",
|
||||
|
@ -45,13 +48,15 @@ void gpsInit(uint32_t baudrate)
|
|||
core.gpsport = uartOpen(USART2, GPS_NewData, baudrate, MODE_RXTX);
|
||||
|
||||
if (mcfg.gps_type == GPS_UBLOX)
|
||||
offset = 0;
|
||||
offset = UBX_INIT_STRING_INDEX;
|
||||
else if (mcfg.gps_type == GPS_MTK)
|
||||
offset = 4;
|
||||
offset = MTK_INIT_STRING_INDEX;
|
||||
|
||||
if (mcfg.gps_type != GPS_NMEA) {
|
||||
for (i = 0; i < 5; i++) {
|
||||
uartChangeBaud((uartPort_t *)core.gpsport, init_speed[i]);
|
||||
serialSetBaudRate(core.gpsport, init_speed[i]);
|
||||
// verify the requested change took effect.
|
||||
baudrate = serialGetBaudRate(core.gpsport);
|
||||
switch (baudrate) {
|
||||
case 19200:
|
||||
gpsPrint(gpsInitStrings[offset]);
|
||||
|
@ -70,10 +75,10 @@ void gpsInit(uint32_t baudrate)
|
|||
}
|
||||
}
|
||||
|
||||
uartChangeBaud((uartPort_t *)core.gpsport, baudrate);
|
||||
serialSetBaudRate(core.gpsport, baudrate);
|
||||
if (mcfg.gps_type == GPS_UBLOX) {
|
||||
for (i = 0; i < sizeof(ubloxInit); i++) {
|
||||
uartWrite(core.gpsport, ubloxInit[i]); // send ubx init binary
|
||||
serialWrite(core.gpsport, ubloxInit[i]); // send ubx init binary
|
||||
delay(4);
|
||||
}
|
||||
} else if (mcfg.gps_type == GPS_MTK) {
|
||||
|
@ -90,13 +95,13 @@ void gpsInit(uint32_t baudrate)
|
|||
static void gpsPrint(const char *str)
|
||||
{
|
||||
while (*str) {
|
||||
uartWrite(core.gpsport, *str);
|
||||
serialWrite(core.gpsport, *str);
|
||||
if (mcfg.gps_type == GPS_UBLOX)
|
||||
delay(4);
|
||||
str++;
|
||||
}
|
||||
// wait to send all
|
||||
while (!isUartTransmitEmpty((uartPort_t *)core.gpsport));
|
||||
while (!isSerialTransmitBufferEmpty(core.gpsport));
|
||||
delay(30);
|
||||
}
|
||||
|
||||
|
|
|
@ -12,7 +12,7 @@ extern uint16_t pwmReadRawRC(uint8_t chan);
|
|||
// gcc/GNU version
|
||||
static void _putc(void *p, char c)
|
||||
{
|
||||
uartWrite(core.mainport, c);
|
||||
serialWrite(core.mainport, c);
|
||||
}
|
||||
#else
|
||||
// keil/armcc version
|
||||
|
@ -20,7 +20,7 @@ int fputc(int c, FILE *f)
|
|||
{
|
||||
// let DMA catch up a bit when using set or dump, we're too fast.
|
||||
while (!isUartTransmitEmpty(core.mainport));
|
||||
uartWrite(core.mainport, c);
|
||||
serialWrite(core.mainport, c);
|
||||
return c;
|
||||
}
|
||||
#endif
|
||||
|
@ -151,7 +151,7 @@ int main(void)
|
|||
|
||||
uint8_t b = serialRead(loopbackPort);
|
||||
serialWrite(loopbackPort, b);
|
||||
//uartWrite(core.mainport, b);
|
||||
//serialWrite(core.mainport, b);
|
||||
};
|
||||
#endif
|
||||
}
|
||||
|
|
2
src/mw.h
2
src/mw.h
|
@ -284,7 +284,7 @@ typedef struct master_t {
|
|||
// gps-related stuff
|
||||
uint8_t gps_type; // Type of GPS hardware. 0: NMEA 1: UBX 2+ ??
|
||||
uint32_t gps_baudrate; // GPS baudrate
|
||||
// serial(uart1) baudrate
|
||||
|
||||
uint32_t serial_baudrate;
|
||||
|
||||
config_t profile[3]; // 3 separate profiles
|
||||
|
|
|
@ -228,7 +228,7 @@ void tfp_printf(char *fmt, ...)
|
|||
va_start(va, fmt);
|
||||
tfp_format(stdout_putp, stdout_putf, fmt, va);
|
||||
va_end(va);
|
||||
while (!isUartTransmitEmpty((uartPort_t *)core.mainport));
|
||||
while (!isSerialTransmitBufferEmpty(core.mainport));
|
||||
}
|
||||
|
||||
static void putcp(void *p, char c)
|
||||
|
|
14
src/serial.c
14
src/serial.c
|
@ -157,16 +157,16 @@ void serialize32(uint32_t a)
|
|||
{
|
||||
static uint8_t t;
|
||||
t = a;
|
||||
uartWrite(core.mainport, t);
|
||||
serialWrite(core.mainport, t);
|
||||
checksum ^= t;
|
||||
t = a >> 8;
|
||||
uartWrite(core.mainport, t);
|
||||
serialWrite(core.mainport, t);
|
||||
checksum ^= t;
|
||||
t = a >> 16;
|
||||
uartWrite(core.mainport, t);
|
||||
serialWrite(core.mainport, t);
|
||||
checksum ^= t;
|
||||
t = a >> 24;
|
||||
uartWrite(core.mainport, t);
|
||||
serialWrite(core.mainport, t);
|
||||
checksum ^= t;
|
||||
}
|
||||
|
||||
|
@ -174,10 +174,10 @@ void serialize16(int16_t a)
|
|||
{
|
||||
static uint8_t t;
|
||||
t = a;
|
||||
uartWrite(core.mainport, t);
|
||||
serialWrite(core.mainport, t);
|
||||
checksum ^= t;
|
||||
t = a >> 8 & 0xff;
|
||||
uartWrite(core.mainport, t);
|
||||
serialWrite(core.mainport, t);
|
||||
checksum ^= t;
|
||||
}
|
||||
|
||||
|
@ -672,7 +672,7 @@ void serialCom(void)
|
|||
HEADER_CMD,
|
||||
} c_state = IDLE;
|
||||
|
||||
// in cli mode, all uart stuff goes to here. enter cli mode by sending #
|
||||
// in cli mode, all serial stuff goes to here. enter cli mode by sending #
|
||||
if (cliMode) {
|
||||
cliProcess();
|
||||
return;
|
||||
|
|
|
@ -50,26 +50,26 @@ extern uint8_t batteryCellCount;
|
|||
|
||||
static void sendDataHead(uint8_t id)
|
||||
{
|
||||
uartWrite(core.telemport, PROTOCOL_HEADER);
|
||||
uartWrite(core.telemport, id);
|
||||
serialWrite(core.telemport, PROTOCOL_HEADER);
|
||||
serialWrite(core.telemport, id);
|
||||
}
|
||||
|
||||
static void sendTelemetryTail(void)
|
||||
{
|
||||
uartWrite(core.telemport, PROTOCOL_TAIL);
|
||||
serialWrite(core.telemport, PROTOCOL_TAIL);
|
||||
}
|
||||
|
||||
static void serializeFrsky(uint8_t data)
|
||||
{
|
||||
// take care of byte stuffing
|
||||
if (data == 0x5e) {
|
||||
uartWrite(core.telemport, 0x5d);
|
||||
uartWrite(core.telemport, 0x3e);
|
||||
serialWrite(core.telemport, 0x5d);
|
||||
serialWrite(core.telemport, 0x3e);
|
||||
} else if (data == 0x5d) {
|
||||
uartWrite(core.telemport, 0x5d);
|
||||
uartWrite(core.telemport, 0x3d);
|
||||
serialWrite(core.telemport, 0x5d);
|
||||
serialWrite(core.telemport, 0x3d);
|
||||
} else
|
||||
uartWrite(core.telemport, data);
|
||||
serialWrite(core.telemport, data);
|
||||
}
|
||||
|
||||
static void serialize16(int16_t a)
|
||||
|
|
Loading…
Reference in New Issue