3 parse a MAVLink protocol XML file and generate a python implementation 5 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
20 print(
"Generating preamble")
23 MAVLink protocol implementation (auto-generated by mavgen.py) 25 Generated from: ${FILELIST} 27 Note: this file has been auto-generated. DO NOT EDIT 29 from __future__ import print_function 30 from builtins import range 31 from builtins import object 32 import struct, array, time, json, os, sys, platform 34 from ...generator.mavcrc import x25crc 37 WIRE_PROTOCOL_VERSION = '${WIRE_PROTOCOL_VERSION}' 38 DIALECT = '${DIALECT}' 40 PROTOCOL_MARKER_V1 = 0xFE 41 PROTOCOL_MARKER_V2 = 0xFD 45 MAVLINK_SIGNATURE_BLOCK_LEN = 13 47 MAVLINK_IFLAG_SIGNED = 0x01 49 native_supported = platform.system() != 'Windows' # Not yet supported on other dialects 50 native_force = 'MAVNATIVE_FORCE' in os.environ # Will force use of native code regardless of what client app wants 51 native_testing = 'MAVNATIVE_TESTING' in os.environ # Will force both native and legacy code to be used and their results compared 53 if native_supported and float(WIRE_PROTOCOL_VERSION) <= 1: 57 print('ERROR LOADING MAVNATIVE - falling back to python implementation') 58 native_supported = False 60 # mavnative isn't supported for MAVLink2 yet 61 native_supported = False 63 # some base types from mavlink_types.h 65 MAVLINK_TYPE_UINT8_T = 1 66 MAVLINK_TYPE_INT8_T = 2 67 MAVLINK_TYPE_UINT16_T = 3 68 MAVLINK_TYPE_INT16_T = 4 69 MAVLINK_TYPE_UINT32_T = 5 70 MAVLINK_TYPE_INT32_T = 6 71 MAVLINK_TYPE_UINT64_T = 7 72 MAVLINK_TYPE_INT64_T = 8 73 MAVLINK_TYPE_FLOAT = 9 74 MAVLINK_TYPE_DOUBLE = 10 77 class MAVLink_header(object): 78 '''MAVLink message header''' 79 def __init__(self, msgId, incompat_flags=0, compat_flags=0, mlen=0, seq=0, srcSystem=0, srcComponent=0): 82 self.srcSystem = srcSystem 83 self.srcComponent = srcComponent 85 self.incompat_flags = incompat_flags 86 self.compat_flags = compat_flags 88 def pack(self, force_mavlink1=False): 89 if WIRE_PROTOCOL_VERSION == '2.0' and not force_mavlink1: 90 return struct.pack('<BBBBBBBHB', ${PROTOCOL_MARKER}, self.mlen, 91 self.incompat_flags, self.compat_flags, 92 self.seq, self.srcSystem, self.srcComponent, 93 self.msgId&0xFFFF, self.msgId>>16) 94 return struct.pack('<BBBBBB', PROTOCOL_MARKER_V1, self.mlen, self.seq, 95 self.srcSystem, self.srcComponent, self.msgId) 97 class MAVLink_message(object): 98 '''base MAVLink message class''' 99 def __init__(self, msgId, name): 100 self._header = MAVLink_header(msgId) 104 self._fieldnames = [] 109 def format_attr(self, field): 110 '''override field getter''' 111 raw_attr = getattr(self,field) 112 if isinstance(raw_attr, bytes): 113 raw_attr = raw_attr.decode("utf-8").rstrip("\\00") 116 def get_msgbuf(self): 117 if isinstance(self._msgbuf, bytearray): 119 return bytearray(self._msgbuf) 121 def get_header(self): 124 def get_payload(self): 130 def get_fieldnames(self): 131 return self._fieldnames 137 return self._header.msgId 139 def get_srcSystem(self): 140 return self._header.srcSystem 142 def get_srcComponent(self): 143 return self._header.srcComponent 146 return self._header.seq 148 def get_signed(self): 151 def get_link_id(self): 155 ret = '%s {' % self._type 156 for a in self._fieldnames: 157 v = self.format_attr(a) 158 ret += '%s : %s, ' % (a, v) 159 ret = ret[0:-2] + '}' 162 def __ne__(self, other): 163 return not self.__eq__(other) 165 def __eq__(self, other): 169 if self.get_type() != other.get_type(): 172 # We do not compare CRC because native code doesn't provide it 173 #if self.get_crc() != other.get_crc(): 176 if self.get_seq() != other.get_seq(): 179 if self.get_srcSystem() != other.get_srcSystem(): 182 if self.get_srcComponent() != other.get_srcComponent(): 185 for a in self._fieldnames: 186 if self.format_attr(a) != other.format_attr(a): 193 d['mavpackettype'] = self._type 194 for a in self._fieldnames: 195 d[a] = self.format_attr(a) 199 return json.dumps(self.to_dict()) 201 def sign_packet(self, mav): 202 h = hashlib.new('sha256') 203 self._msgbuf += struct.pack('<BQ', mav.signing.link_id, mav.signing.timestamp)[:7] 204 h.update(mav.signing.secret_key) 205 h.update(self._msgbuf) 208 mav.signing.timestamp += 1 210 def pack(self, mav, crc_extra, payload, force_mavlink1=False): 212 if WIRE_PROTOCOL_VERSION != '1.0' and not force_mavlink1: 213 # in MAVLink2 we can strip trailing zeros off payloads. This allows for simple 214 # variable length arrays and smaller packets 215 while plen > 1 and payload[plen-1] == chr(0): 217 self._payload = payload[:plen] 219 if mav.signing.sign_outgoing: 220 incompat_flags |= MAVLINK_IFLAG_SIGNED 221 self._header = MAVLink_header(self._header.msgId, 222 incompat_flags=incompat_flags, compat_flags=0, 223 mlen=len(self._payload), seq=mav.seq, 224 srcSystem=mav.srcSystem, srcComponent=mav.srcComponent) 225 self._msgbuf = self._header.pack(force_mavlink1=force_mavlink1) + self._payload 226 crc = x25crc(self._msgbuf[1:]) 227 if ${crc_extra}: # using CRC extra 228 crc.accumulate_str(struct.pack('B', crc_extra)) 230 self._msgbuf += struct.pack('<H', self._crc) 231 if mav.signing.sign_outgoing and not force_mavlink1: 232 self.sign_packet(mav) 235 """, {
'FILELIST':
",".join(args),
236 'PROTOCOL_MARKER': xml.protocol_marker,
237 'DIALECT': os.path.splitext(os.path.basename(basename))[0],
238 'crc_extra': xml.crc_extra,
239 'WIRE_PROTOCOL_VERSION': xml.wire_protocol_version})
243 print(
"Generating enums")
247 class EnumEntry(object): 248 def __init__(self, name, description): 250 self.description = description 255 wrapper = textwrap.TextWrapper(initial_indent=
"", subsequent_indent=
" # ")
257 outf.write(
"\n# %s\n" % e.name)
258 outf.write(
"enums['%s'] = {}\n" % e.name)
259 for entry
in e.entry:
260 outf.write(
"%s = %u # %s\n" % (entry.name, entry.value, wrapper.fill(entry.description)))
261 outf.write(
"enums['%s'][%d] = EnumEntry('%s', '''%s''')\n" % (e.name,
262 int(entry.value), entry.name,
264 for param
in entry.param:
265 outf.write(
"enums['%s'][%d].param[%d] = '''%s'''\n" % (e.name,
272 print(
"Generating message IDs")
273 outf.write(
"\n# message IDs\n")
274 outf.write(
"MAVLINK_MSG_ID_BAD_DATA = -1\n")
276 outf.write(
"MAVLINK_MSG_ID_%s = %u\n" % (m.name.upper(), m.id))
280 print(
"Generating class definitions")
281 wrapper = textwrap.TextWrapper(initial_indent=
" ", subsequent_indent=
" ")
283 classname =
"MAVLink_%s_message" % m.name.lower()
284 fieldname_str =
", ".join([
"'%s'" % s
for s
in m.fieldnames])
285 ordered_fieldname_str =
", ".join([
"'%s'" % s
for s
in m.ordered_fieldnames])
287 fieldtypes_str =
", ".join([
"'%s'" % s
for s
in m.fieldtypes])
289 class %s(MAVLink_message): 293 id = MAVLINK_MSG_ID_%s 296 ordered_fieldnames = [%s] 299 native_format = bytearray('%s', 'ascii') 304 unpacker = struct.Struct('%s') 306 def __init__(self""" % (classname, wrapper.fill(m.description.strip()),
310 ordered_fieldname_str,
319 for i
in range(len(m.fields)):
320 fname = m.fieldnames[i]
321 if m.extensions_start
is not None and i >= m.extensions_start:
322 fdefault = m.fielddefaults[i]
323 outf.write(
", %s=%s" % (fname, fdefault))
325 outf.write(
", %s" % fname)
327 outf.write(
" MAVLink_message.__init__(self, %s.id, %s.name)\n" % (classname, classname))
328 outf.write(
" self._fieldnames = %s.fieldnames\n" % (classname))
330 outf.write(
" self.%s = %s\n" % (f.name, f.name))
332 def pack(self, mav, force_mavlink1=False): 333 return MAVLink_message.pack(self, mav, %u, struct.pack('%s'""" % (m.crc_extra, m.fmtstr))
334 for field
in m.ordered_fields:
335 if (field.type !=
"char" and field.array_length > 1):
336 for i
in range(field.array_length):
337 outf.write(
", self.{0:s}[{1:d}]".format(field.name, i))
339 outf.write(
", self.{0:s}".format(field.name))
340 outf.write(
"), force_mavlink1=force_mavlink1)\n")
344 '''work out the struct format for a type (in a form expected by mavnative)''' 351 'uint8_t_mavlink_version':
'v',
359 return map[field.type]
363 '''work out the struct format for a type''' 370 'uint8_t_mavlink_version':
'B',
379 if field.array_length:
380 if field.type ==
'char':
381 return str(field.array_length)+
's' 382 return str(field.array_length)+map[field.type]
383 return map[field.type]
387 '''returns default value for field (as string) for mavlink2 extensions''' 388 if field.type ==
'char':
392 if field.array_length == 0:
394 return "[" +
",".join([default_value] * field.array_length) +
"]" 398 print(
"Generating MAVLink class")
400 outf.write(
"\n\nmavlink_map = {\n")
402 outf.write(
" MAVLINK_MSG_ID_%s : MAVLink_%s_message,\n" % (
403 m.name.upper(), m.name.lower()))
407 class MAVError(Exception): 408 '''MAVLink error class''' 409 def __init__(self, msg): 410 Exception.__init__(self, msg) 413 class MAVString(str): 414 '''NUL terminated string''' 415 def __init__(self, s): 418 i = self.find(chr(0)) 423 class MAVLink_bad_data(MAVLink_message): 425 a piece of bad data in a mavlink stream 427 def __init__(self, data, reason): 428 MAVLink_message.__init__(self, MAVLINK_MSG_ID_BAD_DATA, 'BAD_DATA') 429 self._fieldnames = ['data', 'reason'] 435 '''Override the __str__ function from MAVLink_messages because non-printable characters are common in to be the reason for this message to exist.''' 436 return '%s {%s, data:%s}' % (self._type, self.reason, [('%x' % ord(i) if isinstance(i, str) else '%x' % i) for i in self.data]) 438 class MAVLinkSigning(object): 439 '''MAVLink signing state class''' 441 self.secret_key = None 444 self.sign_outgoing = False 445 self.allow_unsigned_callback = None 446 self.stream_timestamps = {} 448 self.badsig_count = 0 449 self.goodsig_count = 0 450 self.unsigned_count = 0 451 self.reject_count = 0 453 class MAVLink(object): 454 '''MAVLink protocol handling class''' 455 def __init__(self, file, srcSystem=0, srcComponent=0, use_native=False): 458 self.srcSystem = srcSystem 459 self.srcComponent = srcComponent 461 self.callback_args = None 462 self.callback_kwargs = None 463 self.send_callback = None 464 self.send_callback_args = None 465 self.send_callback_kwargs = None 466 self.buf = bytearray() 468 self.expected_length = HEADER_LEN_V1+2 469 self.have_prefix_error = False 470 self.robust_parsing = False 471 self.protocol_marker = ${protocol_marker} 472 self.little_endian = ${little_endian} 473 self.crc_extra = ${crc_extra} 474 self.sort_fields = ${sort_fields} 475 self.total_packets_sent = 0 476 self.total_bytes_sent = 0 477 self.total_packets_received = 0 478 self.total_bytes_received = 0 479 self.total_receive_errors = 0 480 self.startup_time = time.time() 481 self.signing = MAVLinkSigning() 482 if native_supported and (use_native or native_testing or native_force): 483 print("NOTE: mavnative is currently beta-test code") 484 self.native = mavnative.NativeConnection(MAVLink_message, mavlink_map) 488 self.test_buf = bytearray() 489 self.mav20_unpacker = struct.Struct('<cBBBBBBHB') 490 self.mav10_unpacker = struct.Struct('<cBBBBB') 491 self.mav20_h3_unpacker = struct.Struct('BBB') 492 self.mav_csum_unpacker = struct.Struct('<H') 493 self.mav_sign_unpacker = struct.Struct('<IH') 495 def set_callback(self, callback, *args, **kwargs): 496 self.callback = callback 497 self.callback_args = args 498 self.callback_kwargs = kwargs 500 def set_send_callback(self, callback, *args, **kwargs): 501 self.send_callback = callback 502 self.send_callback_args = args 503 self.send_callback_kwargs = kwargs 505 def send(self, mavmsg, force_mavlink1=False): 506 '''send a MAVLink message''' 507 buf = mavmsg.pack(self, force_mavlink1=force_mavlink1) 509 self.seq = (self.seq + 1) % 256 510 self.total_packets_sent += 1 511 self.total_bytes_sent += len(buf) 512 if self.send_callback: 513 self.send_callback(mavmsg, *self.send_callback_args, **self.send_callback_kwargs) 516 return len(self.buf) - self.buf_index 518 def bytes_needed(self): 519 '''return number of bytes needed for next parsing stage''' 521 ret = self.native.expected_length - self.buf_len() 523 ret = self.expected_length - self.buf_len() 529 def __parse_char_native(self, c): 530 '''this method exists only to see in profiling results''' 531 m = self.native.parse_chars(c) 534 def __callbacks(self, msg): 535 '''this method exists only to make profiling results easier to read''' 537 self.callback(msg, *self.callback_args, **self.callback_kwargs) 539 def parse_char(self, c): 540 '''input some data bytes, possibly returning a new message''' 543 self.total_bytes_received += len(c) 547 self.test_buf.extend(c) 548 m = self.__parse_char_native(self.test_buf) 549 m2 = self.__parse_char_legacy() 551 print("Native: %s\\nLegacy: %s\\n" % (m, m2)) 552 raise Exception('Native vs. Legacy mismatch') 554 m = self.__parse_char_native(self.buf) 556 m = self.__parse_char_legacy() 559 self.total_packets_received += 1 562 # XXX The idea here is if we've read something and there's nothing left in 563 # the buffer, reset it to 0 which frees the memory 564 if self.buf_len() == 0 and self.buf_index != 0: 565 self.buf = bytearray() 570 def __parse_char_legacy(self): 571 '''input some data bytes, possibly returning a new message (uses no native code)''' 572 header_len = HEADER_LEN_V1 573 if self.buf_len() >= 1 and self.buf[self.buf_index] == PROTOCOL_MARKER_V2: 574 header_len = HEADER_LEN_V2 576 if self.buf_len() >= 1 and self.buf[self.buf_index] != PROTOCOL_MARKER_V1 and self.buf[self.buf_index] != PROTOCOL_MARKER_V2: 577 magic = self.buf[self.buf_index] 579 if self.robust_parsing: 580 m = MAVLink_bad_data(bytearray([magic]), 'Bad prefix') 581 self.expected_length = header_len+2 582 self.total_receive_errors += 1 584 if self.have_prefix_error: 586 self.have_prefix_error = True 587 self.total_receive_errors += 1 588 raise MAVError("invalid MAVLink prefix '%s'" % magic) 589 self.have_prefix_error = False 590 if self.buf_len() >= 3: 591 sbuf = self.buf[self.buf_index:3+self.buf_index] 592 if sys.version_info.major < 3: 594 (magic, self.expected_length, incompat_flags) = self.mav20_h3_unpacker.unpack(sbuf) 595 if magic == PROTOCOL_MARKER_V2 and (incompat_flags & MAVLINK_IFLAG_SIGNED): 596 self.expected_length += MAVLINK_SIGNATURE_BLOCK_LEN 597 self.expected_length += header_len + 2 598 if self.expected_length >= (header_len+2) and self.buf_len() >= self.expected_length: 599 mbuf = array.array('B', self.buf[self.buf_index:self.buf_index+self.expected_length]) 600 self.buf_index += self.expected_length 601 self.expected_length = header_len+2 602 if self.robust_parsing: 604 if magic == PROTOCOL_MARKER_V2 and (incompat_flags & ~MAVLINK_IFLAG_SIGNED) != 0: 605 raise MAVError('invalid incompat_flags 0x%x 0x%x %u' % (incompat_flags, magic, self.expected_length)) 606 m = self.decode(mbuf) 607 except MAVError as reason: 608 m = MAVLink_bad_data(mbuf, reason.message) 609 self.total_receive_errors += 1 611 if magic == PROTOCOL_MARKER_V2 and (incompat_flags & ~MAVLINK_IFLAG_SIGNED) != 0: 612 raise MAVError('invalid incompat_flags 0x%x 0x%x %u' % (incompat_flags, magic, self.expected_length)) 613 m = self.decode(mbuf) 617 def parse_buffer(self, s): 618 '''input some data bytes, possibly returning a list of new messages''' 619 m = self.parse_char(s) 624 m = self.parse_char("") 630 def check_signature(self, msgbuf, srcSystem, srcComponent): 631 '''check signature on incoming message''' 632 if isinstance(msgbuf, array.array): 633 msgbuf = msgbuf.tostring() 634 timestamp_buf = msgbuf[-12:-6] 635 link_id = msgbuf[-13] 636 (tlow, thigh) = self.mav_sign_unpacker.unpack(timestamp_buf) 637 timestamp = tlow + (thigh<<32) 639 # see if the timestamp is acceptable 640 stream_key = (link_id,srcSystem,srcComponent) 641 if stream_key in self.signing.stream_timestamps: 642 if timestamp <= self.signing.stream_timestamps[stream_key]: 643 # reject old timestamp 644 # print('old timestamp') 647 # a new stream has appeared. Accept the timestamp if it is at most 648 # one minute behind our current timestamp 649 if timestamp + 6000*1000 < self.signing.timestamp: 650 # print('bad new stream ', timestamp/(100.0*1000*60*60*24*365), self.signing.timestamp/(100.0*1000*60*60*24*365)) 652 self.signing.stream_timestamps[stream_key] = timestamp 653 # print('new stream') 655 h = hashlib.new('sha256') 656 h.update(self.signing.secret_key) 657 h.update(msgbuf[:-6]) 658 sig1 = str(h.digest())[:6] 659 sig2 = str(msgbuf)[-6:] 661 # print('sig mismatch') 664 # the timestamp we next send with is the max of the received timestamp and 665 # our current timestamp 666 self.signing.timestamp = max(self.signing.timestamp, timestamp) 669 def decode(self, msgbuf): 670 '''decode a buffer as a MAVLink message''' 672 if msgbuf[0] != PROTOCOL_MARKER_V1: 675 magic, mlen, incompat_flags, compat_flags, seq, srcSystem, srcComponent, msgIdlow, msgIdhigh = self.mav20_unpacker.unpack(msgbuf[:headerlen]) 676 except struct.error as emsg: 677 raise MAVError('Unable to unpack MAVLink header: %s' % emsg) 678 msgId = msgIdlow | (msgIdhigh<<16) 683 magic, mlen, seq, srcSystem, srcComponent, msgId = self.mav10_unpacker.unpack(msgbuf[:headerlen]) 686 except struct.error as emsg: 687 raise MAVError('Unable to unpack MAVLink header: %s' % emsg) 689 if (incompat_flags & MAVLINK_IFLAG_SIGNED) != 0: 690 signature_len = MAVLINK_SIGNATURE_BLOCK_LEN 694 if ord(magic) != PROTOCOL_MARKER_V1 and ord(magic) != PROTOCOL_MARKER_V2: 695 raise MAVError("invalid MAVLink prefix '%s'" % magic) 696 if mlen != len(msgbuf)-(headerlen+2+signature_len): 697 raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u headerlen=%u' % (len(msgbuf)-(headerlen+2+signature_len), mlen, msgId, headerlen)) 699 if not mapkey in mavlink_map: 700 raise MAVError('unknown MAVLink message ID %s' % str(mapkey)) 703 type = mavlink_map[mapkey] 705 order_map = type.orders 706 len_map = type.lengths 707 crc_extra = type.crc_extra 709 # decode the checksum 711 crc, = self.mav_csum_unpacker.unpack(msgbuf[-(2+signature_len):][:2]) 712 except struct.error as emsg: 713 raise MAVError('Unable to unpack MAVLink CRC: %s' % emsg) 714 crcbuf = msgbuf[1:-(2+signature_len)] 715 if ${crc_extra}: # using CRC extra 716 crcbuf.append(crc_extra) 717 crc2 = x25crc(crcbuf) 719 raise MAVError('invalid MAVLink CRC in msgID %u 0x%04x should be 0x%04x' % (msgId, crc, crc2.crc)) 722 if signature_len == MAVLINK_SIGNATURE_BLOCK_LEN: 723 self.signing.sig_count += 1 724 if self.signing.secret_key is not None: 725 accept_signature = False 726 if signature_len == MAVLINK_SIGNATURE_BLOCK_LEN: 727 sig_ok = self.check_signature(msgbuf, srcSystem, srcComponent) 728 accept_signature = sig_ok 730 self.signing.goodsig_count += 1 732 self.signing.badsig_count += 1 733 if not accept_signature and self.signing.allow_unsigned_callback is not None: 734 accept_signature = self.signing.allow_unsigned_callback(self, msgId) 736 self.signing.unsigned_count += 1 738 self.signing.reject_count += 1 739 elif self.signing.allow_unsigned_callback is not None: 740 accept_signature = self.signing.allow_unsigned_callback(self, msgId) 742 self.signing.unsigned_count += 1 744 self.signing.reject_count += 1 745 if not accept_signature: 746 raise MAVError('Invalid signature') 748 csize = type.unpacker.size 749 mbuf = msgbuf[headerlen:-(2+signature_len)] 750 if len(mbuf) < csize: 751 # zero pad to give right size 752 mbuf.extend([0]*(csize - len(mbuf))) 753 if len(mbuf) < csize: 754 raise MAVError('Bad message of type %s length %u needs %s' % ( 755 type, len(mbuf), csize)) 758 t = type.unpacker.unpack(mbuf) 759 except struct.error as emsg: 760 raise MAVError('Unable to unpack MAVLink payload type=%s fmt=%s payloadLength=%u: %s' % ( 761 type, fmt, len(mbuf), emsg)) 764 # handle sorted fields 767 if sum(len_map) == len(len_map): 768 # message has no arrays in it 769 for i in range(0, len(tlist)): 770 tlist[i] = t[order_map[i]] 772 # message has some arrays 774 for i in range(0, len(order_map)): 777 tip = sum(len_map[:order]) 779 if L == 1 or isinstance(field, str): 782 tlist.append(t[tip:(tip + L)]) 784 # terminate any strings 785 for i in range(0, len(tlist)): 786 if type.fieldtypes[i] == 'char': 787 if sys.version_info.major >= 3: 788 tlist[i] = tlist[i].decode('utf-8') 789 tlist[i] = str(MAVString(tlist[i])) 791 # construct the message object 794 except Exception as emsg: 795 raise MAVError('Unable to instantiate MAVLink message of type %s : %s' % (type, emsg)) 798 m._link_id = msgbuf[-13] 800 m._payload = msgbuf[6:-(2+signature_len)] 802 m._header = MAVLink_header(msgId, incompat_flags, compat_flags, mlen, seq, srcSystem, srcComponent) 808 print(
"Generating methods")
810 def field_descriptions(fields):
815 field_info +=
"%s " % f.units
816 field_info +=
"(type:%s" % f.type
818 field_info +=
", values:%s" % f.enum
820 ret +=
" %-18s : %s %s\n" % (f.name, f.description.strip(), field_info)
823 wrapper = textwrap.TextWrapper(initial_indent=
"", subsequent_indent=
" ")
826 comment =
"%s\n\n%s" % (wrapper.fill(m.description.strip()), field_descriptions(m.fields))
828 selffieldnames =
'self, ' 829 for i
in range(len(m.fields)):
832 selffieldnames +=
'%s=%s, ' % (f.name, f.const_value)
833 elif m.extensions_start
is not None and i >= m.extensions_start:
834 fdefault = m.fielddefaults[i]
835 selffieldnames +=
"%s=%s, " % (f.name, fdefault)
837 selffieldnames +=
'%s, ' % f.name
838 selffieldnames = selffieldnames[:-2]
840 sub = {
'NAMELOWER': m.name.lower(),
841 'SELFFIELDNAMES': selffieldnames,
843 'FIELDNAMES':
", ".join(m.fieldnames)}
846 def ${NAMELOWER}_encode(${SELFFIELDNAMES}): 850 return MAVLink_${NAMELOWER}_message(${FIELDNAMES}) 855 def ${NAMELOWER}_send(${SELFFIELDNAMES}, force_mavlink1=False): 859 return self.send(self.${NAMELOWER}_encode(${FIELDNAMES}), force_mavlink1=force_mavlink1) 865 '''generate complete python implementation''' 866 if basename.endswith(
'.py'):
869 filename = basename +
'.py' 875 msgs.extend(x.message)
877 filelist.append(os.path.basename(x.filename))
881 if xml[0].little_endian:
885 m.native_fmtstr = m.fmtstr
886 for f
in m.ordered_fields:
890 m.order_map = [0] * len(m.fieldnames)
891 m.len_map = [0] * len(m.fieldnames)
892 m.array_len_map = [0] * len(m.fieldnames)
893 for i
in range(0, len(m.fieldnames)):
894 m.order_map[i] = m.ordered_fieldnames.index(m.fieldnames[i])
895 m.array_len_map[i] = m.ordered_fields[i].array_length
896 for i
in range(0, len(m.fieldnames)):
898 m.len_map[n] = m.fieldlengths[i]
900 print(
"Generating %s" % filename)
901 outf = open(filename,
"w")
909 print(
"Generated %s OK" % filename)
def generate_message_ids(outf, msgs)
def generate_classes(outf, msgs)
def generate_enums(outf, enums)
def generate_preamble(outf, msgs, basename, args, xml)
def generate_methods(outf, msgs)
def generate_mavlink_class(outf, msgs, xml)
def generate(basename, xml)