00001
00002 """
00003 Parse a MAVLink protocol XML file and generate Swift implementation
00004
00005 Copyright Max Odnovolyk 2015
00006 Released under GNU GPL version 3 or later
00007 """
00008
00009 import os
00010 from . import mavparse, mavtemplate
00011
00012 abbreviations = ["MAV", "PX4", "UDB", "PPZ", "PIXHAWK", "SLUGS", "FP", "ASLUAV", "VTOL", "ROI", "UART", "UDP", "IMU", "IMU2", "3D", "RC", "GPS", "GPS1", "GPS2", "NED", "RTK"]
00013 swift_types = {'char' : ("String", '"\\0"', "mavString(offset: %u, length: %u)"),
00014 'uint8_t' : ("UInt8", 0, "mavNumber(offset: %u)"),
00015 'int8_t' : ("Int8", 0, "mavNumber(offset: %u)"),
00016 'uint16_t' : ("UInt16", 0, "mavNumber(offset: %u)"),
00017 'int16_t' : ("Int16", 0, "mavNumber(offset: %u)"),
00018 'uint32_t' : ("UInt32", 0, "mavNumber(offset: %u)"),
00019 'int32_t' : ("Int32", 0, "mavNumber(offset: %u)"),
00020 'uint64_t' : ("UInt64", 0, "mavNumber(offset: %u)"),
00021 'int64_t' : ("Int64", 0, "mavNumber(offset: %u)"),
00022 'float' : ("Float", 0, "mavNumber(offset: %u)"),
00023 'double' : ("Double", 0, "mavNumber(offset: %u)"),
00024 'uint8_t_mavlink_version' : ("UInt8", 0, "mavNumber(offset: %u)")}
00025
00026 t = mavtemplate.MAVTemplate()
00027
00028 def generate_header(outf, filelist, xml):
00029 """Generate Swift file header with source files list and creation date"""
00030
00031 print("Generating Swift file header")
00032
00033 t.write(outf, """
00034 //
00035 // MAVLink.swift
00036 // MAVLink Micro Air Vehicle Communication Protocol
00037 //
00038 // Generated from ${FILELIST} on ${PARSE_TIME} by mavgen_swift.py
00039 // http://qgroundcontrol.org/mavlink/start
00040 //
00041
00042 import Foundation
00043
00044
00045 /**
00046 Common protocol for all MAVLink entities which describes type metadata properties
00047 */
00048 public protocol MAVLinkEntity: CustomStringConvertible, CustomDebugStringConvertible {
00049
00050 /// Original MAVLink enum name (from declarations xml)
00051 static var typeName: String { get }
00052
00053 /// Compact type description
00054 static var typeDescription: String { get }
00055
00056 /// Verbose type description
00057 static var typeDebugDescription: String { get }
00058 }
00059
00060
00061 // MARK: MAVLink enums
00062
00063
00064 /**
00065 Enum protocol description with common for all MAVLink enums property requirements
00066 */
00067 public protocol Enum: RawRepresentable, Equatable, MAVLinkEntity {
00068
00069 /// Array with all members of current enum
00070 static var allMembers: [Self] { get }
00071
00072 // Array with `Name` - `Description` tuples (values from declarations xml file)
00073 static var membersInfo: [(String, String)] { get }
00074
00075 /// Original MAVLinks enum member name (as declared in definitions xml file)
00076 var memberName: String { get }
00077
00078 /// Specific member description from definitions xml
00079 var memberDescription: String { get }
00080 }
00081
00082
00083 /**
00084 Enum protocol default implementations
00085 */
00086 extension Enum {
00087 public static var typeDebugDescription: String {
00088 // It seems Xcode 7 beta does not support default protocol implementations for type methods.
00089 // Calling this method without specific implementations inside enums will cause following error on Xcode 7.0 beta (7A120f):
00090 // "Command failed due to signal: Illegal instruction: 4"
00091 let cases = "\\n\\t".join(allMembers.map { $0.debugDescription })
00092 return "Enum \(typeName): \(typeDescription)\\nMembers:\\n\\t\(cases)"
00093 }
00094
00095 public var description: String {
00096 return memberName
00097 }
00098
00099 public var debugDescription: String {
00100 return "\(memberName): \(memberDescription)"
00101 }
00102
00103 public var memberName: String {
00104 return Self.membersInfo[Self.allMembers.indexOf(self)!].0
00105 }
00106
00107 public var memberDescription: String {
00108 return Self.membersInfo[Self.allMembers.indexOf(self)!].1
00109 }
00110 }
00111
00112 """, {'FILELIST' : ", ".join(filelist),
00113 'PARSE_TIME' : xml[0].parse_time})
00114
00115 def generate_enums(outf, enums, msgs):
00116 """Iterate through all enums and create Swift equivalents"""
00117
00118 print("Generating Enums")
00119
00120 for enum in enums:
00121 t.write(outf, """
00122 ${formatted_description}public enum ${swift_name}: ${raw_value_type}, Enum {
00123 ${{entry:${formatted_description}\tcase ${swift_name} = ${value}\n}}
00124 }
00125
00126 extension ${swift_name} {
00127 public static var typeName = "${name}"
00128 public static var typeDescription = "${entity_description}"
00129 public static var typeDebugDescription: String {
00130 let cases = "\\n\\t".join(allMembers.map { $0.debugDescription })
00131 return "Enum \(typeName): \(typeDescription)\\nMembers:\\n\\t\(cases)"
00132 }
00133 public static var allMembers = [${all_entities}]
00134 public static var membersInfo = [${entities_info}]
00135 }
00136
00137 """, enum)
00138
00139 def get_enum_raw_type(enum, msgs):
00140 """Search appropirate raw type for enums in messages fields"""
00141
00142 for msg in msgs:
00143 for field in msg.fields:
00144 if field.enum == enum.name:
00145 return swift_types[field.type][0]
00146 return "Int"
00147
00148 def generate_messages(outf, msgs):
00149 """Generate Swift structs to represent all MAVLink messages"""
00150
00151 print("Generating Messages")
00152
00153 t.write(outf, """
00154
00155 // MARK: MAVLink messages
00156
00157
00158 /**
00159 Message protocol describes common for all MAVLink messages properties and methods requirements
00160 */
00161 public protocol Message: MAVLinkEntity {
00162
00163 /**
00164 Initialize Message from received data
00165
00166 - Warning: Throws `ParserError` or `ParserEnumError` if any parsing error occurred
00167 */
00168 init(data: NSData) throws
00169
00170 /// Array of tuples with fields name, offset, type and description information
00171 static var fieldsInfo: [(String, Int, String, String)] { get }
00172
00173 /// All fields names and values of current Message
00174 var allFields: [(String, Any)] { get }
00175 }
00176
00177
00178 /**
00179 Message protocol default implementations
00180 */
00181 extension Message {
00182 public static var typeDebugDescription: String {
00183 // It seems Xcode 7 beta does not support default protocol implementations for type methods.
00184 // Calling this method without specific implementations inside messages will cause following error in Xcode 7.0 beta (7A120f):
00185 // "Command failed due to signal: Illegal instruction: 4"
00186 let fields = "\\n\\t".join(fieldsInfo.map { "\($0.0): \($0.2): \($0.3)" })
00187 return "Struct \(typeName): \(typeDescription)\\nFields:\\n\\t\(fields)"
00188 }
00189
00190 public var description: String {
00191 let describeField: ((String, Any)) -> String = { (let name, var value) in
00192 value = value is String ? "\\"\(value)\\"" : value
00193 return "\(name): \(value)"
00194 }
00195 let fieldsDescription = ", ".join(allFields.map(describeField))
00196 return "\(self.dynamicType)(\(fieldsDescription))"
00197 }
00198
00199 public var debugDescription: String {
00200 let describeFieldVerbose: ((String, Any)) -> String = { (let name, var value) in
00201 value = value is String ? "\\"\(value)\\"" : value
00202 let (_, _, _, description) = Self.fieldsInfo.filter { $0.0 == name }.first!
00203 return "\(name) = \(value) : \(description)"
00204 }
00205 let fieldsDescription = "\\n\\t".join(allFields.map(describeFieldVerbose))
00206 return "\(Self.typeName): \(Self.typeDescription)\\nFields:\\n\\t\(fieldsDescription)"
00207 }
00208
00209 public var allFields: [(String, Any)] {
00210 var result: [(String, Any)] = []
00211 let mirror = reflect(self)
00212 for i in 0..<mirror.count {
00213 result.append((mirror[i].0, mirror[i].1.value))
00214 }
00215 return result
00216 }
00217 }
00218
00219 """)
00220
00221 for msg in msgs:
00222 t.write(outf, """
00223 ${formatted_description}public struct ${swift_name}: Message {
00224 ${{fields:${formatted_description}\tpublic let ${swift_name}: ${return_type}\n}}
00225
00226 public init(data: NSData) throws {
00227 ${{ordered_fields:\t\tself.${swift_name} = ${initial_value}\n}}
00228 }
00229 }
00230
00231 extension ${swift_name} {
00232 public static var typeName = "${name}"
00233 public static var typeDescription = "${message_description}"
00234 public static var typeDebugDescription: String {
00235 let fields = "\\n\\t".join(fieldsInfo.map { "\($0.0): \($0.2): \($0.3)" })
00236 return "Struct \(typeName): \(typeDescription)\\nFields:\\n\\t\(fields)"
00237 }
00238 public static var fieldsInfo = [${fields_info}]
00239 }
00240
00241 """, msg)
00242
00243 def append_static_code(filename, outf):
00244 """Open and copy static code from specified file"""
00245
00246 basepath = os.path.dirname(os.path.realpath(__file__))
00247 filepath = os.path.join(basepath, 'swift/%s' % filename)
00248
00249 print("Appending content of %s" % filename)
00250
00251 with open(filepath) as inf:
00252 for line in inf:
00253 outf.write(line)
00254
00255 def generate_message_mappings_array(outf, msgs):
00256 """Create array for mapping message Ids to proper structs"""
00257
00258 classes = []
00259 for msg in msgs:
00260 classes.append("%u: %s.self" % (msg.id, msg.swift_name))
00261 t.write(outf, """
00262
00263
00264
00265 /**
00266 Array for mapping message id to proper struct
00267 */
00268 private let messageIdToClass: [UInt8: Message.Type] = [${ARRAY_CONTENT}]
00269 """, {'ARRAY_CONTENT' : ", ".join(classes)})
00270
00271 def generate_message_lengths_array(outf, msgs):
00272 """Create array with message lengths to validate known message lengths"""
00273
00274
00275 lengths = []
00276 for msg in msgs:
00277 lengths.append("%u: %u" % (msg.id, msg.wire_length))
00278
00279 t.write(outf, """
00280
00281
00282 /**
00283 Message lengths array for known messages length validation
00284 */
00285 private let messageLengths: [UInt8: UInt8] = [${ARRAY_CONTENT}]
00286 """, {'ARRAY_CONTENT' : ", ".join(lengths)})
00287
00288 def generate_message_crc_extra_array(outf, msgs):
00289 """Add array with CRC extra values to detect incompatible XML changes"""
00290
00291 crcs = []
00292 for msg in msgs:
00293 crcs.append("%u: %u" % (msg.id, msg.crc_extra))
00294
00295 t.write(outf, """
00296
00297
00298 /**
00299 Message CRSs extra for detection incompatible XML changes
00300 */
00301 private let messageCrcsExtra: [UInt8: UInt8] = [${ARRAY_CONTENT}]
00302 """, {'ARRAY_CONTENT' : ", ".join(crcs)})
00303
00304 def camel_case_from_underscores(string):
00305 """Generate a CamelCase string from an underscore_string"""
00306
00307 components = string.split('_')
00308 string = ''
00309
00310 for component in components:
00311 if component in abbreviations:
00312 string += component
00313 else:
00314 string += component[0].upper() + component[1:].lower()
00315
00316 return string
00317
00318 def lower_camel_case_from_underscores(string):
00319 """Generate a lower-cased camelCase string from an underscore_string"""
00320
00321 components = string.split('_')
00322 string = components[0]
00323 for component in components[1:]:
00324 string += component[0].upper() + component[1:]
00325
00326 return string
00327
00328 def generate_enums_info(enums, msgs):
00329 """Add camel case swift names for enums an entries, descriptions and sort enums alphabetically"""
00330
00331 for enum in enums:
00332 enum.swift_name = camel_case_from_underscores(enum.name)
00333 enum.raw_value_type = get_enum_raw_type(enum, msgs)
00334
00335 enum.formatted_description = ""
00336 if enum.description:
00337 enum.description = " ".join(enum.description.split())
00338 enum.formatted_description = "\n/**\n %s\n*/\n" % enum.description
00339
00340 all_entities = []
00341 entities_info = []
00342
00343 for entry in enum.entry:
00344 name = entry.name.replace(enum.name + '_', '')
00345 """Ensure that enums entry name does not start from digit"""
00346 if name[0].isdigit():
00347 name = "MAV_" + name
00348 entry.swift_name = camel_case_from_underscores(name)
00349
00350 entry.formatted_description = ""
00351 if entry.description:
00352 entry.description = " ".join(entry.description.split())
00353 entry.formatted_description = "\n\t/// " + entry.description + "\n"
00354
00355 all_entities.append(entry.swift_name)
00356 entities_info.append('("%s", "%s")' % (entry.name, entry.description.replace('"','\\"')))
00357
00358 enum.all_entities = ", ".join(all_entities)
00359 enum.entities_info = ", ".join(entities_info)
00360 enum.entity_description = enum.description.replace('"','\\"')
00361
00362 enums.sort(key = lambda enum : enum.swift_name)
00363
00364 def generate_messages_info(msgs):
00365 """Add proper formated variable names, initializers and type names to use in templates"""
00366
00367 for msg in msgs:
00368 msg.swift_name = camel_case_from_underscores(msg.name)
00369
00370 msg.formatted_description = ""
00371 if msg.description:
00372 msg.description = " ".join(msg.description.split())
00373 msg.formatted_description = "\n/**\n %s\n*/\n" % " ".join(msg.description.split())
00374 msg.message_description = msg.description.replace('"','\\"')
00375
00376 for field in msg.ordered_fields:
00377 field.swift_name = lower_camel_case_from_underscores(field.name)
00378 field.return_type = swift_types[field.type][0]
00379
00380
00381 if field.enum:
00382
00383 field.return_type = camel_case_from_underscores(field.enum)
00384 field.initial_value = "try data.mavEnumeration(offset: %u)" % field.wire_offset
00385 elif field.array_length > 0:
00386 if field.return_type == "String":
00387
00388 field.initial_value = "data." + swift_types[field.type][2] % (field.wire_offset, field.array_length)
00389 else:
00390
00391 field.return_type = "[%s]" % field.return_type
00392 field.initial_value = "try data.mavArray(offset: %u, count: %u)" % (field.wire_offset, field.array_length)
00393 else:
00394
00395 field.initial_value = "try data." + swift_types[field.type][2] % field.wire_offset
00396
00397 field.formatted_description = ""
00398 if field.description:
00399 field.description = " ".join(field.description.split())
00400 field.formatted_description = "\n\t/// " + field.description + "\n"
00401
00402 fields_info = map(lambda field: '("%s", %u, "%s", "%s")' % (field.swift_name, field.wire_offset, field.return_type, field.description.replace('"','\\"')), msg.fields)
00403 msg.fields_info = ", ".join(fields_info)
00404
00405 msgs.sort(key = lambda msg : msg.id)
00406
00407 def generate(basename, xml_list):
00408 """Generate complete MAVLink Swift implemenation"""
00409
00410 if os.path.isdir(basename):
00411 filename = os.path.join(basename, 'MAVLink.swift')
00412 else:
00413 filename = basename
00414
00415 msgs = []
00416 enums = []
00417 filelist = []
00418 for xml in xml_list:
00419 msgs.extend(xml.message)
00420 enums.extend(xml.enum)
00421 filelist.append(os.path.basename(xml.filename))
00422
00423 outf = open(filename, "w")
00424 generate_header(outf, filelist, xml_list)
00425 generate_enums_info(enums, msgs)
00426 generate_enums(outf, enums, msgs)
00427 generate_messages_info(msgs)
00428 generate_messages(outf, msgs)
00429 append_static_code('Parser.swift', outf)
00430 generate_message_mappings_array(outf, msgs)
00431 generate_message_lengths_array(outf, msgs)
00432 generate_message_crc_extra_array(outf, msgs)
00433 outf.close()