mavparse.py 22 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563
  1. #!/usr/bin/env python
  2. '''
  3. mavlink python parse functions
  4. Copyright Andrew Tridgell 2011
  5. Released under GNU GPL version 3 or later
  6. '''
  7. from __future__ import print_function
  8. from builtins import range
  9. from builtins import object
  10. import errno
  11. import operator
  12. import os
  13. import sys
  14. import time
  15. import xml.parsers.expat
  16. PROTOCOL_0_9 = "0.9"
  17. PROTOCOL_1_0 = "1.0"
  18. PROTOCOL_2_0 = "2.0"
  19. # message flags
  20. FLAG_HAVE_TARGET_SYSTEM = 1
  21. FLAG_HAVE_TARGET_COMPONENT = 2
  22. class MAVParseError(Exception):
  23. def __init__(self, message, inner_exception=None):
  24. self.message = message
  25. self.inner_exception = inner_exception
  26. self.exception_info = sys.exc_info()
  27. def __str__(self):
  28. return self.message
  29. class MAVField(object):
  30. def __init__(self, name, type, print_format, xml, description='', enum='', display='', units=''):
  31. self.name = name
  32. self.name_upper = name.upper()
  33. self.description = description
  34. self.array_length = 0
  35. self.enum = enum
  36. self.display = display
  37. self.units = units
  38. self.omit_arg = False
  39. self.const_value = None
  40. self.print_format = print_format
  41. lengths = {
  42. 'float' : 4,
  43. 'double' : 8,
  44. 'char' : 1,
  45. 'int8_t' : 1,
  46. 'uint8_t' : 1,
  47. 'uint8_t_mavlink_version' : 1,
  48. 'int16_t' : 2,
  49. 'uint16_t' : 2,
  50. 'int32_t' : 4,
  51. 'uint32_t' : 4,
  52. 'int64_t' : 8,
  53. 'uint64_t' : 8,
  54. }
  55. if type=='uint8_t_mavlink_version':
  56. type = 'uint8_t'
  57. self.omit_arg = True
  58. self.const_value = xml.version
  59. aidx = type.find("[")
  60. if aidx != -1:
  61. assert type[-1:] == ']'
  62. self.array_length = int(type[aidx+1:-1])
  63. type = type[0:aidx]
  64. if type == 'array':
  65. type = 'int8_t'
  66. if type in lengths:
  67. self.type_length = lengths[type]
  68. self.type = type
  69. elif (type+"_t") in lengths:
  70. self.type_length = lengths[type+"_t"]
  71. self.type = type+'_t'
  72. else:
  73. raise MAVParseError("unknown type '%s'" % type)
  74. if self.array_length != 0:
  75. self.wire_length = self.array_length * self.type_length
  76. else:
  77. self.wire_length = self.type_length
  78. self.type_upper = self.type.upper()
  79. def gen_test_value(self, i):
  80. '''generate a testsuite value for a MAVField'''
  81. if self.const_value:
  82. return self.const_value
  83. elif self.type == 'float':
  84. return 17.0 + self.wire_offset*7 + i
  85. elif self.type == 'double':
  86. return 123.0 + self.wire_offset*7 + i
  87. elif self.type == 'char':
  88. return chr(ord('A') + (self.wire_offset + i)%26)
  89. elif self.type in [ 'int8_t', 'uint8_t' ]:
  90. return (5 + self.wire_offset*67 + i) & 0xFF
  91. elif self.type in ['int16_t', 'uint16_t']:
  92. return (17235 + self.wire_offset*52 + i) & 0xFFFF
  93. elif self.type in ['int32_t', 'uint32_t']:
  94. return (963497464 + self.wire_offset*52 + i)&0xFFFFFFFF
  95. elif self.type in ['int64_t', 'uint64_t']:
  96. return 93372036854775807 + self.wire_offset*63 + i
  97. else:
  98. raise MAVParseError('unknown type %s' % self.type)
  99. def set_test_value(self):
  100. '''set a testsuite value for a MAVField'''
  101. if self.array_length:
  102. self.test_value = []
  103. for i in range(self.array_length):
  104. self.test_value.append(self.gen_test_value(i))
  105. else:
  106. self.test_value = self.gen_test_value(0)
  107. if self.type == 'char' and self.array_length:
  108. v = ""
  109. for c in self.test_value:
  110. v += c
  111. self.test_value = v[:-1]
  112. class MAVType(object):
  113. def __init__(self, name, id, linenumber, description=''):
  114. self.name = name
  115. self.name_lower = name.lower()
  116. self.linenumber = linenumber
  117. self.id = int(id)
  118. self.description = description
  119. self.fields = []
  120. self.fieldnames = []
  121. self.extensions_start = None
  122. def base_fields(self):
  123. '''return number of non-extended fields'''
  124. if self.extensions_start is None:
  125. return len(self.fields)
  126. return len(self.fields[:self.extensions_start])
  127. class MAVEnumParam(object):
  128. def __init__(self, index, description='', label='', units='', enum='', increment='', minValue='', maxValue='', reserved=False, default=''):
  129. self.index = index
  130. self.description = description
  131. self.label = label
  132. self.units = units
  133. self.enum = enum
  134. self.increment = increment
  135. self.minValue = minValue
  136. self.maxValue = maxValue
  137. self.reserved = reserved
  138. self.default = default
  139. if self.reserved and not self.default:
  140. self.default = '0'
  141. self.set_description(description)
  142. def set_description(self, description):
  143. if not description.strip() and self.reserved:
  144. self.description = 'Reserved (default:%s)' % self.default
  145. else:
  146. self.description = description
  147. class MAVEnumEntry(object):
  148. def __init__(self, name, value, description='', end_marker=False, autovalue=False, origin_file='', origin_line=0):
  149. self.name = name
  150. self.value = value
  151. self.description = description
  152. self.param = []
  153. self.end_marker = end_marker
  154. self.autovalue = autovalue # True if value was *not* specified in XML
  155. self.origin_file = origin_file
  156. self.origin_line = origin_line
  157. class MAVEnum(object):
  158. def __init__(self, name, linenumber, description=''):
  159. self.name = name
  160. self.description = description
  161. self.entry = []
  162. self.start_value = None
  163. self.highest_value = 0
  164. self.linenumber = linenumber
  165. class MAVXML(object):
  166. '''parse a mavlink XML file'''
  167. def __init__(self, filename, wire_protocol_version=PROTOCOL_0_9):
  168. self.filename = filename
  169. self.basename = os.path.basename(filename)
  170. if self.basename.lower().endswith(".xml"):
  171. self.basename = self.basename[:-4]
  172. self.basename_upper = self.basename.upper()
  173. self.message = []
  174. self.enum = []
  175. # we use only the day for the parse_time, as otherwise
  176. # it causes a lot of unnecessary cache misses with ccache
  177. self.parse_time = time.strftime("%a %b %d %Y")
  178. self.version = 2
  179. self.include = []
  180. self.wire_protocol_version = wire_protocol_version
  181. # setup the protocol features for the requested protocol version
  182. if wire_protocol_version == PROTOCOL_0_9:
  183. self.protocol_marker = ord('U')
  184. self.sort_fields = False
  185. self.little_endian = False
  186. self.crc_extra = False
  187. self.crc_struct = False
  188. self.command_24bit = False
  189. self.allow_extensions = False
  190. elif wire_protocol_version == PROTOCOL_1_0:
  191. self.protocol_marker = 0xFE
  192. self.sort_fields = True
  193. self.little_endian = True
  194. self.crc_extra = True
  195. self.crc_struct = False
  196. self.command_24bit = False
  197. self.allow_extensions = False
  198. elif wire_protocol_version == PROTOCOL_2_0:
  199. self.protocol_marker = 0xFD
  200. self.sort_fields = True
  201. self.little_endian = True
  202. self.crc_extra = True
  203. self.crc_struct = True
  204. self.command_24bit = True
  205. self.allow_extensions = True
  206. else:
  207. print("Unknown wire protocol version")
  208. print("Available versions are: %s %s" % (PROTOCOL_0_9, PROTOCOL_1_0, PROTOCOL_2_0))
  209. raise MAVParseError('Unknown MAVLink wire protocol version %s' % wire_protocol_version)
  210. in_element_list = []
  211. def check_attrs(attrs, check, where):
  212. for c in check:
  213. if c not in attrs:
  214. raise MAVParseError('expected missing %s "%s" attribute at %s:%u' % (
  215. where, c, filename, p.CurrentLineNumber))
  216. def start_element(name, attrs):
  217. in_element_list.append(name)
  218. in_element = '.'.join(in_element_list)
  219. #print in_element
  220. if in_element == "mavlink.messages.message":
  221. check_attrs(attrs, ['name', 'id'], 'message')
  222. self.message.append(MAVType(attrs['name'], attrs['id'], p.CurrentLineNumber))
  223. elif in_element == "mavlink.messages.message.extensions":
  224. self.message[-1].extensions_start = len(self.message[-1].fields)
  225. elif in_element == "mavlink.messages.message.field":
  226. check_attrs(attrs, ['name', 'type'], 'field')
  227. print_format = attrs.get('print_format', None)
  228. enum = attrs.get('enum', '')
  229. display = attrs.get('display', '')
  230. units = attrs.get('units', '')
  231. if units:
  232. units = '[' + units + ']'
  233. new_field = MAVField(attrs['name'], attrs['type'], print_format, self, enum=enum, display=display, units=units)
  234. if self.message[-1].extensions_start is None or self.allow_extensions:
  235. self.message[-1].fields.append(new_field)
  236. elif in_element == "mavlink.enums.enum":
  237. check_attrs(attrs, ['name'], 'enum')
  238. self.enum.append(MAVEnum(attrs['name'], p.CurrentLineNumber))
  239. elif in_element == "mavlink.enums.enum.entry":
  240. check_attrs(attrs, ['name'], 'enum entry')
  241. # determine value and if it was automatically assigned (for possible merging later)
  242. if 'value' in attrs:
  243. value = eval(attrs['value'])
  244. autovalue = False
  245. else:
  246. value = self.enum[-1].highest_value + 1
  247. autovalue = True
  248. # check lowest value
  249. if (self.enum[-1].start_value is None or value < self.enum[-1].start_value):
  250. self.enum[-1].start_value = value
  251. # check highest value
  252. if (value > self.enum[-1].highest_value):
  253. self.enum[-1].highest_value = value
  254. # append the new entry
  255. self.enum[-1].entry.append(MAVEnumEntry(attrs['name'], value, '', False, autovalue, self.filename, p.CurrentLineNumber))
  256. elif in_element == "mavlink.enums.enum.entry.param":
  257. check_attrs(attrs, ['index'], 'enum param')
  258. self.enum[-1].entry[-1].param.append(
  259. MAVEnumParam(attrs['index'],
  260. label=attrs.get('label', ''), units=attrs.get('units', ''),
  261. enum=attrs.get('enum', ''), increment=attrs.get('increment', ''),
  262. minValue=attrs.get('minValue', ''),
  263. maxValue=attrs.get('maxValue', ''), default=attrs.get('default', '0'),
  264. reserved=attrs.get('reserved', False) ))
  265. def is_target_system_field(m, f):
  266. if f.name == 'target_system':
  267. return True
  268. if m.name == "MANUAL_CONTROL" and f.name == "target":
  269. return True
  270. return False
  271. def end_element(name):
  272. in_element_list.pop()
  273. def char_data(data):
  274. in_element = '.'.join(in_element_list)
  275. if in_element == "mavlink.messages.message.description":
  276. self.message[-1].description += data
  277. elif in_element == "mavlink.messages.message.field":
  278. if self.message[-1].extensions_start is None or self.allow_extensions:
  279. self.message[-1].fields[-1].description += data
  280. elif in_element == "mavlink.enums.enum.description":
  281. self.enum[-1].description += data
  282. elif in_element == "mavlink.enums.enum.entry.description":
  283. self.enum[-1].entry[-1].description += data
  284. elif in_element == "mavlink.enums.enum.entry.param":
  285. self.enum[-1].entry[-1].param[-1].description += data
  286. elif in_element == "mavlink.version":
  287. self.version = int(data)
  288. elif in_element == "mavlink.include":
  289. self.include.append(data)
  290. f = open(filename, mode='rb')
  291. p = xml.parsers.expat.ParserCreate()
  292. p.StartElementHandler = start_element
  293. p.EndElementHandler = end_element
  294. p.CharacterDataHandler = char_data
  295. p.ParseFile(f)
  296. f.close()
  297. #Post process to add reserved params (for docs)
  298. for current_enum in self.enum:
  299. if not 'MAV_CMD' in current_enum.name:
  300. continue
  301. print(current_enum.name)
  302. for enum_entry in current_enum.entry:
  303. print(enum_entry.name)
  304. if len(enum_entry.param) == 7:
  305. continue
  306. params_dict=dict()
  307. for param_index in range (1,8):
  308. params_dict[param_index] = MAVEnumParam(param_index, label='', units='', enum='', increment='',
  309. minValue='', maxValue='', default='0', reserved='True')
  310. for a_param in enum_entry.param:
  311. params_dict[int(a_param.index)] = a_param
  312. enum_entry.param=params_dict.values()
  313. self.message_lengths = {}
  314. self.message_min_lengths = {}
  315. self.message_flags = {}
  316. self.message_target_system_ofs = {}
  317. self.message_target_component_ofs = {}
  318. self.message_crcs = {}
  319. self.message_names = {}
  320. self.largest_payload = 0
  321. if not self.command_24bit:
  322. # remove messages with IDs > 255
  323. m2 = []
  324. for m in self.message:
  325. if m.id <= 255:
  326. m2.append(m)
  327. else:
  328. print("Ignoring MAVLink2 message %s" % m.name)
  329. self.message = m2
  330. for m in self.message:
  331. if not self.command_24bit and m.id > 255:
  332. continue
  333. m.wire_length = 0
  334. m.wire_min_length = 0
  335. m.fieldnames = []
  336. m.fieldlengths = []
  337. m.ordered_fieldnames = []
  338. m.ordered_fieldtypes = []
  339. m.fieldtypes = []
  340. m.message_flags = 0
  341. m.target_system_ofs = 0
  342. m.target_component_ofs = 0
  343. if self.sort_fields:
  344. # when we have extensions we only sort up to the first extended field
  345. sort_end = m.base_fields()
  346. m.ordered_fields = sorted(m.fields[:sort_end],
  347. key=operator.attrgetter('type_length'),
  348. reverse=True)
  349. m.ordered_fields.extend(m.fields[sort_end:])
  350. else:
  351. m.ordered_fields = m.fields
  352. for f in m.fields:
  353. m.fieldnames.append(f.name)
  354. L = f.array_length
  355. if L == 0:
  356. m.fieldlengths.append(1)
  357. elif L > 1 and f.type == 'char':
  358. m.fieldlengths.append(1)
  359. else:
  360. m.fieldlengths.append(L)
  361. m.fieldtypes.append(f.type)
  362. for i in range(len(m.ordered_fields)):
  363. f = m.ordered_fields[i]
  364. f.wire_offset = m.wire_length
  365. m.wire_length += f.wire_length
  366. if m.extensions_start is None or i < m.extensions_start:
  367. m.wire_min_length = m.wire_length
  368. m.ordered_fieldnames.append(f.name)
  369. m.ordered_fieldtypes.append(f.type)
  370. f.set_test_value()
  371. if f.name.find('[') != -1:
  372. raise MAVParseError("invalid field name with array descriptor %s" % f.name)
  373. # having flags for target_system and target_component helps a lot for routing code
  374. if is_target_system_field(m, f):
  375. m.message_flags |= FLAG_HAVE_TARGET_SYSTEM
  376. m.target_system_ofs = f.wire_offset
  377. elif f.name == 'target_component':
  378. m.message_flags |= FLAG_HAVE_TARGET_COMPONENT
  379. m.target_component_ofs = f.wire_offset
  380. m.num_fields = len(m.fieldnames)
  381. if m.num_fields > 64:
  382. raise MAVParseError("num_fields=%u : Maximum number of field names allowed is" % (
  383. m.num_fields, 64))
  384. m.crc_extra = message_checksum(m)
  385. key = m.id
  386. self.message_crcs[key] = m.crc_extra
  387. self.message_lengths[key] = m.wire_length
  388. self.message_min_lengths[key] = m.wire_min_length
  389. self.message_names[key] = m.name
  390. self.message_flags[key] = m.message_flags
  391. self.message_target_system_ofs[key] = m.target_system_ofs
  392. self.message_target_component_ofs[key] = m.target_component_ofs
  393. if m.wire_length > self.largest_payload:
  394. self.largest_payload = m.wire_length
  395. if m.wire_length+8 > 64:
  396. print("Note: message %s is longer than 64 bytes long (%u bytes), which can cause fragmentation since many radio modems use 64 bytes as maximum air transfer unit." % (m.name, m.wire_length+8))
  397. def __str__(self):
  398. return "MAVXML for %s from %s (%u message, %u enums)" % (
  399. self.basename, self.filename, len(self.message), len(self.enum))
  400. def message_checksum(msg):
  401. '''calculate a 8-bit checksum of the key fields of a message, so we
  402. can detect incompatible XML changes'''
  403. from .mavcrc import x25crc
  404. crc = x25crc()
  405. crc.accumulate_str(msg.name + ' ')
  406. # in order to allow for extensions the crc does not include
  407. # any field extensions
  408. crc_end = msg.base_fields()
  409. for i in range(crc_end):
  410. f = msg.ordered_fields[i]
  411. crc.accumulate_str(f.type + ' ')
  412. crc.accumulate_str(f.name + ' ')
  413. if f.array_length:
  414. crc.accumulate([f.array_length])
  415. return (crc.crc&0xFF) ^ (crc.crc>>8)
  416. def merge_enums(xml):
  417. '''merge enums between XML files'''
  418. emap = {}
  419. for x in xml:
  420. newenums = []
  421. for enum in x.enum:
  422. if enum.name in emap:
  423. emapitem = emap[enum.name]
  424. # check for possible conflicting auto-assigned values after merge
  425. if (emapitem.start_value <= enum.highest_value and emapitem.highest_value >= enum.start_value):
  426. for entry in emapitem.entry:
  427. # correct the value if necessary, but only if it was auto-assigned to begin with
  428. if entry.value <= enum.highest_value and entry.autovalue is True:
  429. entry.value = enum.highest_value + 1
  430. enum.highest_value = entry.value
  431. # merge the entries
  432. emapitem.entry.extend(enum.entry)
  433. if not emapitem.description:
  434. emapitem.description = enum.description
  435. print("Merged enum %s" % enum.name)
  436. else:
  437. newenums.append(enum)
  438. emap[enum.name] = enum
  439. x.enum = newenums
  440. for e in emap:
  441. # sort by value
  442. emap[e].entry = sorted(emap[e].entry,
  443. key=operator.attrgetter('value'),
  444. reverse=False)
  445. # add a ENUM_END
  446. emap[e].entry.append(MAVEnumEntry("%s_ENUM_END" % emap[e].name,
  447. emap[e].entry[-1].value+1, end_marker=True))
  448. def check_duplicates(xml):
  449. '''check for duplicate message IDs'''
  450. merge_enums(xml)
  451. msgmap = {}
  452. msg_name_map = {}
  453. enummap = {}
  454. for x in xml:
  455. for m in x.message:
  456. key = m.id
  457. if key in msgmap:
  458. print("ERROR: Duplicate message id %u for %s (%s:%u) also used by %s" % (
  459. m.id,
  460. m.name,
  461. x.filename, m.linenumber,
  462. msgmap[key]))
  463. return True
  464. fieldset = set()
  465. for f in m.fields:
  466. if f.name in fieldset:
  467. print("ERROR: Duplicate field %s in message %s (%s:%u)" % (
  468. f.name, m.name,
  469. x.filename, m.linenumber))
  470. return True
  471. fieldset.add(f.name)
  472. msgmap[key] = '%s (%s:%u)' % (m.name, x.filename, m.linenumber)
  473. # Check for duplicate message names
  474. if m.name in msg_name_map:
  475. print("ERROR: Duplicate message name %s for id:%u (%s:%u) also used by %s" % (
  476. m.name,
  477. m.id,
  478. x.filename, m.linenumber,
  479. msg_name_map[m.name]))
  480. return True
  481. msg_name_map[m.name] = '%s (%s:%u)' % (m.id, x.filename, m.linenumber)
  482. for enum in x.enum:
  483. for entry in enum.entry:
  484. if entry.autovalue is True and "common.xml" not in entry.origin_file:
  485. print("Note: An enum value was auto-generated: %s = %u" % (entry.name, entry.value))
  486. s1 = "%s.%s" % (enum.name, entry.name)
  487. s2 = "%s.%s" % (enum.name, entry.value)
  488. if s1 in enummap or s2 in enummap:
  489. print("ERROR: Duplicate enum %s:\n\t%s = %s @ %s:%u\n\t%s" % (
  490. "names" if s1 in enummap else "values",
  491. s1, entry.value, entry.origin_file, entry.origin_line,
  492. enummap.get(s1) or enummap.get(s2)))
  493. return True
  494. enummap[s1] = enummap[s2] = "%s.%s = %s @ %s:%u" % (enum.name, entry.name, entry.value, entry.origin_file, entry.origin_line)
  495. return False
  496. def total_msgs(xml):
  497. '''count total number of msgs'''
  498. count = 0
  499. for x in xml:
  500. count += len(x.message)
  501. return count
  502. def mkdir_p(dir):
  503. try:
  504. os.makedirs(dir)
  505. except OSError as exc:
  506. if exc.errno != errno.EEXIST:
  507. raise
  508. # check version consistent
  509. # add test.xml
  510. # finish test suite
  511. # printf style error macro, if defined call errors