generator/mavgen.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 '''
4 parse a MAVLink protocol XML file and generate a python implementation
5 
6 Copyright Andrew Tridgell 2011
7 Released under GNU GPL version 3 or later
8 
9 '''
10 
11 from __future__ import print_function
12 from future import standard_library
13 standard_library.install_aliases()
14 from builtins import object
15 import os
16 import re
17 import sys
18 from . import mavparse
19 
20 # XSD schema file
21 schemaFile = os.path.join(os.path.dirname(os.path.realpath(__file__)), "mavschema.xsd")
22 
23 # Set defaults for generating MAVLink code
24 DEFAULT_WIRE_PROTOCOL = mavparse.PROTOCOL_1_0
25 DEFAULT_LANGUAGE = 'Python'
26 DEFAULT_ERROR_LIMIT = 200
27 DEFAULT_VALIDATE = True
28 DEFAULT_STRICT_UNITS = False
29 
30 MAXIMUM_INCLUDE_FILE_NESTING = 5
31 
32 # List the supported languages. This is done globally because it's used by the GUI wrapper too
33 supportedLanguages = ["C", "CS", "JavaScript", "Python", "WLua", "ObjC", "Swift", "Java", "C++11"]
34 
35 
36 def mavgen(opts, args):
37  """Generate mavlink message formatters and parsers (C and Python ) using options
38  and args where args are a list of xml files. This function allows python
39  scripts under Windows to control mavgen using the same interface as
40  shell scripts under Unix"""
41 
42  xml = []
43  all_files = set()
44 
45  # Enable validation by default, disabling it if explicitly requested
46  if opts.validate:
47  try:
48  from lxml import etree
49  with open(schemaFile, 'r') as f:
50  xmlschema_root = etree.parse(f)
51  if not opts.strict_units:
52  # replace the strict "SI_Unit" list of known unit strings with a more generic "xs:string" type
53  for elem in xmlschema_root.iterfind('xs:attribute[@name="units"]', xmlschema_root.getroot().nsmap):
54  elem.set("type", "xs:string")
55  xmlschema = etree.XMLSchema(xmlschema_root)
56  except ImportError:
57  print("WARNING: Failed to import lxml module etree. Are lxml, libxml2 and libxslt installed? XML validation will not be performed", file=sys.stderr)
58  opts.validate = False
59  except etree.XMLSyntaxError as err:
60  print("WARNING: XML Syntax Errors detected in %s XML schema file. XML validation will not be performed" % schemaFile, file=sys.stderr)
61  print(str(err.error_log), file=sys.stderr)
62  opts.validate = False
63  except:
64  print("WARNING: Unable to load XML validator libraries. XML validation will not be performed", file=sys.stderr)
65  opts.validate = False
66 
67  def expand_includes():
68  """Expand includes in current list of all files, ignoring those already parsed."""
69  for x in xml[:]:
70  for i in x.include:
71  fname = os.path.join(os.path.dirname(x.filename), i)
72 
73  # Only parse new include files
74  if fname in all_files:
75  continue
76  all_files.add(fname)
77 
78  # Validate XML file with XSD file if possible.
79  if opts.validate:
80  print("Validating %s" % fname)
81  if not mavgen_validate(fname):
82  return False
83  else:
84  print("Validation skipped for %s." % fname)
85 
86  # Parsing
87  print("Parsing %s" % fname)
88  xml.append(mavparse.MAVXML(fname, opts.wire_protocol))
89 
90  # include message lengths and CRCs too
91  x.message_crcs.update(xml[-1].message_crcs)
92  x.message_lengths.update(xml[-1].message_lengths)
93  x.message_min_lengths.update(xml[-1].message_min_lengths)
94  x.message_flags.update(xml[-1].message_flags)
95  x.message_target_system_ofs.update(xml[-1].message_target_system_ofs)
96  x.message_target_component_ofs.update(xml[-1].message_target_component_ofs)
97  x.message_names.update(xml[-1].message_names)
98  x.largest_payload = max(x.largest_payload, xml[-1].largest_payload)
99 
100  def mavgen_validate(xmlfile):
101  """Uses lxml to validate an XML file. We define mavgen_validate
102  here because it relies on the XML libs that were loaded in mavgen(), so it can't be called standalone"""
103  xmlvalid = True
104  try:
105  with open(xmlfile, 'r') as f:
106  xmldocument = etree.parse(f)
107  xmlschema.assertValid(xmldocument)
108  forbidden_names_re = re.compile("^(break$|case$|class$|catch$|const$|continue$|debugger$|default$|delete$|do$|else$|\
109  export$|extends$|finally$|for$|function$|if$|import$|in$|instanceof$|let$|new$|\
110  return$|super$|switch$|this$|throw$|try$|typeof$|var$|void$|while$|with$|yield$|\
111  enum$|await$|implements$|package$|protected$|static$|interface$|private$|public$|\
112  abstract$|boolean$|byte$|char$|double$|final$|float$|goto$|int$|long$|native$|\
113  short$|synchronized$|transient$|volatile$).*", re.IGNORECASE)
114  for element in xmldocument.iter('enum', 'entry', 'message', 'field'):
115  if forbidden_names_re.search(element.get('name')):
116  print("Validation error:", file=sys.stderr)
117  print("Element : %s at line : %s contains forbidden word" % (element.tag, element.sourceline), file=sys.stderr)
118  xmlvalid = False
119 
120  return xmlvalid
121  except etree.XMLSchemaError:
122  return False
123  except etree.DocumentInvalid as err:
124  sys.exit('ERROR: %s' % str(err.error_log))
125  return True
126 
127  # Process all XML files, validating them as necessary.
128  for fname in args:
129  # only add each dialect file argument once.
130  if fname in all_files:
131  continue
132  all_files.add(fname)
133 
134  if opts.validate:
135  print("Validating %s" % fname)
136  if not mavgen_validate(fname):
137  return False
138  else:
139  print("Validation skipped for %s." % fname)
140 
141  print("Parsing %s" % fname)
142  xml.append(mavparse.MAVXML(fname, opts.wire_protocol))
143 
144  # expand includes
145  for i in range(MAXIMUM_INCLUDE_FILE_NESTING):
146  len_allfiles = len(all_files)
147  expand_includes()
148  if len(all_files) == len_allfiles:
149  # stop when loop doesn't add any more included files
150  break
151 
152  # work out max payload size across all includes
153  largest_payload = max(x.largest_payload for x in xml) if xml else 0
154  for x in xml:
155  x.largest_payload = largest_payload
156 
157  if mavparse.check_duplicates(xml):
158  sys.exit(1)
159 
160  print("Found %u MAVLink message types in %u XML files" % (
161  mavparse.total_msgs(xml), len(xml)))
162 
163  # convert language option to lowercase and validate
164  opts.language = opts.language.lower()
165  if opts.language == 'python':
166  from . import mavgen_python
167  mavgen_python.generate(opts.output, xml)
168  elif opts.language == 'c':
169  from . import mavgen_c
170  mavgen_c.generate(opts.output, xml)
171  elif opts.language == 'wlua':
172  from . import mavgen_wlua
173  mavgen_wlua.generate(opts.output, xml)
174  elif opts.language == 'cs':
175  from . import mavgen_cs
176  mavgen_cs.generate(opts.output, xml)
177  elif opts.language == 'javascript':
178  from . import mavgen_javascript
179  mavgen_javascript.generate(opts.output, xml)
180  elif opts.language == 'objc':
181  from . import mavgen_objc
182  mavgen_objc.generate(opts.output, xml)
183  elif opts.language == 'swift':
184  from . import mavgen_swift
185  mavgen_swift.generate(opts.output, xml)
186  elif opts.language == 'java':
187  from . import mavgen_java
188  mavgen_java.generate(opts.output, xml)
189  elif opts.language == 'c++11':
190  from . import mavgen_cpp11
191  mavgen_cpp11.generate(opts.output, xml)
192  else:
193  print("Unsupported language %s" % opts.language)
194 
195  return True
196 
197 
198 # build all the dialects in the dialects subpackage
199 class Opts(object):
200  def __init__(self, output, wire_protocol=DEFAULT_WIRE_PROTOCOL, language=DEFAULT_LANGUAGE, validate=DEFAULT_VALIDATE, error_limit=DEFAULT_ERROR_LIMIT, strict_units=DEFAULT_STRICT_UNITS):
201  self.wire_protocol = wire_protocol
202  self.error_limit = error_limit
203  self.language = language
204  self.output = output
205  self.validate = validate
206  self.strict_units = strict_units
207 
208 
209 def mavgen_python_dialect(dialect, wire_protocol):
210  '''generate the python code on the fly for a MAVLink dialect'''
211  dialects = os.path.join(os.path.dirname(os.path.realpath(__file__)), '..', 'dialects')
212  mdef = os.path.join(os.path.dirname(os.path.realpath(__file__)), '..', '..', 'message_definitions')
213  if wire_protocol == mavparse.PROTOCOL_0_9:
214  py = os.path.join(dialects, 'v09', dialect + '.py')
215  xml = os.path.join(dialects, 'v09', dialect + '.xml')
216  if not os.path.exists(xml):
217  xml = os.path.join(mdef, 'v0.9', dialect + '.xml')
218  elif wire_protocol == mavparse.PROTOCOL_1_0:
219  py = os.path.join(dialects, 'v10', dialect + '.py')
220  xml = os.path.join(dialects, 'v10', dialect + '.xml')
221  if not os.path.exists(xml):
222  xml = os.path.join(mdef, 'v1.0', dialect + '.xml')
223  else:
224  py = os.path.join(dialects, 'v20', dialect + '.py')
225  xml = os.path.join(dialects, 'v20', dialect + '.xml')
226  if not os.path.exists(xml):
227  xml = os.path.join(mdef, 'v1.0', dialect + '.xml')
228  opts = Opts(py, wire_protocol)
229 
230  # Python 2 to 3 compatibility
231  try:
232  import StringIO as io
233  except ImportError:
234  import io
235 
236  # throw away stdout while generating
237  stdout_saved = sys.stdout
238  sys.stdout = io.StringIO()
239  try:
240  xml = os.path.relpath(xml)
241  if not mavgen(opts, [xml]):
242  sys.stdout = stdout_saved
243  return False
244  except Exception:
245  sys.stdout = stdout_saved
246  raise
247  sys.stdout = stdout_saved
248  return True
249 
250 if __name__ == "__main__":
251  raise DeprecationWarning("Executable was moved to pymavlink.tools.mavgen")


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