mavgen_wlua.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 '''
3 parse a MAVLink protocol XML file and generate a Wireshark LUA dissector
4 
5 Copyright Holger Steinhaus 2012
6 Released under GNU GPL version 3 or later
7 
8 Instructions for use:
9 1. python -m pymavlink.tools.mavgen --lang=WLua mymavlink.xml -o ~/.wireshark/plugins/mymavlink.lua
10 2. convert binary stream int .pcap file format (see ../examples/mav2pcap.py)
11 3. open the pcap file in Wireshark
12 '''
13 from __future__ import print_function
14 
15 from builtins import range
16 
17 import os
18 import re
19 from . import mavparse, mavtemplate
20 
22 
23 
24 def lua_type(mavlink_type):
25  # qnd typename conversion
26  if (mavlink_type=='char'):
27  lua_t = 'uint8'
28  else:
29  lua_t = mavlink_type.replace('_t', '')
30  return lua_t
31 
32 def type_size(mavlink_type):
33  # infer size of mavlink types
34  re_int = re.compile('^(u?)int(8|16|32|64)_t$')
35  int_parts = re_int.findall(mavlink_type)
36  if len(int_parts):
37  return (int(int_parts[0][1]) // 8)
38  elif mavlink_type == 'float':
39  return 4
40  elif mavlink_type == 'double':
41  return 8
42  elif mavlink_type == 'char':
43  return 1
44  else:
45  raise Exception('unsupported MAVLink type - please fix me')
46 
47 
48 def mavfmt(field):
49  '''work out the struct format for a type'''
50  map = {
51  'float' : 'f',
52  'double' : 'd',
53  'char' : 'c',
54  'int8_t' : 'b',
55  'uint8_t' : 'B',
56  'uint8_t_mavlink_version' : 'B',
57  'int16_t' : 'h',
58  'uint16_t' : 'H',
59  'int32_t' : 'i',
60  'uint32_t' : 'I',
61  'int64_t' : 'q',
62  'uint64_t' : 'Q',
63  }
64 
65  if field.array_length:
66  if field.type in ['char', 'int8_t', 'uint8_t']:
67  return str(field.array_length)+'s'
68  return str(field.array_length)+map[field.type]
69  return map[field.type]
70 
71 
73  print("Generating preamble")
74  t.write(outf,
75 """
76 -- Wireshark dissector for the MAVLink protocol (please see http://qgroundcontrol.org/mavlink/start for details)
77 
78 unknownFrameBeginOffset = 0
79 local bit = require "bit32"
80 mavlink_proto = Proto("mavlink_proto", "MAVLink protocol")
81 f = mavlink_proto.fields
82 
83 -- from http://lua-users.org/wiki/TimeZone
84 local function get_timezone()
85  local now = os.time()
86  return os.difftime(now, os.time(os.date("!*t", now)))
87 end
88 local signature_time_ref = get_timezone() + os.time{year=2015, month=1, day=1, hour=0}
89 
90 payload_fns = {}
91 
92 """ )
93 
94 
96  t.write(outf,
97 """
98 f.magic = ProtoField.uint8("mavlink_proto.magic", "Magic value / version", base.HEX)
99 f.length = ProtoField.uint8("mavlink_proto.length", "Payload length")
100 f.incompatibility_flag = ProtoField.uint8("mavlink_proto.incompatibility_flag", "Incompatibility flag")
101 f.compatibility_flag = ProtoField.uint8("mavlink_proto.compatibility_flag", "Compatibility flag")
102 f.sequence = ProtoField.uint8("mavlink_proto.sequence", "Packet sequence")
103 f.sysid = ProtoField.uint8("mavlink_proto.sysid", "System id", base.HEX)
104 f.compid = ProtoField.uint8("mavlink_proto.compid", "Component id", base.HEX)
105 f.msgid = ProtoField.uint24("mavlink_proto.msgid", "Message id", base.HEX)
106 f.payload = ProtoField.uint8("mavlink_proto.payload", "Payload", base.DEC, messageName)
107 f.crc = ProtoField.uint16("mavlink_proto.crc", "Message CRC", base.HEX)
108 f.signature_link = ProtoField.uint8("mavlink_proto.signature_link", "Link id", base.DEC)
109 f.signature_time = ProtoField.absolute_time("mavlink_proto.signature_time", "Time")
110 f.signature_signature = ProtoField.bytes("mavlink_proto.signature_signature", "Signature")
111 f.rawheader = ProtoField.bytes("mavlink_proto.rawheader", "Unparsable header fragment")
112 f.rawpayload = ProtoField.bytes("mavlink_proto.rawpayload", "Unparsable payload")
113 
114 """)
115 
116 
117 def generate_msg_table(outf, msgs):
118  t.write(outf, """
119 messageName = {
120 """)
121  for msg in msgs:
122  assert isinstance(msg, mavparse.MAVType)
123  t.write(outf, """
124  [${msgid}] = '${msgname}',
125 """, {'msgid':msg.id, 'msgname':msg.name})
126 
127  t.write(outf, """
128 }
129 
130 """)
131 
132 
133 def generate_msg_fields(outf, msg):
134  assert isinstance(msg, mavparse.MAVType)
135  for f in msg.fields:
136  assert isinstance(f, mavparse.MAVField)
137  mtype = f.type
138  ltype = lua_type(mtype)
139  count = f.array_length if f.array_length>0 else 1
140 
141  # string is no array, but string of chars
142  if mtype == 'char' and count > 1:
143  count = 1
144  ltype = 'string'
145 
146  for i in range(0,count):
147  if count>1:
148  array_text = '[' + str(i) + ']'
149  index_text = '_' + str(i)
150  else:
151  array_text = ''
152  index_text = ''
153 
154  t.write(outf,
155 """
156 f.${fmsg}_${fname}${findex} = ProtoField.${ftype}("mavlink_proto.${fmsg}_${fname}${findex}", "${fname}${farray} (${ftype})")
157 """, {'fmsg':msg.name, 'ftype':ltype, 'fname':f.name, 'findex':index_text, 'farray':array_text})
158 
159  t.write(outf, '\n\n')
160 
161 def generate_field_dissector(outf, msg, field):
162  assert isinstance(field, mavparse.MAVField)
163 
164  mtype = field.type
165  size = type_size(mtype)
166  ltype = lua_type(mtype)
167  count = field.array_length if field.array_length>0 else 1
168 
169  # string is no array but string of chars
170  if mtype == 'char':
171  size = count
172  count = 1
173 
174  # handle arrays, but not strings
175 
176  for i in range(0,count):
177  if count>1:
178  index_text = '_' + str(i)
179  else:
180  index_text = ''
181  t.write(outf,
182 """
183  if (truncated) then
184  tree:add_le(f.${fmsg}_${fname}${findex}, 0)
185  elseif (offset + ${fbytes} <= limit) then
186  tree:add_le(f.${fmsg}_${fname}${findex}, buffer(offset, ${fbytes}))
187  offset = offset + ${fbytes}
188  elseif (offset < limit) then
189  tree:add_le(f.${fmsg}_${fname}${findex}, buffer(offset, limit - offset))
190  offset = limit
191  truncated = true
192  else
193  tree:add_le(f.${fmsg}_${fname}${findex}, 0)
194  truncated = true
195  end
196 """, {'fname':field.name, 'ftype':mtype, 'fmsg': msg.name, 'fbytes':size, 'findex':index_text})
197 
198 
200  assert isinstance(msg, mavparse.MAVType)
201  t.write(outf,
202 """
203 -- dissect payload of message type ${msgname}
204 function payload_fns.payload_${msgid}(buffer, tree, msgid, offset, limit)
205  local truncated = false
206 """, {'msgid':msg.id, 'msgname':msg.name})
207 
208  for f in msg.ordered_fields:
209  generate_field_dissector(outf, msg, f)
210 
211 
212  t.write(outf,
213 """
214  return offset
215 end
216 
217 
218 """)
219 
220 
222  t.write(outf,
223 """
224 -- dissector function
225 function mavlink_proto.dissector(buffer,pinfo,tree)
226  local offset = 0
227  local msgCount = 0
228 
229  -- loop through the buffer to extract all the messages in the buffer
230  while (offset < buffer:len())
231  do
232  msgCount = msgCount + 1
233  local subtree = tree:add (mavlink_proto, buffer(), "MAVLink Protocol ("..buffer:len()..")")
234 
235  -- decode protocol version first
236  local version = buffer(offset,1):uint()
237  local protocolString = ""
238 
239  while (true)
240  do
241  if (version == 0xfe) then
242  protocolString = "MAVLink 1.0"
243  break
244  elseif (version == 0xfd) then
245  protocolString = "MAVLink 2.0"
246  break
247  elseif (version == 0x55) then
248  protocolString = "MAVLink 0.9"
249  break
250  else
251  protocolString = "unknown"
252  -- some unknown data found, record the begin offset
253  if (unknownFrameBeginOffset == 0) then
254  unknownFrameBeginOffset = offset
255  end
256 
257  offset = offset + 1
258 
259  if (offset < buffer:len()) then
260  version = buffer(offset,1):uint()
261  else
262  -- no magic value found in the whole buffer. print the raw data and exit
263  if (unknownFrameBeginOffset ~= 0) then
264  if (msgCount == 1) then
265  pinfo.cols.info:set("Unknown message")
266  else
267  pinfo.cols.info:append(" Unknown message")
268  end
269  size = offset - unknownFrameBeginOffset
270  subtree:add(f.rawpayload, buffer(unknownFrameBeginOffset,size))
271  unknownFrameBeginOffset = 0
272  end
273  return
274  end
275  end
276  end
277 
278  if (unknownFrameBeginOffset ~= 0) then
279  pinfo.cols.info:append("Unknown message")
280  size = offset - unknownFrameBeginOffset
281  subtree:add(f.rawpayload, buffer(unknownFrameBeginOffset,size))
282  unknownFrameBeginOffset = 0
283  -- jump to next loop
284  break
285  end
286 
287  -- some Wireshark decoration
288  pinfo.cols.protocol = protocolString
289 
290  -- HEADER ----------------------------------------
291 
292  local msgid
293  local length
294  local incompatibility_flag
295 
296  if (version == 0xfe) then
297  if (buffer:len() - 2 - offset > 6) then
298  -- normal header
299  local header = subtree:add("Header")
300  header:add(f.magic, buffer(offset,1), version)
301  offset = offset + 1
302 
303  length = buffer(offset,1)
304  header:add(f.length, length)
305  offset = offset + 1
306 
307  local sequence = buffer(offset,1)
308  header:add(f.sequence, sequence)
309  offset = offset + 1
310 
311  local sysid = buffer(offset,1)
312  header:add(f.sysid, sysid)
313  offset = offset + 1
314 
315  local compid = buffer(offset,1)
316  header:add(f.compid, compid)
317  offset = offset + 1
318 
319  pinfo.cols.src = "System: "..tostring(sysid:uint())..', Component: '..tostring(compid:uint())
320 
321  msgid = buffer(offset,1):uint()
322  header:add(f.msgid, buffer(offset,1), msgid)
323  offset = offset + 1
324  else
325  -- handle truncated header
326  local hsize = buffer:len() - 2 - offset
327  subtree:add(f.rawheader, buffer(offset, hsize))
328  offset = offset + hsize
329  end
330  elseif (version == 0xfd) then
331  if (buffer:len() - 2 - offset > 10) then
332  -- normal header
333  local header = subtree:add("Header")
334  header:add(f.magic, buffer(offset,1), version)
335  offset = offset + 1
336  length = buffer(offset,1)
337  header:add(f.length, length)
338  offset = offset + 1
339  incompatibility_flag = buffer(offset,1):uint()
340  header:add(f.incompatibility_flag, buffer(offset,1), incompatibility_flag)
341  offset = offset + 1
342  local compatibility_flag = buffer(offset,1)
343  header:add(f.compatibility_flag, compatibility_flag)
344  offset = offset + 1
345  local sequence = buffer(offset,1)
346  header:add(f.sequence, sequence)
347  offset = offset + 1
348  local sysid = buffer(offset,1)
349  header:add(f.sysid, sysid)
350  offset = offset + 1
351  local compid = buffer(offset,1)
352  header:add(f.compid, compid)
353  offset = offset + 1
354  pinfo.cols.src = "System: "..tostring(sysid:uint())..', Component: '..tostring(compid:uint())
355  msgid = buffer(offset,3):le_uint()
356  header:add(f.msgid, buffer(offset,3), msgid)
357  offset = offset + 3
358  else
359  -- handle truncated header
360  local hsize = buffer:len() - 2 - offset
361  subtree:add(f.rawheader, buffer(offset, hsize))
362  offset = offset + hsize
363  end
364  end
365 
366 
367  -- BODY ----------------------------------------
368 
369  -- dynamically call the type-specific payload dissector
370  local msgnr = msgid
371  local dissect_payload_fn = "payload_"..tostring(msgnr)
372  local fn = payload_fns[dissect_payload_fn]
373  local limit = buffer:len() - 2
374 
375  if (length) then
376  length = length:uint()
377  else
378  length = 0
379  end
380 
381  if (offset + length < limit) then
382  limit = offset + length
383  end
384 
385  if (fn == nil) then
386  pinfo.cols.info:append ("Unknown message type ")
387  subtree:add_expert_info(PI_MALFORMED, PI_ERROR, "Unknown message type")
388  size = buffer:len() - 2 - offset
389  subtree:add(f.rawpayload, buffer(offset,size))
390  offset = offset + size
391  else
392  local payload = subtree:add(f.payload, msgid)
393  pinfo.cols.dst:set(messageName[msgid])
394  if (msgCount == 1) then
395  -- first message should over write the TCP/UDP info
396  pinfo.cols.info = messageName[msgid]
397  else
398  pinfo.cols.info:append(" "..messageName[msgid])
399  end
400  fn(buffer, payload, msgid, offset, limit)
401  offset = limit
402  end
403 
404  -- CRC ----------------------------------------
405 
406  local crc = buffer(offset,2)
407  subtree:add_le(f.crc, crc)
408  offset = offset + 2
409 
410  -- SIGNATURE ----------------------------------
411 
412  if (version == 0xfd and incompatibility_flag == 0x01) then
413  local signature = subtree:add("Signature")
414 
415  local link = buffer(offset,1)
416  signature:add(f.signature_link, link)
417  offset = offset + 1
418 
419  local signature_time = buffer(offset,6):le_uint64()
420  local time_secs = signature_time / 100000
421  local time_nsecs = (signature_time - (time_secs * 100000)) * 10000
422  signature:add(f.signature_time, buffer(offset,6), NSTime.new(signature_time_ref + time_secs:tonumber(), time_nsecs:tonumber()))
423  offset = offset + 6
424 
425  local signature_signature = buffer(offset,6)
426  signature:add(f.signature_signature, signature_signature)
427  offset = offset + 6
428  end
429 
430  end
431 end
432 
433 
434 """)
435 
436 
437 
438 def generate_epilog(outf):
439  print("Generating epilog")
440  t.write(outf,
441 """
442 -- bind protocol dissector to USER0 linktype
443 
444 wtap_encap = DissectorTable.get("wtap_encap")
445 wtap_encap:add(wtap.USER0, mavlink_proto)
446 
447 -- bind protocol dissector to port 14550
448 
449 local udp_dissector_table = DissectorTable.get("udp.port")
450 udp_dissector_table:add(14550, mavlink_proto)
451 """)
452 
453 def generate(basename, xml):
454  '''generate complete python implemenation'''
455  if basename.endswith('.lua'):
456  filename = basename
457  else:
458  filename = basename + '.lua'
459 
460  msgs = []
461  enums = []
462  filelist = []
463  for x in xml:
464  msgs.extend(x.message)
465  enums.extend(x.enum)
466  filelist.append(os.path.basename(x.filename))
467 
468  for m in msgs:
469  if xml[0].little_endian:
470  m.fmtstr = '<'
471  else:
472  m.fmtstr = '>'
473  for f in m.ordered_fields:
474  m.fmtstr += mavfmt(f)
475  m.order_map = [ 0 ] * len(m.fieldnames)
476  for i in range(0, len(m.fieldnames)):
477  m.order_map[i] = m.ordered_fieldnames.index(m.fieldnames[i])
478 
479  print("Generating %s" % filename)
480  outf = open(filename, "w")
481  generate_preamble(outf)
482  generate_msg_table(outf, msgs)
484 
485  for m in msgs:
486  generate_msg_fields(outf, m)
487 
488  for m in msgs:
490 
491  generate_packet_dis(outf)
492 # generate_enums(outf, enums)
493 # generate_message_ids(outf, msgs)
494 # generate_classes(outf, msgs)
495 # generate_mavlink_class(outf, msgs, xml[0])
496 # generate_methods(outf, msgs)
497  generate_epilog(outf)
498  outf.close()
499  print("Generated %s OK" % filename)
500 


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Jul 7 2019 03:22:06