-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathindex.js
More file actions
executable file
·252 lines (196 loc) · 6.47 KB
/
index.js
File metadata and controls
executable file
·252 lines (196 loc) · 6.47 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
/**
* Interoperability script. Authenticates with auvsi server
* listens for mavlink packets through udp4 socket
* posts groundstation telemetry to auvsi server ten times per
* second. GETs auvsi server time every second. Gets SDA
* obstacle information from auvsi server every second, converts
* obstacle information into mavlink waypoints and reuses the
* same udp socket used for receiving telemetry to send auvsi
* server obstacle information to mavproxy groundstation.
*
* @author juanvallejo
* @date 6/20/15
*/
var http = require('http');
var fs = require('fs');
var utils = require('./utils.js');
var auvsi = require('./auvsi.js');
var api = require('./api.js');
var mavlink = require('./mavl.js');
var mission = require('./mission.js');
var telemetry = require('./telemetry.js');
var waypoints = require('./waypoints.js');
var libsock = require('./libsock.js');
var server = require('./server.js');
var config = require('./config.js');
/**
* Initialize module event listeners
* Listen for mavlink messages and auvsi
* api data
*/
function init_listeners() {
utils.log('_JAM V1.0.\nAwaiting telemetry...');
var telemetryCount = 0;
var lastTelemetryFreq = 0;
var telemetryCountUpdated = false;
var futureTime = (Date.now() / 1000) + 1;
libsock.on('message', function(message, rinfo) {
mavlink.incoming.parse(message);
});
// subscribe to websocket connection events
server.on('connection', function(client) {
utils.log('server>client> ' + client.id + ' has connected');
libsock.io_register(client.id, client);
client.on('disconnect', function() {
libsock.io_unregister(client.id);
});
});
// subscribe to http request events
server.on('request', function(request, response, path) {
if(path.match(/\/api\/.*/gi)) {
if(path.match(/\/api\/grid/gi)) {
return server.receive_api_grid_request(request, response,
api.get_grid_details(telemetry, waypoints));
}
if(path.match(/\/api\/path/gi)) {
return server.receive_api_path_request(request, response);
}
// relay /api/target requests to interop
if(path.match(/\/api\/targets(\/)?.*/gi)) {
return server.receive_api_target_request(request, response, auvsi);
}
return server.receive_api_request(request, response, server.REQUEST_API_IS_INVALID);
}
server.receive_request(request, response, path);
});
server.on('error', function(e) {
if (e.code == 'EADDRINUSE') {
console.log('ERROR: http server port already in use, exiting');
process.exit(1);
} else {
console.log('ERROR: Error in http server ' + e);
}
});
// subscribe to auvsi server info events
auvsi.on('info', function(data) {
libsock.io_broadcast('server_info', data);
});
// subscribe to auvsi obstacle events
auvsi.on('obstacles', function(data) {
libsock.io_broadcast('obstacle_data', data);
});
auvsi.on('mission', function(data) {
libsock.io_broadcast('mission_data', data);
});
// subscribe to mission waypoints received events
mission.on('waypoints', function(data) {
console.log('_JAM WAYPOINTS received');
waypoints.set_waypoints(data);
libsock.io_broadcast('waypoint_data', data);
});
// handle mission errors
mission.on('error', function(err) {
utils.log(err);
});
// listen for response after sending MISSION_REQUEST_LIST message
mavlink.incoming.on('MISSION_COUNT', function(message, fields) {
mission.waypoints_count_limit = fields.count;
mission.receive_waypoint_count(libsock, mavlink, fields.count);
});
// retireve current waypoint
mavlink.incoming.on('MISSION_CURRENT', function(message, fields) {
// determine if waypoint exists and update
// waypoints for api. Setting the current waypt
// sets the next, previous, and following waypoints
if(waypoints.get_waypoint(fields.seq)) {
libsock.io_broadcast('waypoint_data', waypoints.get_waypoints());
return waypoints.set_current_waypoint(mavlink, fields.seq);
}
// assume no waypoints have been requested / loaded
if(!mission.is_received_waypoint_count() && !mission.is_queued_waypoint_count()) {
console.log('Requesting waypoints...');
mission.request_waypoints(libsock, mavlink);
}
});
/**
* Handle waypoint data from GCS
*/
mavlink.incoming.on('MISSION_ITEM', function(message, fields) {
console.log('mission item received');
mission.receive_waypoint(libsock, mavlink, fields, mission.waypoints_count_limit);
});
mavlink.incoming.on('STATUSTEXT', function(message, fields) {
utils.log('MAVLINK INCOMING received status text');
});
/**
* Handle plane location telemetry from GCS
*/
mavlink.incoming.on('GLOBAL_POSITION_INT', function(message, fields) {
// update telemetry
mavlink.set_time_boot(fields['time_boot_ms']);
telemetry.set_lat(fields['lat'] / (Math.pow(10, 7)));
telemetry.set_lon(fields['lon'] / (Math.pow(10, 7)));
telemetry.set_alt_msl(fields['alt'] * 0.00328084);
telemetry.set_heading(fields['hdg'] / 100);
// check for appropriate telemetry values
if(telemetry.get_lat() > 90) {
telemetry.set_lat(90);
}
if(telemetry.get_lat() < -90) {
telemetry.set_lat(-90);
}
if(telemetry.get_lon() > 180) {
telemetry.set_lon(180);
}
if(telemetry.get_lon() < -180) {
telemetry.set_lon(-180);
}
if(telemetry.get_heading() > 360) {
telemetry.set_heading(360);
}
if(telemetry.get_heading() < 0) {
telemetry.set_heading(0);
}
if(!mavlink.is_received_message()) {
mavlink.is_received_message(true);
}
// post telemetry to auvsi
if(mavlink.get_time_boot() == mavlink.get_previous_time_boot()) {
utils.log('WARN MAVLINK Duplicate data received, discarding...');
return;
}
// calculate message frequency
telemetryCountUpdated = false;
telemetryCount++;
if(Date.now() >= futureTime) {
futureTime = Date.now() + 1000;
lastTelemetryFreq = telemetryCount;
telemetryCountUpdated = true;
telemetryCount = 0;
}
auvsi.post_telemetry(telemetry, mavlink);
// send mavlink event to all socket.io clients
libsock.io_broadcast('mavlink', telemetry);
if(telemetryCountUpdated) {
libsock.io_broadcast('frequency_status', { frequency: lastTelemetryFreq });
}
});
}
/**
* Start mavlink event listeners and initialize
* rest of the application / modules
*/
(function init() {
try {
// set user module configuration
mavlink.init(function() {
libsock.init(function() {
auvsi.init();
server.init();
init_listeners();
});
});
} catch(e) {
console.log('Seems like something has gone wrong:', e);
}
})();