-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathserver.js
More file actions
328 lines (271 loc) · 8.19 KB
/
server.js
File metadata and controls
328 lines (271 loc) · 8.19 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
const express = require('express');
const net = require('net');
const { SerialPort } = require('serialport');
const WebSocket = require('ws');
const mavlink = require('mavlinkjs/mavlink_all_v2');
const HTTP_PORT = 3001;
const DEFAULT_TCP_HOST = '192.168.1.1';
//const DEFAULT_TCP_HOST = '127.0.0.1';
const DEFAULT_TCP_PORT = 8888;
const DEFAULT_UART_PORT = 'COM5';
const DEFAULT_UART_BAUD = 921600;
const RECONNECT_DELAY_MS = 100;
const HEARTBEAT_INTERVAL_MS = 1000; // send heartbeat every second
const MAVLINK_SYS_ID = 1;
const MAVLINK_COMP_ID = 249;
const app = express();
app.use((req, res, next) => {
res.header('Access-Control-Allow-Origin', '*');
res.header('Access-Control-Allow-Methods', 'GET,POST,OPTIONS');
res.header('Access-Control-Allow-Headers', 'Content-Type');
if (req.method === 'OPTIONS') {
res.sendStatus(204);
return;
}
next();
});
app.use(express.static('public'));
app.use(express.json());
const inputConfig = {
mode: 'tcp',
tcpHost: DEFAULT_TCP_HOST,
tcpPort: DEFAULT_TCP_PORT,
uartPort: DEFAULT_UART_PORT,
uartBaud: DEFAULT_UART_BAUD,
};
const args = process.argv.slice(2);
if (args.length > 0) {
const [host, port] = args[0].split(':');
if (host) inputConfig.tcpHost = host;
if (port) inputConfig.tcpPort = parseInt(port, 10);
}
function getPublicInputConfig() {
return {
mode: inputConfig.mode,
tcpHost: inputConfig.tcpHost,
tcpPort: inputConfig.tcpPort,
uartPort: inputConfig.uartPort,
uartBaud: inputConfig.uartBaud,
};
}
async function listAvailableSerialPorts() {
try {
const ports = await SerialPort.list();
return ports.map((port) => ({
path: port.path,
manufacturer: port.manufacturer || '',
friendlyName: [port.path, port.friendlyName || port.manufacturer]
.filter(Boolean)
.join(' - '),
}));
} catch (err) {
console.error('⚠️ Failed to enumerate serial ports:', err.message);
return [];
}
}
app.get('/api/input-config', (req, res) => {
res.json({ config: getPublicInputConfig() });
});
app.get('/api/serial-ports', async (req, res) => {
const ports = await listAvailableSerialPorts();
res.json({ ports });
});
app.post('/api/input-config', (req, res) => {
const body = req.body || {};
const mode = String(body.mode || '').toLowerCase();
if (mode !== 'tcp' && mode !== 'uart') {
res.status(400).json({ error: 'mode must be either "tcp" or "uart"' });
return;
}
const nextConfig = {
mode,
tcpHost: String(body.tcpHost || inputConfig.tcpHost || '').trim(),
tcpPort: Number(body.tcpPort ?? inputConfig.tcpPort),
uartPort: String(body.uartPort || inputConfig.uartPort || '').trim(),
uartBaud: Number(body.uartBaud ?? inputConfig.uartBaud),
};
if (!nextConfig.tcpHost) {
res.status(400).json({ error: 'tcpHost must not be empty' });
return;
}
if (!Number.isInteger(nextConfig.tcpPort) || nextConfig.tcpPort <= 0 || nextConfig.tcpPort > 65535) {
res.status(400).json({ error: 'tcpPort must be a valid TCP port' });
return;
}
if (!nextConfig.uartPort) {
res.status(400).json({ error: 'uartPort must not be empty' });
return;
}
if (!Number.isInteger(nextConfig.uartBaud) || nextConfig.uartBaud <= 0) {
res.status(400).json({ error: 'uartBaud must be a positive integer' });
return;
}
inputConfig.mode = nextConfig.mode;
inputConfig.tcpHost = nextConfig.tcpHost;
inputConfig.tcpPort = nextConfig.tcpPort;
inputConfig.uartPort = nextConfig.uartPort;
inputConfig.uartBaud = nextConfig.uartBaud;
console.log(`⚙️ Input config updated: ${JSON.stringify(getPublicInputConfig())}`);
reconnectInput();
res.json({ ok: true, config: getPublicInputConfig() });
});
const server = app.listen(HTTP_PORT, () => {
console.log(`🌐 HTTP server running at http://localhost:${HTTP_PORT}`);
});
const wss = new WebSocket.Server({ server });
function broadcast(msg) {
const json = JSON.stringify(msg);
wss.clients.forEach(client => {
if (client.readyState === WebSocket.OPEN) {
client.send(json);
}
});
}
// MAVLink parser
const mav = new mavlink.MAVLink20Processor(null, MAVLINK_SYS_ID, MAVLINK_COMP_ID);
let tcpClient;
let serialClient;
let reconnectTimer = null;
let heartbeatTimer = null;
function handleMavlinkData(data) {
let messages;
try {
messages = mav.parseBuffer(data);
for (const m of messages) {
if (m.id > -1) {
broadcast(m);
}
}
} catch (err) {
console.error('⚠️ MAVLink parse error:', err.message);
console.log(data);
}
}
function cleanupInput() {
stopHeartbeat();
if (tcpClient) {
tcpClient.removeAllListeners();
tcpClient.destroy();
tcpClient = null;
}
if (serialClient) {
serialClient.removeAllListeners();
if (serialClient.isOpen) {
serialClient.close(() => {});
}
serialClient = null;
}
}
function reconnectInput() {
if (reconnectTimer) {
clearTimeout(reconnectTimer);
reconnectTimer = null;
}
cleanupInput();
connectInput();
}
function connectInput() {
if (inputConfig.mode === 'uart') {
connectUART();
return;
}
connectTCP();
}
function connectTCP() {
cleanupInput();
tcpClient = new net.Socket();
console.log(`🔌 Attempting TCP connection to MAVLink server at ${inputConfig.tcpHost}:${inputConfig.tcpPort}...`);
tcpClient.connect(inputConfig.tcpPort, inputConfig.tcpHost);
tcpClient.on('connect', () => {
console.log(`✅ Connected to MAVLink TCP server at ${inputConfig.tcpHost}:${inputConfig.tcpPort} with SYS:COMP ${MAVLINK_SYS_ID}:${MAVLINK_COMP_ID}`);
// Start sending heartbeat
startHeartbeat();
});
tcpClient.on('data', (data) => {
handleMavlinkData(data);
});
tcpClient.on('error', (err) => {
console.error('❌ TCP connection error:', err.message);
});
tcpClient.on('close', () => {
console.warn('🔌 TCP connection closed');
stopHeartbeat();
scheduleReconnect();
});
}
function connectUART() {
cleanupInput();
if (!inputConfig.uartPort) {
console.error('❌ UART connection error: no COM port configured');
scheduleReconnect();
return;
}
serialClient = new SerialPort({
path: inputConfig.uartPort,
baudRate: inputConfig.uartBaud,
autoOpen: false,
});
console.log(`🔌 Attempting UART connection on ${inputConfig.uartPort} @ ${inputConfig.uartBaud} baud...`);
serialClient.on('open', () => {
console.log(`✅ Connected to MAVLink UART port ${inputConfig.uartPort} @ ${inputConfig.uartBaud} baud with SYS:COMP ${MAVLINK_SYS_ID}:${MAVLINK_COMP_ID}`);
startHeartbeat();
});
serialClient.on('data', (data) => {
handleMavlinkData(data);
});
serialClient.on('error', (err) => {
console.error('❌ UART connection error:', err.message);
});
serialClient.on('close', () => {
console.warn('🔌 UART connection closed');
stopHeartbeat();
scheduleReconnect();
});
serialClient.open((err) => {
if (err) {
console.error('❌ Failed to open UART port:', err.message);
scheduleReconnect();
}
});
}
function scheduleReconnect() {
if (reconnectTimer) return;
console.log(`⏳ Reconnecting ${inputConfig.mode.toUpperCase()} input in ${RECONNECT_DELAY_MS / 1000} seconds...`);
reconnectTimer = setTimeout(() => {
reconnectTimer = null;
connectInput();
}, RECONNECT_DELAY_MS);
}
function writeToInput(buffer) {
if (inputConfig.mode === 'uart') {
if (!serialClient || !serialClient.isOpen) {
throw new Error('UART is not connected');
}
serialClient.write(buffer);
return;
}
if (!tcpClient || tcpClient.destroyed) {
throw new Error('TCP socket is not connected');
}
tcpClient.write(buffer);
}
function startHeartbeat() {
if (heartbeatTimer) return;
heartbeatTimer = setInterval(() => {
try {
// type, autopilot, base_mode, custom_mode, system_status, mavlink_version
const hb = new mavlink.mavlink20.messages.heartbeat(6, 8, 0,0,0,3);
writeToInput(Buffer.from(hb.pack(mav)));
// console.log("❤️ Sent heartbeat");
} catch (err) {
console.error("⚠️ Failed to send heartbeat:", err.message);
}
}, HEARTBEAT_INTERVAL_MS);
}
function stopHeartbeat() {
if (heartbeatTimer) {
clearInterval(heartbeatTimer);
heartbeatTimer = null;
}
}
connectInput();