3 Parse a MAVLink protocol XML file and generate Swift implementation 5 Copyright Max Odnovolyk 2015 6 Released under GNU GPL version 3 or later 8 from __future__
import print_function
11 from .
import mavparse, mavtemplate
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)")}
33 print(
"Generating MAVLink.swift file")
35 mavparse.mkdir_p(directory)
36 filename =
'MAVLink.swift' 37 filepath = os.path.join(directory, filename)
38 outf = open(filepath,
"w")
47 """Generate Swift file header with source files list and creation date""" 52 // MAVLink Protocol Swift Library 54 // Generated from ${FILELIST} on ${PARSE_TIME} by mavgen_swift.py 55 // https://github.com/modnovolyk/MAVLinkSwift 58 """, {
'FILENAME' : filename,
59 'FILELIST' :
", ".join(filelist),
60 'PARSE_TIME' : xml_list[0].parse_time})
63 """Iterate through all enums and create Swift equivalents""" 65 print(
"Generating Enumerations")
68 filename =
"%s%sEnum.swift" % (enum.swift_name, enum.basename)
69 filepath = os.path.join(directory, filename)
70 outf = open(filepath,
"w")
73 ${formatted_description}public enum ${swift_name}: ${raw_value_type} { 74 ${{entry:${formatted_description}\tcase ${swift_name} = ${value}\n}} 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}) 88 """Search appropirate raw type for enums in messages fields""" 91 for field
in msg.fields:
92 if field.enum == enum.name:
93 return swift_types[field.type][0]
97 """Generate Swift structs to represent all MAVLink messages""" 99 print(
"Generating Messages")
102 filename =
"%s%sMsg.swift" % (msg.swift_name, msg.basename)
103 filepath = os.path.join(directory, filename)
104 outf = open(filepath,
"w")
109 ${formatted_description}public struct ${swift_name} { 110 ${{fields:${formatted_description}\tpublic let ${swift_name}: ${return_type}\n}} 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}] 119 public init(data: Data) throws { 120 ${{ordered_fields:\t\t${init_accessor} = ${initial_value}\n}} 123 public func pack() throws -> Data { 124 var payload = Data(count: ${wire_length}) 125 ${{ordered_fields:\t\ttry payload.${payload_setter}\n}} 133 """Open and copy static code from specified file""" 135 basepath = os.path.dirname(os.path.realpath(__file__))
136 filepath = os.path.join(basepath,
'swift/%s' % filename)
138 print(
"Appending content of %s" % filename)
140 with open(filepath)
as inf:
145 """Create array for mapping message Ids to proper structs""" 149 classes.append(
"%u: %s.self" % (msg.id, msg.swift_name))
152 /// Array for mapping message id to proper struct 153 private let messageIdToClass: [UInt8: Message.Type] = [${ARRAY_CONTENT}] 154 """, {
'ARRAY_CONTENT' :
", ".join(classes)})
157 """Create array with message lengths to validate known message lengths""" 162 lengths.append(
"%u: %u" % (msg.id, msg.wire_length))
166 /// Message lengths array for known messages length validation 167 private let messageLengths: [UInt8: UInt8] = [${ARRAY_CONTENT}] 168 """, {
'ARRAY_CONTENT' :
", ".join(lengths)})
171 """Add array with CRC extra values to detect incompatible XML changes""" 175 crcs.append(
"%u: %u" % (msg.id, msg.crc_extra))
179 /// Message CRSs extra for detection incompatible XML changes 180 private let messageCRCsExtra: [UInt8: UInt8] = [${ARRAY_CONTENT}] 181 """, {
'ARRAY_CONTENT' :
", ".join(crcs)})
184 """Generate a CamelCase string from an underscore_string""" 186 components = string.split(
'_')
189 for component
in components:
190 if component
in abbreviations:
193 string += component[0].upper() + component[1:].lower()
198 """Generate a lower-cased camelCase string from an underscore_string""" 200 components = string.split(
'_')
201 string = components[0].lower()
202 for component
in components[1:]:
203 string += component[0].upper() + component[1:].lower()
208 """Add camel case swift names for enums an entries, descriptions and sort enums alphabetically""" 214 enum.formatted_description =
"" 216 enum.description =
" ".join(enum.description.split())
217 enum.formatted_description =
"/// %s\n" % enum.description
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]
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():
234 """Ensure that enums entry name does not match any swift keyword""" 235 if entry.swift_name
in swift_keywords:
238 entry.formatted_description =
"" 239 if entry.description:
240 entry.description =
" ".join(entry.description.split())
241 entry.formatted_description =
"\n\t/// " + entry.description +
"\n" 243 all_entities.append(entry.swift_name)
244 entities_info.append(
'("%s", "%s")' % (entry.name, entry.description.replace(
'"',
'\\"')))
246 enum.all_entities =
", ".join(all_entities)
247 enum.entities_info =
", ".join(entities_info)
248 enum.entity_description = enum.description.replace(
'"',
'\\"')
250 enums.sort(key =
lambda enum : enum.swift_name)
253 """Add proper formated variable names, initializers and type names to use in templates""" 258 msg.formatted_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(
'"',
'\\"')
264 for field
in msg.ordered_fields:
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]
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":
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)
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)
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)
291 field.formatted_description =
"" 292 if field.description:
293 field.description =
" ".join(field.description.split())
294 field.formatted_description =
"\n\t/// " + field.description +
"\n" 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)
299 msgs.sort(key =
lambda msg : msg.id)
302 """Generate complete MAVLink Swift implemenation""" 309 for msg
in xml.message: msg.basename = xml.basename.title()
310 for enum
in xml.enum: enum.basename = xml.basename.title()
312 msgs.extend(xml.message)
313 enums.extend(xml.enum)
314 filelist.append(os.path.basename(xml.filename))
def generate_messages(directory, filelist, xml_list, msgs)
def get_enum_raw_type(enum, msgs)
def generate_enums_type_info(enums, msgs)
def generate_message_crc_extra_array(outf, msgs)
def lower_camel_case_from_underscores(string)
def generate_enums(directory, filelist, xml_list, enums, msgs)
def generate_mavlink(directory, filelist, xml_list, msgs)
def generate_messages_type_info(msgs)
def append_static_code(filename, outf)
def generate_header(outf, filelist, xml_list, filename)
def camel_case_from_underscores(string)
def generate_message_mappings_array(outf, msgs)
def generate(basename, xml_list)
def generate_message_lengths_array(outf, msgs)