2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
23 * Dominic Clifton - Serial port abstraction, Separation of common STM32 code for cleanflight, various cleanups.
24 * Hamasaki/Timecop - Initial baseflight code
34 #include "build/build_config.h"
36 #include "common/utils.h"
38 #include "io/serial.h"
39 #include "serial_tcp.h"
41 #define BASE_PORT 5760
43 static const struct serialPortVTable tcpVTable
; // Forward
44 static tcpPort_t tcpSerialPorts
[SERIAL_PORT_COUNT
];
45 static bool tcpPortInitialized
[SERIAL_PORT_COUNT
];
46 static bool tcpStart
= false;
51 static void onData(dyad_Event
*e
)
53 tcpPort_t
* s
= (tcpPort_t
*)(e
->udata
);
54 tcpDataIn(s
, (uint8_t*)e
->data
, e
->size
);
56 static void onClose(dyad_Event
*e
)
58 tcpPort_t
* s
= (tcpPort_t
*)(e
->udata
);
61 fprintf(stderr
, "[CLS]UART%u: %d,%d\n", s
->id
+ 1, s
->connected
, s
->clientCount
);
62 if (s
->clientCount
== 0) {
66 static void onAccept(dyad_Event
*e
)
68 tcpPort_t
* s
= (tcpPort_t
*)(e
->udata
);
69 fprintf(stderr
, "New connection on UART%u, %d\n", s
->id
+ 1, s
->clientCount
);
72 if (s
->clientCount
> 0) {
73 dyad_close(e
->remote
);
77 fprintf(stderr
, "[NEW]UART%u: %d,%d\n", s
->id
+ 1, s
->connected
, s
->clientCount
);
79 dyad_setNoDelay(e
->remote
, 1);
80 dyad_setTimeout(e
->remote
, 120);
81 dyad_addListener(e
->remote
, DYAD_EVENT_DATA
, onData
, e
->udata
);
82 dyad_addListener(e
->remote
, DYAD_EVENT_CLOSE
, onClose
, e
->udata
);
84 static tcpPort_t
* tcpReconfigure(tcpPort_t
*s
, int id
)
86 if (tcpPortInitialized
[id
]) {
87 fprintf(stderr
, "port is already initialized!\n");
91 if (pthread_mutex_init(&s
->txLock
, NULL
) != 0) {
92 fprintf(stderr
, "TX mutex init failed - %d\n", errno
);
93 // TODO: clean up & re-init
96 if (pthread_mutex_init(&s
->rxLock
, NULL
) != 0) {
97 fprintf(stderr
, "RX mutex init failed - %d\n", errno
);
98 // TODO: clean up & re-init
103 tcpPortInitialized
[id
] = true;
105 s
->connected
= false;
109 s
->serv
= dyad_newStream();
110 dyad_setNoDelay(s
->serv
, 1);
111 dyad_addListener(s
->serv
, DYAD_EVENT_ACCEPT
, onAccept
, s
);
113 if (dyad_listenEx(s
->serv
, NULL
, BASE_PORT
+ id
+ 1, 10) == 0) {
114 fprintf(stderr
, "bind port %u for UART%u\n", (unsigned)BASE_PORT
+ id
+ 1, (unsigned)id
+ 1);
116 fprintf(stderr
, "bind port %u for UART%u failed!!\n", (unsigned)BASE_PORT
+ id
+ 1, (unsigned)id
+ 1);
121 serialPort_t
*serTcpOpen(int id
, serialReceiveCallbackPtr rxCallback
, void *rxCallbackData
, uint32_t baudRate
, portMode_e mode
, portOptions_e options
)
125 #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)
126 if (id
>= 0 && id
< SERIAL_PORT_COUNT
) {
127 s
= tcpReconfigure(&tcpSerialPorts
[id
], id
);
133 s
->port
.vTable
= &tcpVTable
;
135 // common serial initialisation code should move to serialPort::init()
136 s
->port
.rxBufferHead
= s
->port
.rxBufferTail
= 0;
137 s
->port
.txBufferHead
= s
->port
.txBufferTail
= 0;
138 s
->port
.rxBufferSize
= RX_BUFFER_SIZE
;
139 s
->port
.txBufferSize
= TX_BUFFER_SIZE
;
140 s
->port
.rxBuffer
= s
->rxBuffer
;
141 s
->port
.txBuffer
= s
->txBuffer
;
143 // callback works for IRQ-based RX ONLY
144 s
->port
.rxCallback
= rxCallback
;
145 s
->port
.rxCallbackData
= rxCallbackData
;
147 s
->port
.baudRate
= baudRate
;
148 s
->port
.options
= options
;
150 return (serialPort_t
*)s
;
153 uint32_t tcpTotalRxBytesWaiting(const serialPort_t
*instance
)
155 tcpPort_t
*s
= (tcpPort_t
*)instance
;
157 pthread_mutex_lock(&s
->rxLock
);
158 if (s
->port
.rxBufferHead
>= s
->port
.rxBufferTail
) {
159 count
= s
->port
.rxBufferHead
- s
->port
.rxBufferTail
;
161 count
= s
->port
.rxBufferSize
+ s
->port
.rxBufferHead
- s
->port
.rxBufferTail
;
163 pthread_mutex_unlock(&s
->rxLock
);
168 uint32_t tcpTotalTxBytesFree(const serialPort_t
*instance
)
170 tcpPort_t
*s
= (tcpPort_t
*)instance
;
173 pthread_mutex_lock(&s
->txLock
);
174 if (s
->port
.txBufferHead
>= s
->port
.txBufferTail
) {
175 bytesUsed
= s
->port
.txBufferHead
- s
->port
.txBufferTail
;
177 bytesUsed
= s
->port
.txBufferSize
+ s
->port
.txBufferHead
- s
->port
.txBufferTail
;
179 uint32_t bytesFree
= (s
->port
.txBufferSize
- 1) - bytesUsed
;
180 pthread_mutex_unlock(&s
->txLock
);
185 bool isTcpTransmitBufferEmpty(const serialPort_t
*instance
)
187 tcpPort_t
*s
= (tcpPort_t
*)instance
;
188 pthread_mutex_lock(&s
->txLock
);
189 bool isEmpty
= s
->port
.txBufferTail
== s
->port
.txBufferHead
;
190 pthread_mutex_unlock(&s
->txLock
);
194 uint8_t tcpRead(serialPort_t
*instance
)
197 tcpPort_t
*s
= (tcpPort_t
*)instance
;
198 pthread_mutex_lock(&s
->rxLock
);
200 ch
= s
->port
.rxBuffer
[s
->port
.rxBufferTail
];
201 if (s
->port
.rxBufferTail
+ 1 >= s
->port
.rxBufferSize
) {
202 s
->port
.rxBufferTail
= 0;
204 s
->port
.rxBufferTail
++;
206 pthread_mutex_unlock(&s
->rxLock
);
211 void tcpWrite(serialPort_t
*instance
, uint8_t ch
)
213 tcpPort_t
*s
= (tcpPort_t
*)instance
;
214 pthread_mutex_lock(&s
->txLock
);
216 s
->port
.txBuffer
[s
->port
.txBufferHead
] = ch
;
217 if (s
->port
.txBufferHead
+ 1 >= s
->port
.txBufferSize
) {
218 s
->port
.txBufferHead
= 0;
220 s
->port
.txBufferHead
++;
222 pthread_mutex_unlock(&s
->txLock
);
227 void tcpDataOut(tcpPort_t
*instance
)
229 tcpPort_t
*s
= (tcpPort_t
*)instance
;
230 if (s
->conn
== NULL
) return;
231 pthread_mutex_lock(&s
->txLock
);
233 if (s
->port
.txBufferHead
< s
->port
.txBufferTail
) {
234 // send data till end of buffer
235 int chunk
= s
->port
.txBufferSize
- s
->port
.txBufferTail
;
236 dyad_write(s
->conn
, (const void *)&s
->port
.txBuffer
[s
->port
.txBufferTail
], chunk
);
237 s
->port
.txBufferTail
= 0;
239 int chunk
= s
->port
.txBufferHead
- s
->port
.txBufferTail
;
241 dyad_write(s
->conn
, (const void*)&s
->port
.txBuffer
[s
->port
.txBufferTail
], chunk
);
242 s
->port
.txBufferTail
= s
->port
.txBufferHead
;
244 pthread_mutex_unlock(&s
->txLock
);
247 void tcpDataIn(tcpPort_t
*instance
, uint8_t* ch
, int size
)
249 tcpPort_t
*s
= (tcpPort_t
*)instance
;
250 pthread_mutex_lock(&s
->rxLock
);
253 // printf("%c", *ch);
254 s
->port
.rxBuffer
[s
->port
.rxBufferHead
] = *(ch
++);
255 if (s
->port
.rxBufferHead
+ 1 >= s
->port
.rxBufferSize
) {
256 s
->port
.rxBufferHead
= 0;
258 s
->port
.rxBufferHead
++;
261 pthread_mutex_unlock(&s
->rxLock
);
265 static const struct serialPortVTable tcpVTable
= {
266 .serialWrite
= tcpWrite
,
267 .serialTotalRxWaiting
= tcpTotalRxBytesWaiting
,
268 .serialTotalTxFree
= tcpTotalTxBytesFree
,
269 .serialRead
= tcpRead
,
270 .serialSetBaudRate
= NULL
,
271 .isSerialTransmitBufferEmpty
= isTcpTransmitBufferEmpty
,
273 .setCtrlLineStateCb
= NULL
,
274 .setBaudRateCb
= NULL
,