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;
47 bool tcpIsStart(void) {
50 static void onData(dyad_Event
*e
) {
51 tcpPort_t
* s
= (tcpPort_t
*)(e
->udata
);
52 tcpDataIn(s
, (uint8_t*)e
->data
, e
->size
);
54 static void onClose(dyad_Event
*e
) {
55 tcpPort_t
* s
= (tcpPort_t
*)(e
->udata
);
58 fprintf(stderr
, "[CLS]UART%u: %d,%d\n", s
->id
+ 1, s
->connected
, s
->clientCount
);
59 if (s
->clientCount
== 0) {
63 static void onAccept(dyad_Event
*e
) {
64 tcpPort_t
* s
= (tcpPort_t
*)(e
->udata
);
65 fprintf(stderr
, "New connection on UART%u, %d\n", s
->id
+ 1, s
->clientCount
);
68 if (s
->clientCount
> 0) {
69 dyad_close(e
->remote
);
73 fprintf(stderr
, "[NEW]UART%u: %d,%d\n", s
->id
+ 1, s
->connected
, s
->clientCount
);
75 dyad_setNoDelay(e
->remote
, 1);
76 dyad_setTimeout(e
->remote
, 120);
77 dyad_addListener(e
->remote
, DYAD_EVENT_DATA
, onData
, e
->udata
);
78 dyad_addListener(e
->remote
, DYAD_EVENT_CLOSE
, onClose
, e
->udata
);
80 static tcpPort_t
* tcpReconfigure(tcpPort_t
*s
, int id
)
82 if (tcpPortInitialized
[id
]) {
83 fprintf(stderr
, "port is already initialized!\n");
87 if (pthread_mutex_init(&s
->txLock
, NULL
) != 0) {
88 fprintf(stderr
, "TX mutex init failed - %d\n", errno
);
89 // TODO: clean up & re-init
92 if (pthread_mutex_init(&s
->rxLock
, NULL
) != 0) {
93 fprintf(stderr
, "RX mutex init failed - %d\n", errno
);
94 // TODO: clean up & re-init
99 tcpPortInitialized
[id
] = true;
101 s
->connected
= false;
105 s
->serv
= dyad_newStream();
106 dyad_setNoDelay(s
->serv
, 1);
107 dyad_addListener(s
->serv
, DYAD_EVENT_ACCEPT
, onAccept
, s
);
109 if (dyad_listenEx(s
->serv
, NULL
, BASE_PORT
+ id
+ 1, 10) == 0) {
110 fprintf(stderr
, "bind port %u for UART%u\n", (unsigned)BASE_PORT
+ id
+ 1, (unsigned)id
+ 1);
112 fprintf(stderr
, "bind port %u for UART%u failed!!\n", (unsigned)BASE_PORT
+ id
+ 1, (unsigned)id
+ 1);
117 serialPort_t
*serTcpOpen(int id
, serialReceiveCallbackPtr rxCallback
, void *rxCallbackData
, uint32_t baudRate
, portMode_e mode
, portOptions_e options
)
121 #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)
122 if (id
>= 0 && id
< SERIAL_PORT_COUNT
) {
123 s
= tcpReconfigure(&tcpSerialPorts
[id
], id
);
129 s
->port
.vTable
= &tcpVTable
;
131 // common serial initialisation code should move to serialPort::init()
132 s
->port
.rxBufferHead
= s
->port
.rxBufferTail
= 0;
133 s
->port
.txBufferHead
= s
->port
.txBufferTail
= 0;
134 s
->port
.rxBufferSize
= RX_BUFFER_SIZE
;
135 s
->port
.txBufferSize
= TX_BUFFER_SIZE
;
136 s
->port
.rxBuffer
= s
->rxBuffer
;
137 s
->port
.txBuffer
= s
->txBuffer
;
139 // callback works for IRQ-based RX ONLY
140 s
->port
.rxCallback
= rxCallback
;
141 s
->port
.rxCallbackData
= rxCallbackData
;
143 s
->port
.baudRate
= baudRate
;
144 s
->port
.options
= options
;
146 return (serialPort_t
*)s
;
149 uint32_t tcpTotalRxBytesWaiting(const serialPort_t
*instance
)
151 tcpPort_t
*s
= (tcpPort_t
*)instance
;
153 pthread_mutex_lock(&s
->rxLock
);
154 if (s
->port
.rxBufferHead
>= s
->port
.rxBufferTail
) {
155 count
= s
->port
.rxBufferHead
- s
->port
.rxBufferTail
;
157 count
= s
->port
.rxBufferSize
+ s
->port
.rxBufferHead
- s
->port
.rxBufferTail
;
159 pthread_mutex_unlock(&s
->rxLock
);
164 uint32_t tcpTotalTxBytesFree(const serialPort_t
*instance
)
166 tcpPort_t
*s
= (tcpPort_t
*)instance
;
169 pthread_mutex_lock(&s
->txLock
);
170 if (s
->port
.txBufferHead
>= s
->port
.txBufferTail
) {
171 bytesUsed
= s
->port
.txBufferHead
- s
->port
.txBufferTail
;
173 bytesUsed
= s
->port
.txBufferSize
+ s
->port
.txBufferHead
- s
->port
.txBufferTail
;
175 uint32_t bytesFree
= (s
->port
.txBufferSize
- 1) - bytesUsed
;
176 pthread_mutex_unlock(&s
->txLock
);
181 bool isTcpTransmitBufferEmpty(const serialPort_t
*instance
)
183 tcpPort_t
*s
= (tcpPort_t
*)instance
;
184 pthread_mutex_lock(&s
->txLock
);
185 bool isEmpty
= s
->port
.txBufferTail
== s
->port
.txBufferHead
;
186 pthread_mutex_unlock(&s
->txLock
);
190 uint8_t tcpRead(serialPort_t
*instance
)
193 tcpPort_t
*s
= (tcpPort_t
*)instance
;
194 pthread_mutex_lock(&s
->rxLock
);
196 ch
= s
->port
.rxBuffer
[s
->port
.rxBufferTail
];
197 if (s
->port
.rxBufferTail
+ 1 >= s
->port
.rxBufferSize
) {
198 s
->port
.rxBufferTail
= 0;
200 s
->port
.rxBufferTail
++;
202 pthread_mutex_unlock(&s
->rxLock
);
207 void tcpWrite(serialPort_t
*instance
, uint8_t ch
)
209 tcpPort_t
*s
= (tcpPort_t
*)instance
;
210 pthread_mutex_lock(&s
->txLock
);
212 s
->port
.txBuffer
[s
->port
.txBufferHead
] = ch
;
213 if (s
->port
.txBufferHead
+ 1 >= s
->port
.txBufferSize
) {
214 s
->port
.txBufferHead
= 0;
216 s
->port
.txBufferHead
++;
218 pthread_mutex_unlock(&s
->txLock
);
223 void tcpDataOut(tcpPort_t
*instance
)
225 tcpPort_t
*s
= (tcpPort_t
*)instance
;
226 if (s
->conn
== NULL
) return;
227 pthread_mutex_lock(&s
->txLock
);
229 if (s
->port
.txBufferHead
< s
->port
.txBufferTail
) {
230 // send data till end of buffer
231 int chunk
= s
->port
.txBufferSize
- s
->port
.txBufferTail
;
232 dyad_write(s
->conn
, (const void *)&s
->port
.txBuffer
[s
->port
.txBufferTail
], chunk
);
233 s
->port
.txBufferTail
= 0;
235 int chunk
= s
->port
.txBufferHead
- s
->port
.txBufferTail
;
237 dyad_write(s
->conn
, (const void*)&s
->port
.txBuffer
[s
->port
.txBufferTail
], chunk
);
238 s
->port
.txBufferTail
= s
->port
.txBufferHead
;
240 pthread_mutex_unlock(&s
->txLock
);
243 void tcpDataIn(tcpPort_t
*instance
, uint8_t* ch
, int size
)
245 tcpPort_t
*s
= (tcpPort_t
*)instance
;
246 pthread_mutex_lock(&s
->rxLock
);
249 // printf("%c", *ch);
250 s
->port
.rxBuffer
[s
->port
.rxBufferHead
] = *(ch
++);
251 if (s
->port
.rxBufferHead
+ 1 >= s
->port
.rxBufferSize
) {
252 s
->port
.rxBufferHead
= 0;
254 s
->port
.rxBufferHead
++;
257 pthread_mutex_unlock(&s
->rxLock
);
261 static const struct serialPortVTable tcpVTable
= {
262 .serialWrite
= tcpWrite
,
263 .serialTotalRxWaiting
= tcpTotalRxBytesWaiting
,
264 .serialTotalTxFree
= tcpTotalTxBytesFree
,
265 .serialRead
= tcpRead
,
266 .serialSetBaudRate
= NULL
,
267 .isSerialTransmitBufferEmpty
= isTcpTransmitBufferEmpty
,
269 .setCtrlLineStateCb
= NULL
,
270 .setBaudRateCb
= NULL
,