uartOpen signature got changed, breaking SITL (hard way)

This cleans up serial_tcp a bit and uses new function name.
This commit is contained in:
Petr Ledvina 2017-05-19 23:17:41 +02:00
parent a452b21a59
commit 00bd8d91d5
3 changed files with 34 additions and 35 deletions

View File

@ -37,9 +37,9 @@
#define BASE_PORT 5760 #define BASE_PORT 5760
const struct serialPortVTable uartVTable[]; // Forward static const struct serialPortVTable tcpVTable; // Forward
static tcpPort_t tcpSerialPorts[SERIAL_PORT_COUNT]; static tcpPort_t tcpSerialPorts[SERIAL_PORT_COUNT];
static bool portInited[SERIAL_PORT_COUNT]; static bool tcpPortInited[SERIAL_PORT_COUNT];
static bool tcpStart = false; static bool tcpStart = false;
bool tcpIsStart(void) { bool tcpIsStart(void) {
return tcpStart; return tcpStart;
@ -76,8 +76,8 @@ static void onAccept(dyad_Event *e) {
} }
static tcpPort_t* tcpReconfigure(tcpPort_t *s, int id) static tcpPort_t* tcpReconfigure(tcpPort_t *s, int id)
{ {
if(portInited[id]) { if(tcpPortInited[id]) {
fprintf(stderr, "port had initialed!!\n"); fprintf(stderr, "port is already initialed!\n");
return s; return s;
} }
@ -93,7 +93,7 @@ static tcpPort_t* tcpReconfigure(tcpPort_t *s, int id)
} }
tcpStart = true; tcpStart = true;
portInited[id] = true; tcpPortInited[id] = true;
s->connected = false; s->connected = false;
s->clientCount = 0; s->clientCount = 0;
@ -104,25 +104,26 @@ static tcpPort_t* tcpReconfigure(tcpPort_t *s, int id)
dyad_addListener(s->serv, DYAD_EVENT_ACCEPT, onAccept, s); dyad_addListener(s->serv, DYAD_EVENT_ACCEPT, onAccept, s);
if(dyad_listenEx(s->serv, NULL, BASE_PORT + id + 1, 10) == 0) { if(dyad_listenEx(s->serv, NULL, BASE_PORT + id + 1, 10) == 0) {
fprintf(stderr, "bind port %u for UART%u\n", (unsigned)BASE_PORT + id + 1, (unsigned)id+1); fprintf(stderr, "bind port %u for UART%u\n", (unsigned)BASE_PORT + id + 1, (unsigned)id + 1);
} else { } else {
fprintf(stderr, "bind port %u for UART%u failed!!\n", (unsigned)BASE_PORT + id + 1, (unsigned)id+1); fprintf(stderr, "bind port %u for UART%u failed!!\n", (unsigned)BASE_PORT + id + 1, (unsigned)id + 1);
} }
return s; return s;
} }
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options) serialPort_t *serTcpOpen(int id, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options)
{ {
tcpPort_t *s = NULL; tcpPort_t *s = NULL;
#if defined(USE_UART1) || defined(USE_UART2) || defined(USE_UART3) || defined(USE_UART4) || defined(USE_UART5) || defined(USE_UART6) || defined(USE_UART7) || defined(USE_UART8) #if defined(USE_UART1) || defined(USE_UART2) || defined(USE_UART3) || defined(USE_UART4) || defined(USE_UART5) || defined(USE_UART6) || defined(USE_UART7) || defined(USE_UART8)
uintptr_t id = ((uintptr_t)USARTx - 1); if(id >= 0 && id < SERIAL_PORT_COUNT) {
s = tcpReconfigure(&tcpSerialPorts[id], id); s = tcpReconfigure(&tcpSerialPorts[id], id);
#else }
return (serialPort_t *)s;
#endif #endif
if(!s)
return NULL;
s->port.vTable = uartVTable; s->port.vTable = &tcpVTable;
// common serial initialisation code should move to serialPort::init() // common serial initialisation code should move to serialPort::init()
s->port.rxBufferHead = s->port.rxBufferTail = 0; s->port.rxBufferHead = s->port.rxBufferTail = 0;
@ -167,10 +168,10 @@ uint32_t tcpTotalTxBytesFree(const serialPort_t *instance)
} else { } else {
bytesUsed = s->port.txBufferSize + s->port.txBufferHead - s->port.txBufferTail; bytesUsed = s->port.txBufferSize + s->port.txBufferHead - s->port.txBufferTail;
} }
bytesUsed = (s->port.txBufferSize - 1) - bytesUsed; uint32_t bytesFree = (s->port.txBufferSize - 1) - bytesUsed;
pthread_mutex_unlock(&s->txLock); pthread_mutex_unlock(&s->txLock);
return bytesUsed; return bytesFree;
} }
bool isTcpTransmitBufferEmpty(const serialPort_t *instance) bool isTcpTransmitBufferEmpty(const serialPort_t *instance)
@ -217,18 +218,19 @@ void tcpWrite(serialPort_t *instance, uint8_t ch)
void tcpDataOut(tcpPort_t *instance) void tcpDataOut(tcpPort_t *instance)
{ {
uint32_t bytesUsed;
tcpPort_t *s = (tcpPort_t *)instance; tcpPort_t *s = (tcpPort_t *)instance;
if(s->conn == NULL) return; if(s->conn == NULL) return;
pthread_mutex_lock(&s->txLock); pthread_mutex_lock(&s->txLock);
if (s->port.txBufferHead < s->port.txBufferTail) { if (s->port.txBufferHead < s->port.txBufferTail) {
bytesUsed = s->port.txBufferSize + s->port.txBufferHead - s->port.txBufferTail; // send data till end of buffer
dyad_write(s->conn, (const void *)(s->port.txBuffer + s->port.txBufferTail), s->port.txBufferSize - s->port.txBufferTail); int chunk = s->port.txBufferSize - s->port.txBufferTail;
dyad_write(s->conn, (const void *)&s->port.txBuffer[s->port.txBufferTail], chunk);
s->port.txBufferTail = 0; s->port.txBufferTail = 0;
} }
bytesUsed = s->port.txBufferHead - s->port.txBufferTail; int chunk = s->port.txBufferHead - s->port.txBufferTail;
dyad_write(s->conn, (const void *)(&(s->port.txBuffer[s->port.txBufferTail])), bytesUsed); if(chunk)
dyad_write(s->conn, (const void*)&s->port.txBuffer[s->port.txBufferTail], chunk);
s->port.txBufferTail = s->port.txBufferHead; s->port.txBufferTail = s->port.txBufferHead;
pthread_mutex_unlock(&s->txLock); pthread_mutex_unlock(&s->txLock);
@ -252,8 +254,7 @@ void tcpDataIn(tcpPort_t *instance, uint8_t* ch, int size)
// printf("\n"); // printf("\n");
} }
const struct serialPortVTable uartVTable[] = { static const struct serialPortVTable tcpVTable = {
{
.serialWrite = tcpWrite, .serialWrite = tcpWrite,
.serialTotalRxWaiting = tcpTotalRxBytesWaiting, .serialTotalRxWaiting = tcpTotalRxBytesWaiting,
.serialTotalTxFree = tcpTotalTxBytesFree, .serialTotalTxFree = tcpTotalTxBytesFree,
@ -264,5 +265,4 @@ const struct serialPortVTable uartVTable[] = {
.writeBuf = NULL, .writeBuf = NULL,
.beginWrite = NULL, .beginWrite = NULL,
.endWrite = NULL, .endWrite = NULL,
}
}; };

View File

@ -20,19 +20,14 @@
#include <netinet/in.h> #include <netinet/in.h>
#include <pthread.h> #include <pthread.h>
#include "dyad.h" #include "dyad.h"
// 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 RX_BUFFER_SIZE 1400 #define RX_BUFFER_SIZE 1400
#define TX_BUFFER_SIZE 1400 #define TX_BUFFER_SIZE 1400
typedef struct { typedef struct {
serialPort_t port; serialPort_t port;
volatile uint8_t rxBuffer[RX_BUFFER_SIZE]; uint8_t rxBuffer[RX_BUFFER_SIZE];
volatile uint8_t txBuffer[TX_BUFFER_SIZE]; uint8_t txBuffer[TX_BUFFER_SIZE];
dyad_Stream *serv; dyad_Stream *serv;
dyad_Stream *conn; dyad_Stream *conn;
@ -43,16 +38,11 @@ typedef struct {
uint8_t id; uint8_t id;
} tcpPort_t; } tcpPort_t;
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options); serialPort_t *serTcpOpen(int id, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options);
// tcpPort API // tcpPort API
void tcpWrite(serialPort_t *instance, uint8_t ch);
void tcpDataIn(tcpPort_t *instance, uint8_t* ch, int size); void tcpDataIn(tcpPort_t *instance, uint8_t* ch, int size);
uint32_t tcpTotalRxBytesWaiting(const serialPort_t *instance);
uint32_t tcpTotalTxBytesFree(const serialPort_t *instance);
uint8_t tcpRead(serialPort_t *instance);
void tcpDataOut(tcpPort_t *instance); void tcpDataOut(tcpPort_t *instance);
bool isTcpTransmitBufferEmpty(const serialPort_t *s);
bool tcpIsStart(void); bool tcpIsStart(void);
bool* tcpGetUsed(void); bool* tcpGetUsed(void);

View File

@ -44,6 +44,10 @@
#include "drivers/serial_uart.h" #include "drivers/serial_uart.h"
#endif #endif
#ifdef SITL
#include "drivers/serial_tcp.h"
#endif
#include "drivers/light_led.h" #include "drivers/light_led.h"
#if defined(USE_VCP) #if defined(USE_VCP)
@ -379,7 +383,12 @@ serialPort_t *openSerialPort(
#ifdef USE_UART8 #ifdef USE_UART8
case SERIAL_PORT_USART8: case SERIAL_PORT_USART8:
#endif #endif
#ifdef SITL
// SITL emulates serial ports over TCP
serialPort = serTcpOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, baudRate, mode, options);
#else
serialPort = uartOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, baudRate, mode, options); serialPort = uartOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, baudRate, mode, options);
#endif
break; break;
#endif #endif