mavgen_swift.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 """
3 Parse a MAVLink protocol XML file and generate Swift implementation
4 
5 Copyright Max Odnovolyk 2015
6 Released under GNU GPL version 3 or later
7 """
8 from __future__ import print_function
9 
10 import os
11 from . import mavparse, mavtemplate
12 
13 abbreviations = ["MAV", "PX4", "UDB", "PPZ", "PIXHAWK", "SLUGS", "FP", "ASLUAV", "VTOL", "ROI", "UART", "UDP", "IMU", "IMU2", "3D", "RC", "GPS", "GPS1", "GPS2", "NED", "RTK", "ADSB"]
14 swift_keywords = ["associatedtype", "class", "deinit", "enum", "extension", "fileprivate", "func", "import", "init", "inout", "internal", "let", "open", "operator", "private", "protocol",
15  "public", "static", "struct", "subscript", "typealias", "var", "break" "case", "continue", "default", "defer", "do", "else", "fallthrough", "for", "guard", "if", "in", "repeat", "return", "switch",
16  "where", "while", "Any", "catch", "false", "is", "nil", "rethrows", "super", "self", "Self", "throw", "throws", "true", "try"]
17 swift_types = {'char' : ("String", '"\\0"', "string(at: %u, length: %u)", "set(%s, at: %u, length: %u)"),
18  'uint8_t' : ("UInt8", 0, "number(at: %u)", "set(%s, at: %u)"),
19  'int8_t' : ("Int8", 0, "number(at: %u)", "set(%s, at: %u)"),
20  'uint16_t' : ("UInt16", 0, "number(at: %u)", "set(%s, at: %u)"),
21  'int16_t' : ("Int16", 0, "number(at: %u)", "set(%s, at: %u)"),
22  'uint32_t' : ("UInt32", 0, "number(at: %u)", "set(%s, at: %u)"),
23  'int32_t' : ("Int32", 0, "number(at: %u)", "set(%s, at: %u)"),
24  'uint64_t' : ("UInt64", 0, "number(at: %u)", "set(%s, at: %u)"),
25  'int64_t' : ("Int64", 0, "number(at: %u)", "set(%s, at: %u)"),
26  'float' : ("Float", 0, "number(at: %u)", "set(%s, at: %u)"),
27  'double' : ("Double", 0, "number(at: %u)", "set(%s, at: %u)"),
28  'uint8_t_mavlink_version' : ("UInt8", 0, "number(at: %u)", "set(%s, at: %u)")}
29 
31 
32 def generate_mavlink(directory, filelist, xml_list, msgs):
33  print("Generating MAVLink.swift file")
34 
35  mavparse.mkdir_p(directory)
36  filename = 'MAVLink.swift'
37  filepath = os.path.join(directory, filename)
38  outf = open(filepath, "w")
39  generate_header(outf, filelist, xml_list, filename)
40  append_static_code('MAVLink.swift', outf)
44  outf.close()
45 
46 def generate_header(outf, filelist, xml_list, filename):
47  """Generate Swift file header with source files list and creation date"""
48 
49  t.write(outf, """
50 //
51 // ${FILENAME}
52 // MAVLink Protocol Swift Library
53 //
54 // Generated from ${FILELIST} on ${PARSE_TIME} by mavgen_swift.py
55 // https://github.com/modnovolyk/MAVLinkSwift
56 //
57 
58 """, {'FILENAME' : filename,
59  'FILELIST' : ", ".join(filelist),
60  'PARSE_TIME' : xml_list[0].parse_time})
61 
62 def generate_enums(directory, filelist, xml_list, enums, msgs):
63  """Iterate through all enums and create Swift equivalents"""
64 
65  print("Generating Enumerations")
66 
67  for enum in enums:
68  filename = "%s%sEnum.swift" % (enum.swift_name, enum.basename)
69  filepath = os.path.join(directory, filename)
70  outf = open(filepath, "w")
71  generate_header(outf, filelist, xml_list, filename)
72  t.write(outf, """
73 ${formatted_description}public enum ${swift_name}: ${raw_value_type} {
74 ${{entry:${formatted_description}\tcase ${swift_name} = ${value}\n}}
75 }
76 
77 extension ${swift_name}: Enumeration {
78  public static var typeName = "${name}"
79  public static var typeDescription = "${entity_description}"
80  public static var allMembers = [${all_entities}]
81  public static var membersDescriptions = [${entities_info}]
82  public static var enumEnd = UInt(${enum_end})
83 }
84 """, enum)
85  outf.close()
86 
87 def get_enum_raw_type(enum, msgs):
88  """Search appropirate raw type for enums in messages fields"""
89 
90  for msg in msgs:
91  for field in msg.fields:
92  if field.enum == enum.name:
93  return swift_types[field.type][0]
94  return "Int"
95 
96 def generate_messages(directory, filelist, xml_list, msgs):
97  """Generate Swift structs to represent all MAVLink messages"""
98 
99  print("Generating Messages")
100 
101  for msg in msgs:
102  filename = "%s%sMsg.swift" % (msg.swift_name, msg.basename)
103  filepath = os.path.join(directory, filename)
104  outf = open(filepath, "w")
105  generate_header(outf, filelist, xml_list, filename)
106  t.write(outf, """
107 import Foundation
108 
109 ${formatted_description}public struct ${swift_name} {
110 ${{fields:${formatted_description}\tpublic let ${swift_name}: ${return_type}\n}}
111 }
112 
113 extension ${swift_name}: Message {
114  public static let id = UInt8(${id})
115  public static var typeName = "${name}"
116  public static var typeDescription = "${message_description}"
117  public static var fieldDefinitions: [FieldDefinition] = [${fields_info}]
118 
119  public init(data: Data) throws {
120 ${{ordered_fields:\t\t${init_accessor} = ${initial_value}\n}}
121  }
122 
123  public func pack() throws -> Data {
124  var payload = Data(count: ${wire_length})
125 ${{ordered_fields:\t\ttry payload.${payload_setter}\n}}
126  return payload
127  }
128 }
129 """, msg)
130  outf.close()
131 
132 def append_static_code(filename, outf):
133  """Open and copy static code from specified file"""
134 
135  basepath = os.path.dirname(os.path.realpath(__file__))
136  filepath = os.path.join(basepath, 'swift/%s' % filename)
137 
138  print("Appending content of %s" % filename)
139 
140  with open(filepath) as inf:
141  for line in inf:
142  outf.write(line)
143 
145  """Create array for mapping message Ids to proper structs"""
146 
147  classes = []
148  for msg in msgs:
149  classes.append("%u: %s.self" % (msg.id, msg.swift_name))
150  t.write(outf, """
151 
152 /// Array for mapping message id to proper struct
153 private let messageIdToClass: [UInt8: Message.Type] = [${ARRAY_CONTENT}]
154 """, {'ARRAY_CONTENT' : ", ".join(classes)})
155 
157  """Create array with message lengths to validate known message lengths"""
158 
159  # form message lengths array
160  lengths = []
161  for msg in msgs:
162  lengths.append("%u: %u" % (msg.id, msg.wire_length))
163 
164  t.write(outf, """
165 
166 /// Message lengths array for known messages length validation
167 private let messageLengths: [UInt8: UInt8] = [${ARRAY_CONTENT}]
168 """, {'ARRAY_CONTENT' : ", ".join(lengths)})
169 
171  """Add array with CRC extra values to detect incompatible XML changes"""
172 
173  crcs = []
174  for msg in msgs:
175  crcs.append("%u: %u" % (msg.id, msg.crc_extra))
176 
177  t.write(outf, """
178 
179 /// Message CRSs extra for detection incompatible XML changes
180 private let messageCRCsExtra: [UInt8: UInt8] = [${ARRAY_CONTENT}]
181 """, {'ARRAY_CONTENT' : ", ".join(crcs)})
182 
184  """Generate a CamelCase string from an underscore_string"""
185 
186  components = string.split('_')
187  string = ''
188 
189  for component in components:
190  if component in abbreviations:
191  string += component
192  else:
193  string += component[0].upper() + component[1:].lower()
194 
195  return string
196 
198  """Generate a lower-cased camelCase string from an underscore_string"""
199 
200  components = string.split('_')
201  string = components[0].lower()
202  for component in components[1:]:
203  string += component[0].upper() + component[1:].lower()
204 
205  return string
206 
207 def generate_enums_type_info(enums, msgs):
208  """Add camel case swift names for enums an entries, descriptions and sort enums alphabetically"""
209 
210  for enum in enums:
211  enum.swift_name = camel_case_from_underscores(enum.name)
212  enum.raw_value_type = get_enum_raw_type(enum, msgs)
213 
214  enum.formatted_description = ""
215  if enum.description:
216  enum.description = " ".join(enum.description.split())
217  enum.formatted_description = "/// %s\n" % enum.description
218 
219  for index, entry in enumerate(enum.entry):
220  if entry.name.endswith("_ENUM_END"):
221  enum.enum_end = entry.value
222  del enum.entry[index]
223 
224  all_entities = []
225  entities_info = []
226 
227  for entry in enum.entry:
228  name = entry.name.replace(enum.name + '_', '')
229  """Ensure that enums entry name does not start from digit"""
230  if name[0].isdigit():
231  name = "MAV_" + name
232  entry.swift_name = lower_camel_case_from_underscores(name)
233 
234  """Ensure that enums entry name does not match any swift keyword"""
235  if entry.swift_name in swift_keywords:
236  entry.swift_name = lower_camel_case_from_underscores("MAV_" + name)
237 
238  entry.formatted_description = ""
239  if entry.description:
240  entry.description = " ".join(entry.description.split())
241  entry.formatted_description = "\n\t/// " + entry.description + "\n"
242 
243  all_entities.append(entry.swift_name)
244  entities_info.append('("%s", "%s")' % (entry.name, entry.description.replace('"','\\"')))
245 
246  enum.all_entities = ", ".join(all_entities)
247  enum.entities_info = ", ".join(entities_info)
248  enum.entity_description = enum.description.replace('"','\\"')
249 
250  enums.sort(key = lambda enum : enum.swift_name)
251 
253  """Add proper formated variable names, initializers and type names to use in templates"""
254 
255  for msg in msgs:
256  msg.swift_name = camel_case_from_underscores(msg.name)
257 
258  msg.formatted_description = ""
259  if msg.description:
260  msg.description = " ".join(msg.description.split())
261  msg.formatted_description = "/// %s\n" % " ".join(msg.description.split())
262  msg.message_description = msg.description.replace('"','\\"')
263 
264  for field in msg.ordered_fields:
265  field.swift_name = lower_camel_case_from_underscores(field.name)
266  field.init_accessor = field.swift_name if field.swift_name != "data" else "self.%s" % field.swift_name
267  field.pack_accessor = field.swift_name if field.swift_name != "payload" else "self.%s" % field.swift_name
268  field.return_type = swift_types[field.type][0]
269 
270  # configure fields initializers
271  if field.enum:
272  # handle enums
273  field.return_type = camel_case_from_underscores(field.enum)
274  field.initial_value = "try data.enumeration(at: %u)" % field.wire_offset
275  field.payload_setter = "set(%s, at: %u)" % (field.pack_accessor, field.wire_offset)
276  elif field.array_length > 0:
277  if field.return_type == "String":
278  # handle strings
279  field.initial_value = "try data." + swift_types[field.type][2] % (field.wire_offset, field.array_length)
280  field.payload_setter = swift_types[field.type][3] % (field.pack_accessor, field.wire_offset, field.array_length)
281  else:
282  # other array types
283  field.return_type = "[%s]" % field.return_type
284  field.initial_value = "try data.array(at: %u, capacity: %u)" % (field.wire_offset, field.array_length)
285  field.payload_setter = "set(%s, at: %u, capacity: %u)" % (field.pack_accessor, field.wire_offset, field.array_length)
286  else:
287  # simple type field
288  field.initial_value = "try data." + swift_types[field.type][2] % field.wire_offset
289  field.payload_setter = swift_types[field.type][3] % (field.pack_accessor, field.wire_offset)
290 
291  field.formatted_description = ""
292  if field.description:
293  field.description = " ".join(field.description.split())
294  field.formatted_description = "\n\t/// " + field.description + "\n"
295 
296  fields_info = ['("%s", %u, "%s", %u, "%s")' % (field.swift_name, field.wire_offset, field.return_type, field.array_length, field.description.replace('"','\\"')) for field in msg.fields]
297  msg.fields_info = ", ".join(fields_info)
298 
299  msgs.sort(key = lambda msg : msg.id)
300 
301 def generate(basename, xml_list):
302  """Generate complete MAVLink Swift implemenation"""
303 
304  msgs = []
305  enums = []
306  filelist = []
307 
308  for xml in xml_list:
309  for msg in xml.message: msg.basename = xml.basename.title()
310  for enum in xml.enum: enum.basename = xml.basename.title()
311 
312  msgs.extend(xml.message)
313  enums.extend(xml.enum)
314  filelist.append(os.path.basename(xml.filename))
315 
316  generate_enums_type_info(enums, msgs)
318 
319  generate_mavlink(basename, filelist, xml_list, msgs)
320  generate_enums(basename, filelist, xml_list, enums, msgs)
321  generate_messages(basename, filelist, xml_list, msgs)


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