mavgen_javascript.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 '''
3 parse a MAVLink protocol XML file and generate a Node.js javascript module implementation
4 
5 Based on original work Copyright Andrew Tridgell 2011
6 Released under GNU GPL version 3 or later
7 '''
8 from __future__ import print_function
9 
10 from builtins import range
11 
12 import os
13 import textwrap
14 from . import mavtemplate
15 
17 
18 def generate_preamble(outf, msgs, args, xml):
19  print("Generating preamble")
20  t.write(outf, """
21 /*
22 MAVLink protocol implementation for node.js (auto-generated by mavgen_javascript.py)
23 
24 Generated from: ${FILELIST}
25 
26 Note: this file has been auto-generated. DO NOT EDIT
27 */
28 
29 jspack = require("jspack").jspack,
30  _ = require("underscore"),
31  events = require("events"),
32  util = require("util");
33 
34 // Add a convenience method to Buffer
35 Buffer.prototype.toByteArray = function () {
36  return Array.prototype.slice.call(this, 0)
37 }
38 
39 mavlink = function(){};
40 
41 // Implement the X25CRC function (present in the Python version through the mavutil.py package)
42 mavlink.x25Crc = function(buffer, crc) {
43 
44  var bytes = buffer;
45  var crc = crc || 0xffff;
46  _.each(bytes, function(e) {
47  var tmp = e ^ (crc & 0xff);
48  tmp = (tmp ^ (tmp << 4)) & 0xff;
49  crc = (crc >> 8) ^ (tmp << 8) ^ (tmp << 3) ^ (tmp >> 4);
50  crc = crc & 0xffff;
51  });
52  return crc;
53 
54 }
55 
56 mavlink.WIRE_PROTOCOL_VERSION = "${WIRE_PROTOCOL_VERSION}";
57 
58 mavlink.MAVLINK_TYPE_CHAR = 0
59 mavlink.MAVLINK_TYPE_UINT8_T = 1
60 mavlink.MAVLINK_TYPE_INT8_T = 2
61 mavlink.MAVLINK_TYPE_UINT16_T = 3
62 mavlink.MAVLINK_TYPE_INT16_T = 4
63 mavlink.MAVLINK_TYPE_UINT32_T = 5
64 mavlink.MAVLINK_TYPE_INT32_T = 6
65 mavlink.MAVLINK_TYPE_UINT64_T = 7
66 mavlink.MAVLINK_TYPE_INT64_T = 8
67 mavlink.MAVLINK_TYPE_FLOAT = 9
68 mavlink.MAVLINK_TYPE_DOUBLE = 10
69 
70 // Mavlink headers incorporate sequence, source system (platform) and source component.
71 mavlink.header = function(msgId, mlen, seq, srcSystem, srcComponent) {
72 
73  this.mlen = ( typeof mlen === 'undefined' ) ? 0 : mlen;
74  this.seq = ( typeof seq === 'undefined' ) ? 0 : seq;
75  this.srcSystem = ( typeof srcSystem === 'undefined' ) ? 0 : srcSystem;
76  this.srcComponent = ( typeof srcComponent === 'undefined' ) ? 0 : srcComponent;
77  this.msgId = msgId
78 
79 }
80 
81 mavlink.header.prototype.pack = function() {
82  return jspack.Pack('BBBBBB', [${PROTOCOL_MARKER}, this.mlen, this.seq, this.srcSystem, this.srcComponent, this.msgId]);
83 }
84 
85 // Base class declaration: mavlink.message will be the parent class for each
86 // concrete implementation in mavlink.messages.
87 mavlink.message = function() {};
88 
89 // Convenience setter to facilitate turning the unpacked array of data into member properties
90 mavlink.message.prototype.set = function(args) {
91  _.each(this.fieldnames, function(e, i) {
92  this[e] = args[i];
93  }, this);
94 };
95 
96 // This pack function builds the header and produces a complete MAVLink message,
97 // including header and message CRC.
98 mavlink.message.prototype.pack = function(mav, crc_extra, payload) {
99 
100  this.payload = payload;
101  this.header = new mavlink.header(this.id, payload.length, mav.seq, mav.srcSystem, mav.srcComponent);
102  this.msgbuf = this.header.pack().concat(payload);
103  var crc = mavlink.x25Crc(this.msgbuf.slice(1));
104 
105  // For now, assume always using crc_extra = True. TODO: check/fix this.
106  crc = mavlink.x25Crc([crc_extra], crc);
107  this.msgbuf = this.msgbuf.concat(jspack.Pack('<H', [crc] ) );
108  return this.msgbuf;
109 
110 }
111 
112 """, {'FILELIST' : ",".join(args),
113  'PROTOCOL_MARKER' : xml.protocol_marker,
114  'crc_extra' : xml.crc_extra,
115  'WIRE_PROTOCOL_VERSION' : xml.wire_protocol_version })
116 
117 def generate_enums(outf, enums):
118  print("Generating enums")
119  outf.write("\n// enums\n")
120  wrapper = textwrap.TextWrapper(initial_indent="", subsequent_indent=" // ")
121  for e in enums:
122  outf.write("\n// %s\n" % e.name)
123  for entry in e.entry:
124  outf.write("mavlink.%s = %u // %s\n" % (entry.name, entry.value, wrapper.fill(entry.description)))
125 
126 def generate_message_ids(outf, msgs):
127  print("Generating message IDs")
128  outf.write("\n// message IDs\n")
129  outf.write("mavlink.MAVLINK_MSG_ID_BAD_DATA = -1\n")
130  for m in msgs:
131  outf.write("mavlink.MAVLINK_MSG_ID_%s = %u\n" % (m.name.upper(), m.id))
132 
133 def generate_classes(outf, msgs):
134  """
135  Generate the implementations of the classes representing MAVLink messages.
136 
137  """
138  print("Generating class definitions")
139  wrapper = textwrap.TextWrapper(initial_indent="", subsequent_indent="")
140  outf.write("\nmavlink.messages = {};\n\n");
141 
142  def field_descriptions(fields):
143  ret = ""
144  for f in fields:
145  ret += " %-18s : %s (%s)\n" % (f.name, f.description.strip(), f.type)
146  return ret
147 
148  for m in msgs:
149 
150  comment = "%s\n\n%s" % (wrapper.fill(m.description.strip()), field_descriptions(m.fields))
151 
152  selffieldnames = 'self, '
153  for f in m.fields:
154  # if f.omit_arg:
155  # selffieldnames += '%s=%s, ' % (f.name, f.const_value)
156  #else:
157  # -- Omitting the code above because it is rarely used (only once?) and would need some special handling
158  # in javascript. Specifically, inside the method definition, it needs to check for a value then assign
159  # a default.
160  selffieldnames += '%s, ' % f.name
161  selffieldnames = selffieldnames[:-2]
162 
163  sub = {'NAMELOWER' : m.name.lower(),
164  'SELFFIELDNAMES' : selffieldnames,
165  'COMMENT' : comment,
166  'FIELDNAMES' : ", ".join(m.fieldnames)}
167 
168  t.write(outf, """
169 /*
170 ${COMMENT}
171 */
172 """, sub)
173 
174  # function signature + declaration
175  outf.write("mavlink.messages.%s = function(" % (m.name.lower()))
176  if len(m.fields) != 0:
177  outf.write(", ".join(m.fieldnames))
178  outf.write(") {")
179 
180  # body: set message type properties
181  outf.write("""
182 
183  this.format = '%s';
184  this.id = mavlink.MAVLINK_MSG_ID_%s;
185  this.order_map = %s;
186  this.crc_extra = %u;
187  this.name = '%s';
188 
189 """ % (m.fmtstr, m.name.upper(), m.order_map, m.crc_extra, m.name.upper()))
190 
191  # body: set own properties
192  if len(m.fieldnames) != 0:
193  outf.write(" this.fieldnames = ['%s'];\n" % "', '".join(m.fieldnames))
194  outf.write("""
195 
196  this.set(arguments);
197 
198 }
199  """)
200 
201  # inherit methods from the base message class
202  outf.write("""
203 mavlink.messages.%s.prototype = new mavlink.message;
204 """ % m.name.lower())
205 
206  # Implement the pack() function for this message
207  outf.write("""
208 mavlink.messages.%s.prototype.pack = function(mav) {
209  return mavlink.message.prototype.pack.call(this, mav, this.crc_extra, jspack.Pack(this.format""" % m.name.lower())
210  if len(m.fields) != 0:
211  outf.write(", [ this." + ", this.".join(m.ordered_fieldnames) + ']')
212  outf.write("));\n}\n\n")
213 
214 def mavfmt(field):
215  '''work out the struct format for a type'''
216  map = {
217  'float' : 'f',
218  'double' : 'd',
219  'char' : 'c',
220  'int8_t' : 'b',
221  'uint8_t' : 'B',
222  'uint8_t_mavlink_version' : 'B',
223  'int16_t' : 'h',
224  'uint16_t' : 'H',
225  'int32_t' : 'i',
226  'uint32_t' : 'I',
227  'int64_t' : 'q',
228  'uint64_t' : 'Q',
229  }
230 
231  if field.array_length:
232  if field.type in ['char', 'int8_t', 'uint8_t']:
233  return str(field.array_length)+'s'
234  return str(field.array_length)+map[field.type]
235  return map[field.type]
236 
237 def generate_mavlink_class(outf, msgs, xml):
238  print("Generating MAVLink class")
239 
240  # Write mapper to enable decoding based on the integer message type
241  outf.write("\n\nmavlink.map = {\n");
242  for m in msgs:
243  outf.write(" %s: { format: '%s', type: mavlink.messages.%s, order_map: %s, crc_extra: %u },\n" % (
244  m.id, m.fmtstr, m.name.lower(), m.order_map, m.crc_extra))
245  outf.write("}\n\n")
246 
247  t.write(outf, """
248 
249 // Special mavlink message to capture malformed data packets for debugging
250 mavlink.messages.bad_data = function(data, reason) {
251  this.id = mavlink.MAVLINK_MSG_ID_BAD_DATA;
252  this.data = data;
253  this.reason = reason;
254  this.msgbuf = data;
255 }
256 
257 /* MAVLink protocol handling class */
258 MAVLink = function(logger, srcSystem, srcComponent) {
259 
260  this.logger = logger;
261 
262  this.seq = 0;
263  this.buf = new Buffer(0);
264  this.bufInError = new Buffer(0);
265 
266  this.srcSystem = (typeof srcSystem === 'undefined') ? 0 : srcSystem;
267  this.srcComponent = (typeof srcComponent === 'undefined') ? 0 : srcComponent;
268 
269  // The first packet we expect is a valid header, 6 bytes.
270  this.expected_length = 6;
271 
272  this.have_prefix_error = false;
273 
274  this.protocol_marker = 254;
275  this.little_endian = true;
276 
277  this.crc_extra = true;
278  this.sort_fields = true;
279  this.total_packets_sent = 0;
280  this.total_bytes_sent = 0;
281  this.total_packets_received = 0;
282  this.total_bytes_received = 0;
283  this.total_receive_errors = 0;
284  this.startup_time = Date.now();
285 
286 }
287 
288 // Implements EventEmitter
289 util.inherits(MAVLink, events.EventEmitter);
290 
291 // If the logger exists, this function will add a message to it.
292 // Assumes the logger is a winston object.
293 MAVLink.prototype.log = function(message) {
294  if(this.logger) {
295  this.logger.info(message);
296  }
297 }
298 
299 MAVLink.prototype.log = function(level, message) {
300  if(this.logger) {
301  this.logger.log(level, message);
302  }
303 }
304 
305 MAVLink.prototype.send = function(mavmsg) {
306  buf = mavmsg.pack(this);
307  this.file.write(buf);
308  this.seq = (this.seq + 1) % 256;
309  this.total_packets_sent +=1;
310  this.total_bytes_sent += buf.length;
311 }
312 
313 // return number of bytes needed for next parsing stage
314 MAVLink.prototype.bytes_needed = function() {
315  ret = this.expected_length - this.buf.length;
316  return ( ret <= 0 ) ? 1 : ret;
317 }
318 
319 // add data to the local buffer
320 MAVLink.prototype.pushBuffer = function(data) {
321  if(data) {
322  this.buf = Buffer.concat([this.buf, data]);
323  this.total_bytes_received += data.length;
324  }
325 }
326 
327 // Decode prefix. Elides the prefix.
328 MAVLink.prototype.parsePrefix = function() {
329 
330  // Test for a message prefix.
331  if( this.buf.length >= 1 && this.buf[0] != 254 ) {
332 
333  // Strip the offending initial byte and throw an error.
334  var badPrefix = this.buf[0];
335  this.bufInError = this.buf.slice(0,1);
336  this.buf = this.buf.slice(1);
337  this.expected_length = 6;
338 
339  // TODO: enable subsequent prefix error suppression if robust_parsing is implemented
340  //if(!this.have_prefix_error) {
341  // this.have_prefix_error = true;
342  throw new Error("Bad prefix ("+badPrefix+")");
343  //}
344 
345  }
346  //else if( this.buf.length >= 1 && this.buf[0] == 254 ) {
347  // this.have_prefix_error = false;
348  //}
349 
350 }
351 
352 // Determine the length. Leaves buffer untouched.
353 MAVLink.prototype.parseLength = function() {
354 
355  if( this.buf.length >= 2 ) {
356  var unpacked = jspack.Unpack('BB', this.buf.slice(0, 2));
357  this.expected_length = unpacked[1] + 8; // length of message + header + CRC
358  }
359 
360 }
361 
362 // input some data bytes, possibly returning a new message
363 MAVLink.prototype.parseChar = function(c) {
364 
365  var m = null;
366 
367  try {
368 
369  this.pushBuffer(c);
370  this.parsePrefix();
371  this.parseLength();
372  m = this.parsePayload();
373 
374  } catch(e) {
375 
376  this.log('error', e.message);
377  this.total_receive_errors += 1;
378  m = new mavlink.messages.bad_data(this.bufInError, e.message);
379  this.bufInError = new Buffer(0);
380 
381  }
382 
383  if(null != m) {
384  this.emit(m.name, m);
385  this.emit('message', m);
386  }
387 
388  return m;
389 
390 }
391 
392 MAVLink.prototype.parsePayload = function() {
393 
394  var m = null;
395 
396  // If we have enough bytes to try and read it, read it.
397  if( this.expected_length >= 8 && this.buf.length >= this.expected_length ) {
398 
399  // Slice off the expected packet length, reset expectation to be to find a header.
400  var mbuf = this.buf.slice(0, this.expected_length);
401  // TODO: slicing off the buffer should depend on the error produced by the decode() function
402  // - if a message we find a well formed message, cut-off the expected_length
403  // - if the message is not well formed (correct prefix by accident), cut-off 1 char only
404  this.buf = this.buf.slice(this.expected_length);
405  this.expected_length = 6;
406 
407  // w.info("Attempting to parse packet, message candidate buffer is ["+mbuf.toByteArray()+"]");
408 
409  try {
410  m = this.decode(mbuf);
411  this.total_packets_received += 1;
412  }
413  catch(e) {
414  // Set buffer in question and re-throw to generic error handling
415  this.bufInError = mbuf;
416  throw e;
417  }
418  }
419 
420  return m;
421 
422 }
423 
424 // input some data bytes, possibly returning an array of new messages
425 MAVLink.prototype.parseBuffer = function(s) {
426 
427  // Get a message, if one is available in the stream.
428  var m = this.parseChar(s);
429 
430  // No messages available, bail.
431  if ( null === m ) {
432  return null;
433  }
434 
435  // While more valid messages can be read from the existing buffer, add
436  // them to the array of new messages and return them.
437  var ret = [m];
438  while(true) {
439  m = this.parseChar();
440  if ( null === m ) {
441  // No more messages left.
442  return ret;
443  }
444  ret.push(m);
445  }
446  return ret;
447 
448 }
449 
450 /* decode a buffer as a MAVLink message */
451 MAVLink.prototype.decode = function(msgbuf) {
452 
453  var magic, mlen, seq, srcSystem, srcComponent, unpacked, msgId;
454 
455  // decode the header
456  try {
457  unpacked = jspack.Unpack('cBBBBB', msgbuf.slice(0, 6));
458  magic = unpacked[0];
459  mlen = unpacked[1];
460  seq = unpacked[2];
461  srcSystem = unpacked[3];
462  srcComponent = unpacked[4];
463  msgId = unpacked[5];
464  }
465  catch(e) {
466  throw new Error('Unable to unpack MAVLink header: ' + e.message);
467  }
468 
469  if (magic.charCodeAt(0) != 254) {
470  throw new Error("Invalid MAVLink prefix ("+magic.charCodeAt(0)+")");
471  }
472 
473  if( mlen != msgbuf.length - 8 ) {
474  throw new Error("Invalid MAVLink message length. Got " + (msgbuf.length - 8) + " expected " + mlen + ", msgId=" + msgId);
475  }
476 
477  if( false === _.has(mavlink.map, msgId) ) {
478  throw new Error("Unknown MAVLink message ID (" + msgId + ")");
479  }
480 
481  // decode the payload
482  // refs: (fmt, type, order_map, crc_extra) = mavlink.map[msgId]
483  var decoder = mavlink.map[msgId];
484 
485  // decode the checksum
486  try {
487  var receivedChecksum = jspack.Unpack('<H', msgbuf.slice(msgbuf.length - 2));
488  } catch (e) {
489  throw new Error("Unable to unpack MAVLink CRC: " + e.message);
490  }
491 
492  var messageChecksum = mavlink.x25Crc(msgbuf.slice(1, msgbuf.length - 2));
493 
494  // Assuming using crc_extra = True. See the message.prototype.pack() function.
495  messageChecksum = mavlink.x25Crc([decoder.crc_extra], messageChecksum);
496 
497  if ( receivedChecksum != messageChecksum ) {
498  throw new Error('invalid MAVLink CRC in msgID ' +msgId+ ', got 0x' + receivedChecksum + ' checksum, calculated payload checkum as 0x'+messageChecksum );
499  }
500 
501  // Decode the payload and reorder the fields to match the order map.
502  try {
503  var t = jspack.Unpack(decoder.format, msgbuf.slice(6, msgbuf.length));
504  }
505  catch (e) {
506  throw new Error('Unable to unpack MAVLink payload type='+decoder.type+' format='+decoder.format+' payloadLength='+ msgbuf.slice(6, -2).length +': '+ e.message);
507  }
508 
509  // Reorder the fields to match the order map
510  var args = [];
511  _.each(t, function(e, i, l) {
512  args[i] = t[decoder.order_map[i]]
513  });
514 
515  // construct the message object
516  try {
517  var m = new decoder.type(args);
518  m.set.call(m, args);
519  }
520  catch (e) {
521  throw new Error('Unable to instantiate MAVLink message of type '+decoder.type+' : ' + e.message);
522  }
523  m.msgbuf = msgbuf;
524  m.payload = msgbuf.slice(6);
525  m.crc = receivedChecksum;
526  m.header = new mavlink.header(msgId, mlen, seq, srcSystem, srcComponent);
527  this.log(m);
528  return m;
529 }
530 
531 """, xml)
532 
533 def generate_footer(outf):
534  t.write(outf, """
535 
536 // Expose this code as a module
537 module.exports = mavlink;
538 
539 """)
540 
541 def generate(basename, xml):
542  '''generate complete javascript implementation'''
543 
544  if basename.endswith('.js'):
545  filename = basename
546  else:
547  filename = basename + '.js'
548 
549  msgs = []
550  enums = []
551  filelist = []
552  for x in xml:
553  msgs.extend(x.message)
554  enums.extend(x.enum)
555  filelist.append(os.path.basename(x.filename))
556 
557  for m in msgs:
558  if xml[0].little_endian:
559  m.fmtstr = '<'
560  else:
561  m.fmtstr = '>'
562  for f in m.ordered_fields:
563  m.fmtstr += mavfmt(f)
564  m.order_map = [ 0 ] * len(m.fieldnames)
565  for i in range(0, len(m.fieldnames)):
566  m.order_map[i] = m.ordered_fieldnames.index(m.fieldnames[i])
567 
568  print("Generating %s" % filename)
569  outf = open(filename, "w")
570  generate_preamble(outf, msgs, filelist, xml[0])
571  generate_enums(outf, enums)
572  generate_message_ids(outf, msgs)
573  generate_classes(outf, msgs)
574  generate_mavlink_class(outf, msgs, xml[0])
575  generate_footer(outf)
576  outf.close()
577  print("Generated %s OK" % filename)


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Apr 7 2019 02:06:02