-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathindex.js
99 lines (77 loc) · 2.4 KB
/
index.js
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
/*
* Copyright (c) 2021. UAVenture AG. All rights reserved.
*/
let dgram = require('dgram');
const mavlib = require('mavlink-lib');
const express = require('express');
const http = require('http');
const { Server } = require(`socket.io`);
const HTTP_PORT = process.env.HTTP_PORT || 81;
// On Balena replace the IP with: copilot
const COPILOT_IP = process.env.COPILOT_IP || 'copilot';
const COPILOT_PORT = process.env.COPILOT_PORT || 44000;
const app = express();
const server = http.createServer(app);
const io = new Server(server);
let udpClient = dgram.createSocket('udp4');
// Capture kill signal and clean up.
process.on('SIGINT', () => {
console.log('Closing port');
if (udpClient) {
udpClient.close();
}
if (heartbeatInterval) {
clearInterval(heartbeatInterval);
}
});
/*****************************************************
* Webserver
*****************************************************/
app.get('/', (req, res) => {
res.sendFile(__dirname + '/static/index.html');
});
server.listen(HTTP_PORT, function() {
console.log("server is listening on port", HTTP_PORT);
});
/*****************************************************
* MAVLink
*****************************************************/
let mav = new mavlib.MavlinkLib(240, 1, null);
mav.on('message', function(message) {
//console.log(`Message: ${message.name}`);
io.emit('msg', { name: message.name });
});
const heartbeatInterval = setInterval(function () {
sendHeartbeat();
}, 1000);
function sendHeartbeat() {
const heartbeat = new mavlib.messages.heartbeat(
type = mavlib.mavlink.MAV_TYPE_ONBOARD_CONTROLLER,
autopilot = mavlib.mavlink.MAV_AUTOPILOT_AIRRAILS,
base_mode = 64,
custom_mode = 0,
system_status = mavlib.mavlink.MAV_STATE_ACTIVE,
mavlink_version = mavlib.mavlink.WIRE_PROTOCOL_VERSION
);
const bytes = new Buffer(heartbeat.pack(mav));
sendMessage(bytes);
}
/*****************************************************
* UDP
*****************************************************/
udpClient.on('message', (data, rinfo) => {
if (mav) {
mav.parseData(data);
}
});
udpClient.on('error', (err) => {
console.log('MAVLink: client error: ' + err);
udpClient.close();
});
function sendMessage(bytes) {
if (udpClient) {
udpClient.send(bytes, 0, bytes.length, COPILOT_PORT, COPILOT_IP, function (err, bytes) {
if (err) console.error('MAVLink: UDP Send error: ' + err);
});
}
}