3 parse a MAVLink protocol XML file and generate a Node.js javascript module implementation 5 Based on original work Copyright Andrew Tridgell 2011 6 Released under GNU GPL version 3 or later 8 from __future__
import print_function
10 from builtins
import range
14 from .
import mavtemplate
19 print(
"Generating preamble")
22 MAVLink protocol implementation for node.js (auto-generated by mavgen_javascript.py) 24 Generated from: ${FILELIST} 26 Note: this file has been auto-generated. DO NOT EDIT 29 jspack = require("jspack").jspack, 30 _ = require("underscore"), 31 events = require("events"), 32 util = require("util"); 34 // Add a convenience method to Buffer 35 Buffer.prototype.toByteArray = function () { 36 return Array.prototype.slice.call(this, 0) 39 mavlink = function(){}; 41 // Implement the X25CRC function (present in the Python version through the mavutil.py package) 42 mavlink.x25Crc = function(buffer, crc) { 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); 56 mavlink.WIRE_PROTOCOL_VERSION = "${WIRE_PROTOCOL_VERSION}"; 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 70 // Mavlink headers incorporate sequence, source system (platform) and source component. 71 mavlink.header = function(msgId, mlen, seq, srcSystem, srcComponent) { 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; 81 mavlink.header.prototype.pack = function() { 82 return jspack.Pack('BBBBBB', [${PROTOCOL_MARKER}, this.mlen, this.seq, this.srcSystem, this.srcComponent, this.msgId]); 85 // Base class declaration: mavlink.message will be the parent class for each 86 // concrete implementation in mavlink.messages. 87 mavlink.message = function() {}; 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) { 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) { 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)); 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] ) ); 112 """, {
'FILELIST' :
",".join(args),
113 'PROTOCOL_MARKER' : xml.protocol_marker,
114 'crc_extra' : xml.crc_extra,
115 'WIRE_PROTOCOL_VERSION' : xml.wire_protocol_version })
118 print(
"Generating enums")
119 outf.write(
"\n// enums\n")
120 wrapper = textwrap.TextWrapper(initial_indent=
"", subsequent_indent=
" // ")
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)))
127 print(
"Generating message IDs")
128 outf.write(
"\n// message IDs\n")
129 outf.write(
"mavlink.MAVLINK_MSG_ID_BAD_DATA = -1\n")
131 outf.write(
"mavlink.MAVLINK_MSG_ID_%s = %u\n" % (m.name.upper(), m.id))
135 Generate the implementations of the classes representing MAVLink messages. 138 print(
"Generating class definitions")
139 wrapper = textwrap.TextWrapper(initial_indent=
"", subsequent_indent=
"")
140 outf.write(
"\nmavlink.messages = {};\n\n");
142 def field_descriptions(fields):
145 ret +=
" %-18s : %s (%s)\n" % (f.name, f.description.strip(), f.type)
150 comment =
"%s\n\n%s" % (wrapper.fill(m.description.strip()), field_descriptions(m.fields))
152 selffieldnames =
'self, ' 160 selffieldnames +=
'%s, ' % f.name
161 selffieldnames = selffieldnames[:-2]
163 sub = {
'NAMELOWER' : m.name.lower(),
164 'SELFFIELDNAMES' : selffieldnames,
166 'FIELDNAMES' :
", ".join(m.fieldnames)}
175 outf.write(
"mavlink.messages.%s = function(" % (m.name.lower()))
176 if len(m.fields) != 0:
177 outf.write(
", ".join(m.fieldnames))
184 this.id = mavlink.MAVLINK_MSG_ID_%s; 189 """ % (m.fmtstr, m.name.upper(), m.order_map, m.crc_extra, m.name.upper()))
192 if len(m.fieldnames) != 0:
193 outf.write(
" this.fieldnames = ['%s'];\n" %
"', '".join(m.fieldnames))
203 mavlink.messages.%s.prototype = new mavlink.message; 204 """ % m.name.lower())
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")
215 '''work out the struct format for a type''' 222 'uint8_t_mavlink_version' :
'B',
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]
238 print(
"Generating MAVLink class")
241 outf.write(
"\n\nmavlink.map = {\n");
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))
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; 253 this.reason = reason; 257 /* MAVLink protocol handling class */ 258 MAVLink = function(logger, srcSystem, srcComponent) { 260 this.logger = logger; 263 this.buf = new Buffer(0); 264 this.bufInError = new Buffer(0); 266 this.srcSystem = (typeof srcSystem === 'undefined') ? 0 : srcSystem; 267 this.srcComponent = (typeof srcComponent === 'undefined') ? 0 : srcComponent; 269 // The first packet we expect is a valid header, 6 bytes. 270 this.expected_length = 6; 272 this.have_prefix_error = false; 274 this.protocol_marker = 254; 275 this.little_endian = true; 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(); 288 // Implements EventEmitter 289 util.inherits(MAVLink, events.EventEmitter); 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) { 295 this.logger.info(message); 299 MAVLink.prototype.log = function(level, message) { 301 this.logger.log(level, message); 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; 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; 319 // add data to the local buffer 320 MAVLink.prototype.pushBuffer = function(data) { 322 this.buf = Buffer.concat([this.buf, data]); 323 this.total_bytes_received += data.length; 327 // Decode prefix. Elides the prefix. 328 MAVLink.prototype.parsePrefix = function() { 330 // Test for a message prefix. 331 if( this.buf.length >= 1 && this.buf[0] != 254 ) { 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; 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+")"); 346 //else if( this.buf.length >= 1 && this.buf[0] == 254 ) { 347 // this.have_prefix_error = false; 352 // Determine the length. Leaves buffer untouched. 353 MAVLink.prototype.parseLength = function() { 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 362 // input some data bytes, possibly returning a new message 363 MAVLink.prototype.parseChar = function(c) { 372 m = this.parsePayload(); 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); 384 this.emit(m.name, m); 385 this.emit('message', m); 392 MAVLink.prototype.parsePayload = function() { 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 ) { 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; 407 // w.info("Attempting to parse packet, message candidate buffer is ["+mbuf.toByteArray()+"]"); 410 m = this.decode(mbuf); 411 this.total_packets_received += 1; 414 // Set buffer in question and re-throw to generic error handling 415 this.bufInError = mbuf; 424 // input some data bytes, possibly returning an array of new messages 425 MAVLink.prototype.parseBuffer = function(s) { 427 // Get a message, if one is available in the stream. 428 var m = this.parseChar(s); 430 // No messages available, bail. 435 // While more valid messages can be read from the existing buffer, add 436 // them to the array of new messages and return them. 439 m = this.parseChar(); 441 // No more messages left. 450 /* decode a buffer as a MAVLink message */ 451 MAVLink.prototype.decode = function(msgbuf) { 453 var magic, mlen, seq, srcSystem, srcComponent, unpacked, msgId; 457 unpacked = jspack.Unpack('cBBBBB', msgbuf.slice(0, 6)); 461 srcSystem = unpacked[3]; 462 srcComponent = unpacked[4]; 466 throw new Error('Unable to unpack MAVLink header: ' + e.message); 469 if (magic.charCodeAt(0) != 254) { 470 throw new Error("Invalid MAVLink prefix ("+magic.charCodeAt(0)+")"); 473 if( mlen != msgbuf.length - 8 ) { 474 throw new Error("Invalid MAVLink message length. Got " + (msgbuf.length - 8) + " expected " + mlen + ", msgId=" + msgId); 477 if( false === _.has(mavlink.map, msgId) ) { 478 throw new Error("Unknown MAVLink message ID (" + msgId + ")"); 481 // decode the payload 482 // refs: (fmt, type, order_map, crc_extra) = mavlink.map[msgId] 483 var decoder = mavlink.map[msgId]; 485 // decode the checksum 487 var receivedChecksum = jspack.Unpack('<H', msgbuf.slice(msgbuf.length - 2)); 489 throw new Error("Unable to unpack MAVLink CRC: " + e.message); 492 var messageChecksum = mavlink.x25Crc(msgbuf.slice(1, msgbuf.length - 2)); 494 // Assuming using crc_extra = True. See the message.prototype.pack() function. 495 messageChecksum = mavlink.x25Crc([decoder.crc_extra], messageChecksum); 497 if ( receivedChecksum != messageChecksum ) { 498 throw new Error('invalid MAVLink CRC in msgID ' +msgId+ ', got 0x' + receivedChecksum + ' checksum, calculated payload checkum as 0x'+messageChecksum ); 501 // Decode the payload and reorder the fields to match the order map. 503 var t = jspack.Unpack(decoder.format, msgbuf.slice(6, msgbuf.length)); 506 throw new Error('Unable to unpack MAVLink payload type='+decoder.type+' format='+decoder.format+' payloadLength='+ msgbuf.slice(6, -2).length +': '+ e.message); 509 // Reorder the fields to match the order map 511 _.each(t, function(e, i, l) { 512 args[i] = t[decoder.order_map[i]] 515 // construct the message object 517 var m = new decoder.type(args); 521 throw new Error('Unable to instantiate MAVLink message of type '+decoder.type+' : ' + e.message); 524 m.payload = msgbuf.slice(6); 525 m.crc = receivedChecksum; 526 m.header = new mavlink.header(msgId, mlen, seq, srcSystem, srcComponent); 536 // Expose this code as a module 537 module.exports = mavlink; 542 '''generate complete javascript implementation''' 544 if basename.endswith(
'.js'):
547 filename = basename +
'.js' 553 msgs.extend(x.message)
555 filelist.append(os.path.basename(x.filename))
558 if xml[0].little_endian:
562 for f
in m.ordered_fields:
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])
568 print(
"Generating %s" % filename)
569 outf = open(filename,
"w")
577 print(
"Generated %s OK" % filename)
def generate_message_ids(outf, msgs)
def generate_classes(outf, msgs)
def generate_mavlink_class(outf, msgs, xml)
def generate_enums(outf, enums)
def generate_footer(outf)
def generate(basename, xml)
def generate_preamble(outf, msgs, args, xml)