MAVLink.swift 40 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062
  1. import Foundation
  2. /// Common protocol for all MAVLink entities which describes types
  3. /// metadata properties.
  4. public protocol MAVLinkEntity: CustomStringConvertible, CustomDebugStringConvertible {
  5. /// Original MAVLink enum name (from declarations xml)
  6. static var typeName: String { get }
  7. /// Compact type description
  8. static var typeDescription: String { get }
  9. /// Verbose type description
  10. static var typeDebugDescription: String { get }
  11. }
  12. // MARK: - Enumeration protocol
  13. /// Enumeration protocol description with common for all MAVLink enums
  14. /// properties requirements.
  15. public protocol Enumeration: RawRepresentable, Equatable, MAVLinkEntity {
  16. /// Array with all members of current enum
  17. static var allMembers: [Self] { get }
  18. // Array with `Name` - `Description` tuples (values from declarations xml file)
  19. static var membersDescriptions: [(String, String)] { get }
  20. /// `ENUM_END` flag for checking if enum case value is valid
  21. static var enumEnd: UInt { get }
  22. /// Original MAVLinks enum member name (as declared in definition's xml file)
  23. var memberName: String { get }
  24. /// Specific member description from definitions xml
  25. var memberDescription: String { get }
  26. }
  27. /// Enumeration protocol default behaviour implementation.
  28. extension Enumeration {
  29. public static var typeDebugDescription: String {
  30. let cases = allMembers.map({ $0.debugDescription }).joined(separator: "\\n\\t")
  31. return "Enum \(typeName): \(typeDescription)\\nMembers:\\n\\t\(cases)"
  32. }
  33. public var description: String {
  34. return memberName
  35. }
  36. public var debugDescription: String {
  37. return "\(memberName): \(memberDescription)"
  38. }
  39. public var memberName: String {
  40. return Self.membersDescriptions[Self.allMembers.index(of: self)!].0
  41. }
  42. public var memberDescription: String {
  43. return Self.membersDescriptions[Self.allMembers.index(of: self)!].1
  44. }
  45. }
  46. // MARK: - Message protocol
  47. /// Message field definition tuple.
  48. public typealias FieldDefinition = (name: String, offset: Int, type: String, length: UInt, description: String)
  49. /// Message protocol describes all common MAVLink messages properties and
  50. /// methods requirements.
  51. public protocol Message: MAVLinkEntity {
  52. static var id: UInt8 { get }
  53. static var payloadLength: UInt8 { get }
  54. /// Array of tuples with field definition info
  55. static var fieldDefinitions: [FieldDefinition] { get }
  56. /// All field's names and values of current Message
  57. var allFields: [(String, Any)] { get }
  58. /// Initialize Message from received data.
  59. ///
  60. /// - parameter data: Data to decode.
  61. ///
  62. /// - throws: Throws `ParseError` or `ParseEnumError` if any parsing errors
  63. /// occur.
  64. init(data: Data) throws
  65. /// Returns `Data` representation of current `Message` struct guided
  66. /// by format from `fieldDefinitions`.
  67. ///
  68. /// - throws: Throws `PackError` if any of message fields do not comply
  69. /// format from `fieldDefinitions`.
  70. ///
  71. /// - returns: Receiver's `Data` representation
  72. func pack() throws -> Data
  73. }
  74. /// Message protocol default behaviour implementation.
  75. extension Message {
  76. public static var payloadLength: UInt8 {
  77. return messageLengths[id] ?? Packet.Constant.maxPayloadLength
  78. }
  79. public static var typeDebugDescription: String {
  80. let fields = fieldDefinitions.map({ "\($0.name): \($0.type): \($0.description)" }).joined(separator: "\n\t")
  81. return "Struct \(typeName): \(typeDescription)\nFields:\n\t\(fields)"
  82. }
  83. public var description: String {
  84. let describeField: ((String, Any)) -> String = { (name, value) in
  85. let valueString = value is String ? "\"\(value)\"" : value
  86. return "\(name): \(valueString)"
  87. }
  88. let fieldsDescription = allFields.map(describeField).joined(separator: ", ")
  89. return "\(type(of: self))(\(fieldsDescription))"
  90. }
  91. public var debugDescription: String {
  92. let describeFieldVerbose: ((String, Any)) -> String = { (name, value) in
  93. let valueString = value is String ? "\"\(value)\"" : value
  94. let (_, _, _, _, description) = Self.fieldDefinitions.filter { $0.name == name }.first!
  95. return "\(name) = \(valueString) : \(description)"
  96. }
  97. let fieldsDescription = allFields.map(describeFieldVerbose).joined(separator: "\n\t")
  98. return "\(Self.typeName): \(Self.typeDescription)\nFields:\n\t\(fieldsDescription)"
  99. }
  100. public var allFields: [(String, Any)] {
  101. var result: [(String, Any)] = []
  102. let mirror = Mirror(reflecting: self)
  103. for case let (label?, value) in mirror.children {
  104. result.append((label, value))
  105. }
  106. return result
  107. }
  108. }
  109. // MARK: - Type aliases
  110. public typealias Channel = UInt8
  111. // MARK: - Errors
  112. public protocol MAVLinkError: Error, CustomStringConvertible, CustomDebugStringConvertible { }
  113. // MARK: Parsing error enumeration
  114. /// Parsing errors
  115. public enum ParseError: MAVLinkError {
  116. /// Size of expected number is larger than receiver's data length.
  117. /// - offset: Expected number offset in received data.
  118. /// - size: Expected number size in bytes.
  119. /// - upperBound: The number of bytes in the data.
  120. case valueSizeOutOfBounds(offset: Int, size: Int, upperBound: Int)
  121. /// Data contains non ASCII characters.
  122. /// - offset: String offset in received data.
  123. /// - length: Expected length of string to read.
  124. case invalidStringEncoding(offset: Int, length: Int)
  125. /// Length check of payload for known `messageId` did fail.
  126. /// - messageId: Id of expected `Message` type.
  127. /// - receivedLength: Received payload length.
  128. /// - properLength: Expected payload length for `Message` type.
  129. case invalidPayloadLength(messageId: UInt8, receivedLength: UInt8, expectedLength: UInt8)
  130. /// Received `messageId` was not recognized so we can't create appropriate
  131. /// `Message`.
  132. /// - messageId: Id of the message that was not found in the known message
  133. /// list (`messageIdToClass` array).
  134. case unknownMessageId(messageId: UInt8)
  135. /// Checksum check failed. Message id is known but calculated CRC bytes
  136. /// do not match received CRC value.
  137. /// - messageId: Id of expected `Message` type.
  138. case badCRC(messageId: UInt8)
  139. }
  140. extension ParseError {
  141. /// Textual representation used when written to output stream.
  142. public var description: String {
  143. switch self {
  144. case .valueSizeOutOfBounds:
  145. return "ParseError.valueSizeOutOfBounds"
  146. case .invalidStringEncoding:
  147. return "ParseError.invalidStringEncoding"
  148. case .invalidPayloadLength:
  149. return "ParseError.invalidPayloadLength"
  150. case .unknownMessageId:
  151. return "ParseError.unknownMessageId"
  152. case .badCRC:
  153. return "ParseError.badCRC"
  154. }
  155. }
  156. /// Debug textual representation used when written to output stream, which
  157. /// includes all associated values and their labels.
  158. public var debugDescription: String {
  159. switch self {
  160. case let .valueSizeOutOfBounds(offset, size, upperBound):
  161. return "ParseError.valueSizeOutOfBounds(offset: \(offset), size: \(size), upperBound: \(upperBound))"
  162. case let .invalidStringEncoding(offset, length):
  163. return "ParseError.invalidStringEncoding(offset: \(offset), length: \(length))"
  164. case let .invalidPayloadLength(messageId, receivedLength, expectedLength):
  165. return "ParseError.invalidPayloadLength(messageId: \(messageId), receivedLength: \(receivedLength), expectedLength: \(expectedLength))"
  166. case let .unknownMessageId(messageId):
  167. return "ParseError.unknownMessageId(messageId: \(messageId))"
  168. case let .badCRC(messageId):
  169. return "ParseError.badCRC(messageId: \(messageId))"
  170. }
  171. }
  172. }
  173. // MARK: Parsing enumeration error
  174. /// Special error type for returning Enum parsing errors with details in associated
  175. /// values (types of these values are not compatible with `ParseError` enum).
  176. public enum ParseEnumError<T: RawRepresentable>: MAVLinkError {
  177. /// Enumeration case with `rawValue` at `valueOffset` was not found in
  178. /// `enumType` enumeration.
  179. /// - enumType: Type of expected enumeration.
  180. /// - rawValue: Raw value that was not found in `enumType`.
  181. /// - valueOffset: Value offset in received payload data.
  182. case unknownValue(enumType: T.Type, rawValue: T.RawValue, valueOffset: Int)
  183. }
  184. extension ParseEnumError {
  185. /// Textual representation used when written to the output stream.
  186. public var description: String {
  187. switch self {
  188. case .unknownValue:
  189. return "ParseEnumError.unknownValue"
  190. }
  191. }
  192. /// Debug textual representation used when written to the output stream, which
  193. /// includes all associated values and their labels.
  194. public var debugDescription: String {
  195. switch self {
  196. case let .unknownValue(enumType, rawValue, valueOffset):
  197. return "ParseEnumError.unknownValue(enumType: \(enumType), rawValue: \(rawValue), valueOffset: \(valueOffset))"
  198. }
  199. }
  200. }
  201. // MARK: Packing errors
  202. /// Errors that can occur while packing `Message` for sending.
  203. public enum PackError: MAVLinkError {
  204. /// Size of received value (together with offset) is out of receiver's length.
  205. /// - offset: Expected value offset in payload.
  206. /// - size: Provided field value size in bytes.
  207. /// - upperBound: Available payload length.
  208. case valueSizeOutOfBounds(offset: Int, size: Int, upperBound: Int)
  209. /// Length check for provided field value did fail.
  210. /// - offset: Expected value offset in payload.
  211. /// - providedValueLength: Count of elements (characters) in provided value.
  212. /// - allowedLength: Maximum number of elements (characters) allowed in field.
  213. case invalidValueLength(offset: Int, providedValueLength: Int, allowedLength: Int)
  214. /// String field contains non ASCII characters.
  215. /// - offset: Expected value offset in payload.
  216. /// - string: Original string.
  217. case invalidStringEncoding(offset: Int, string: String)
  218. /// CRC extra byte not found for provided `messageId` type.
  219. /// - messageId: Id of message type.
  220. case crcExtraNotFound(messageId: UInt8)
  221. /// Packet finalization process failed due to `message` absence.
  222. case messageNotSet
  223. }
  224. extension PackError {
  225. /// Textual representation used when written to the output stream.
  226. public var description: String {
  227. switch self {
  228. case .valueSizeOutOfBounds:
  229. return "PackError.valueSizeOutOfBounds"
  230. case .invalidValueLength:
  231. return "PackError.invalidValueLength"
  232. case .invalidStringEncoding:
  233. return "PackError.invalidStringEncoding"
  234. case .crcExtraNotFound:
  235. return "PackError.crcExtraNotFound"
  236. case .messageNotSet:
  237. return "PackError.messageNotSet"
  238. }
  239. }
  240. /// Debug textual representation used when written to the output stream, which
  241. /// includes all associated values and their labels.
  242. public var debugDescription: String {
  243. switch self {
  244. case let .valueSizeOutOfBounds(offset, size, upperBound):
  245. return "PackError.valueSizeOutOfBounds(offset: \(offset), size: \(size), upperBound: \(upperBound))"
  246. case let .invalidValueLength(offset, providedValueLength, allowedLength):
  247. return "PackError.invalidValueLength(offset: \(offset), providedValueLength: \(providedValueLength), allowedLength: \(allowedLength))"
  248. case let .invalidStringEncoding(offset, string):
  249. return "PackError.invalidStringEncoding(offset: \(offset), string: \(string))"
  250. case let .crcExtraNotFound(messageId):
  251. return "PackError.crcExtraNotFound(messageId: \(messageId))"
  252. case .messageNotSet:
  253. return "PackError.messageNotSet"
  254. }
  255. }
  256. }
  257. // MARK: - Delegate protocol
  258. /// Alternative way to receive parsed Messages, finalized packet's data and all
  259. /// errors is to implement this protocol and set as `MAVLink`'s delegate.
  260. public protocol MAVLinkDelegate: class {
  261. /// Called when MAVLink packet is successfully received, payload length
  262. /// and CRC checks are passed.
  263. ///
  264. /// - parameter packet: Completely received `Packet`.
  265. /// - parameter channel: Channel on which `packet` was received.
  266. /// - parameter link: `MAVLink` object that handled `packet`.
  267. func didReceive(packet: Packet, on channel: Channel, via link: MAVLink)
  268. /// Packet receiving failed due to `InvalidPayloadLength` or `BadCRC` error.
  269. ///
  270. /// - parameter packet: Partially received `Packet`.
  271. /// - parameter error: Error that occurred while receiving `data`
  272. /// (`InvalidPayloadLength` or `BadCRC` error).
  273. /// - parameter channel: Channel on which `packet` was received.
  274. /// - parameter link: `MAVLink` object that received `data`.
  275. func didFailToReceive(packet: Packet?, with error: MAVLinkError, on channel: Channel, via link: MAVLink)
  276. /// Called when received data was successfully parsed into appropriate
  277. /// `message` structure.
  278. ///
  279. /// - parameter message: Successfully parsed `Message`.
  280. /// - parameter packet: Completely received `Packet`.
  281. /// - parameter channel: Channel on which `message` was received.
  282. /// - parameter link: `MAVLink` object that handled `packet`.
  283. func didParse(message: Message, from packet: Packet, on channel: Channel, via link: MAVLink)
  284. /// Called when `packet` completely received but `MAVLink` was not able to
  285. /// finish `Message` processing due to unknown `messageId` or type validation
  286. /// errors.
  287. ///
  288. /// - parameter packet: Completely received `Packet`.
  289. /// - parameter error: Error that occurred while parsing `packet`'s
  290. /// payload into `Message`.
  291. /// - parameter channel: Channel on which `message` was received.
  292. /// - parameter link: `MAVLink` object that handled `packet`.
  293. func didFailToParseMessage(from packet: Packet, with error: MAVLinkError, on channel: Channel, via link: MAVLink)
  294. /// Called when message is finalized and ready for sending to aircraft.
  295. ///
  296. /// - parameter message: Message to be sent.
  297. /// - parameter data: Compiled data that represents `message`.
  298. /// - parameter channel: Channel on which `message` should be sent.
  299. /// - parameter link: `MAVLink` object that handled `message`.
  300. func didFinalize(message: Message, from packet: Packet, to data: Data, on channel: Channel, in link: MAVLink)
  301. }
  302. // MARK: - Classes implementations
  303. /// Main MAVLink class, performs `Packet` receiving, recognition, validation,
  304. /// `Message` structure creation and `Message` packing, finalizing for sending.
  305. /// Also returns errors through delegation if any errors occurred.
  306. /// - warning: Supports only 1.0 version of the MAVlink wire protocol.
  307. public class MAVLink {
  308. /// States for the parsing state machine.
  309. enum ParseState {
  310. case uninit
  311. case idle
  312. case gotStx
  313. case gotSequence
  314. case gotLength
  315. case gotSystemId
  316. case gotComponentId
  317. case gotMessageId
  318. case gotPayload
  319. case gotCRC1
  320. case gotBadCRC1
  321. }
  322. enum Framing: UInt8 {
  323. case incomplete = 0
  324. case ok = 1
  325. case badCRC = 2
  326. }
  327. /// Storage for MAVLink parsed packets count, states and errors statistics.
  328. class Status {
  329. /// Number of received packets
  330. var packetReceived: Framing = .incomplete
  331. /// Number of parse errors
  332. var parseError: UInt8 = 0
  333. /// Parsing state machine
  334. var parseState: ParseState = .uninit
  335. /// Sequence number of the last received packet
  336. var currentRxSeq: UInt8 = 0
  337. /// Sequence number of the last sent packet
  338. var currentTxSeq: UInt8 = 0
  339. /// Received packets
  340. var packetRxSuccessCount: UInt16 = 0
  341. /// Number of packet drops
  342. var packetRxDropCount: UInt16 = 0
  343. }
  344. /// MAVLink Packets and States buffers
  345. let channelBuffers = (0 ..< Channel.max).map({ _ in Packet() })
  346. let channelStatuses = (0 ..< Channel.max).map({ _ in Status() })
  347. /// Object to pass received packets, messages, errors, finalized data to.
  348. public weak var delegate: MAVLinkDelegate?
  349. /// Enable this option to check the length of each message. This allows
  350. /// invalid messages to be caught much sooner. Use it if the transmission
  351. /// medium is prone to missing (or extra) characters (e.g. a radio that
  352. /// fades in and out). Use only if the channel will contain message
  353. /// types listed in the headers.
  354. public var checkMessageLength = true
  355. /// Use one extra CRC that is added to the message CRC to detect mismatches
  356. /// in the message specifications. This is to prevent that two devices using
  357. /// different message versions incorrectly decode a message with the same
  358. /// length. Defined as `let` as we support only the latest version (1.0) of
  359. /// the MAVLink wire protocol.
  360. public let crcExtra = true
  361. public init() { }
  362. /// This is a convenience function which handles the complete MAVLink
  363. /// parsing. The function will parse one byte at a time and return the
  364. /// complete packet once it could be successfully decoded. Checksum and
  365. /// other failures will be delegated to `delegate`.
  366. ///
  367. /// - parameter char: The char to parse.
  368. /// - parameter channel: Id of the current channel. This allows to parse
  369. /// different channels with this function. A channel is not a physical
  370. /// message channel like a serial port, but a logic partition of the
  371. /// communication streams in this case.
  372. ///
  373. /// - returns: Returns `nil` if packet could be decoded at the moment,
  374. /// the `Packet` structure else.
  375. public func parse(char: UInt8, channel: Channel) -> Packet? {
  376. /// Function to check if current char is Stx byte. If current char is
  377. /// STX, modifies current rxpack and status.
  378. func handleSTX(char: UInt8, rxpack: Packet, status: Status) {
  379. if char == Packet.Constant.packetStx {
  380. rxpack.length = 0
  381. rxpack.channel = channel
  382. rxpack.magic = char
  383. rxpack.checksum.start()
  384. status.parseState = .gotStx
  385. }
  386. }
  387. let rxpack = channelBuffers[Int(channel)]
  388. let status = channelStatuses[Int(channel)]
  389. status.packetReceived = .incomplete
  390. switch status.parseState {
  391. case .uninit, .idle:
  392. handleSTX(char: char, rxpack: rxpack, status: status)
  393. case .gotStx:
  394. rxpack.length = char
  395. rxpack.payload.count = 0
  396. rxpack.checksum.accumulate(char)
  397. status.parseState = .gotLength
  398. case .gotLength:
  399. rxpack.sequence = char
  400. rxpack.checksum.accumulate(char)
  401. status.parseState = .gotSequence
  402. case .gotSequence:
  403. rxpack.systemId = char
  404. rxpack.checksum.accumulate(char)
  405. status.parseState = .gotSystemId
  406. case .gotSystemId:
  407. rxpack.componentId = char
  408. rxpack.checksum.accumulate(char)
  409. status.parseState = .gotComponentId
  410. case .gotComponentId:
  411. // Check Message length if `checkMessageLength` enabled and
  412. // `messageLengths` contains proper id. If `messageLengths` does not
  413. // contain info for current messageId, parsing will fail later on CRC check.
  414. if checkMessageLength {
  415. let messageLength = messageLengths[char] ?? 0
  416. if rxpack.length != messageLength {
  417. status.parseError += 1
  418. status.parseState = .idle
  419. let error = ParseError.invalidPayloadLength(messageId: char, receivedLength: rxpack.length, expectedLength: messageLength)
  420. delegate?.didFailToReceive(packet: nil, with: error, on: channel, via: self)
  421. break
  422. }
  423. }
  424. rxpack.messageId = char
  425. rxpack.checksum.accumulate(char)
  426. if rxpack.length == 0 {
  427. status.parseState = .gotPayload
  428. } else {
  429. status.parseState = .gotMessageId
  430. }
  431. case .gotMessageId:
  432. rxpack.payload.append(char)
  433. rxpack.checksum.accumulate(char)
  434. if rxpack.payload.count == Int(rxpack.length) {
  435. status.parseState = .gotPayload
  436. }
  437. case .gotPayload:
  438. if crcExtra && (messageCRCsExtra[rxpack.messageId] != nil) {
  439. rxpack.checksum.accumulate(messageCRCsExtra[rxpack.messageId]!)
  440. }
  441. rxpack.payload.append(char)
  442. if char != rxpack.checksum.lowByte {
  443. status.parseState = .gotBadCRC1
  444. fallthrough
  445. } else {
  446. status.parseState = .gotCRC1
  447. }
  448. case .gotCRC1, .gotBadCRC1:
  449. if (status.parseState == .gotBadCRC1) || (char != rxpack.checksum.highByte) {
  450. status.parseError += 1
  451. status.packetReceived = .badCRC
  452. let error = messageIdToClass[rxpack.messageId] == nil ? ParseError.unknownMessageId(messageId: rxpack.messageId) : ParseError.badCRC(messageId: rxpack.messageId)
  453. delegate?.didFailToReceive(packet: Packet(packet: rxpack), with: error, on: channel, via: self)
  454. handleSTX(char: char, rxpack: rxpack, status: status)
  455. } else {
  456. // Successfully got message
  457. rxpack.payload.append(char)
  458. status.packetReceived = .ok
  459. }
  460. status.parseState = .idle
  461. }
  462. defer {
  463. // Сollect stat here
  464. status.parseError = 0
  465. }
  466. // If a packet has been sucessfully received
  467. guard status.packetReceived == .ok else {
  468. return nil
  469. }
  470. // Copy and delegate received packet
  471. let packet = Packet(packet: rxpack)
  472. delegate?.didReceive(packet: packet, on: channel, via: self)
  473. status.currentRxSeq = rxpack.sequence
  474. // Initial condition: If no packet has been received so far, drop count is undefined
  475. if status.packetRxSuccessCount == 0 {
  476. status.packetRxDropCount = 0
  477. }
  478. // Count this packet as received
  479. status.packetRxSuccessCount = status.packetRxSuccessCount &+ 1
  480. // Try to create appropriate Message structure, delegate results
  481. guard let messageClass = messageIdToClass[packet.messageId] else {
  482. let error = ParseError.unknownMessageId(messageId: rxpack.messageId)
  483. delegate?.didFailToParseMessage(from: packet, with: error, on: channel, via: self)
  484. return packet
  485. }
  486. do {
  487. packet.message = try messageClass.init(data: rxpack.payload)
  488. delegate?.didParse(message: packet.message!, from: packet, on: channel, via: self)
  489. } catch {
  490. delegate?.didFailToParseMessage(from: packet, with: error as! MAVLinkError, on: channel, via: self)
  491. return packet
  492. }
  493. return packet
  494. }
  495. /// Parse new portion of data, then call `messageHandler` if new message
  496. /// is available.
  497. ///
  498. /// - parameter data: Data to be parsed.
  499. /// - parameter channel: Id of the current channel. This allows to
  500. /// parse different channels with this function. A channel is not a physical
  501. /// message channel like a serial port, but a logic partition of the
  502. /// communication streams in this case.
  503. /// - parameter messageHandler: The message handler to call when the
  504. /// provided data is enough to complete message parsing. Unless you have
  505. /// provided a custom delegate, this parameter must not be `nil`, because
  506. /// there is no other way to retrieve the parsed message and packet.
  507. public func parse(data: Data, channel: Channel, messageHandler: ((Message, Packet) -> Void)? = nil) {
  508. data.forEach { byte in
  509. if let packet = parse(char: byte, channel: channel), let message = packet.message, let messageHandler = messageHandler {
  510. messageHandler(message, packet)
  511. }
  512. }
  513. }
  514. /// Prepare `message` bytes for sending, pass to `delegate` for further
  515. /// processing and increase sequence counter.
  516. ///
  517. /// - parameter message: Message to be compiled into bytes and sent.
  518. /// - parameter systemId: Id of the sending (this) system.
  519. /// - parameter componentId: Id of the sending component.
  520. /// - parameter channel: Id of the current channel.
  521. ///
  522. /// - throws: Throws `PackError`.
  523. public func dispatch(message: Message, systemId: UInt8, componentId: UInt8, channel: Channel) throws {
  524. let channelStatus = channelStatuses[Int(channel)]
  525. let packet = Packet(message: message, systemId: systemId, componentId: componentId, channel: channel)
  526. let data = try packet.finalize(sequence: channelStatus.currentTxSeq)
  527. delegate?.didFinalize(message: message, from: packet, to: data, on: channel, in: self)
  528. channelStatus.currentTxSeq = channelStatus.currentTxSeq &+ 1
  529. }
  530. }
  531. /// MAVLink Packet structure to store received data that is not full message yet.
  532. /// Contains additional to Message info like channel, system id, component id
  533. /// and raw payload data, etc. Also used to store and transfer received data of
  534. /// unknown or corrupted Messages.
  535. /// [More details](http://qgroundcontrol.org/mavlink/start).
  536. public class Packet {
  537. /// MAVlink Packet constants
  538. struct Constant {
  539. /// Maximum packets payload length
  540. static let maxPayloadLength = UInt8.max
  541. static let numberOfChecksumBytes = 2
  542. /// Length of core header (of the comm. layer): message length
  543. /// (1 byte) + message sequence (1 byte) + message system id (1 byte) +
  544. /// message component id (1 byte) + message type id (1 byte).
  545. static let coreHeaderLength = 5
  546. /// Length of all header bytes, including core and checksum
  547. static let numberOfHeaderBytes = Constant.numberOfChecksumBytes + Constant.coreHeaderLength + 1
  548. /// Packet start sign. Indicates the start of a new packet. v1.0.
  549. static let packetStx: UInt8 = 0xFE
  550. }
  551. /// Channel on which packet was received
  552. public internal(set) var channel: UInt8 = 0
  553. /// Sent at the end of packet
  554. public internal(set) var checksum = Checksum()
  555. /// Protocol magic marker (PacketStx value)
  556. public internal(set) var magic: UInt8 = 0
  557. /// Length of payload
  558. public internal(set) var length: UInt8 = 0
  559. /// Sequence of packet
  560. public internal(set) var sequence: UInt8 = 0
  561. /// Id of message sender system/aircraft
  562. public internal(set) var systemId: UInt8 = 0
  563. /// Id of the message sender component
  564. public internal(set) var componentId: UInt8 = 0
  565. /// Id of message type in payload
  566. public internal(set) var messageId: UInt8 = 0
  567. /// Message bytes
  568. public internal(set) var payload = Data(capacity: Int(Constant.maxPayloadLength) + Constant.numberOfChecksumBytes)
  569. /// Received Message structure if available
  570. public internal(set) var message: Message?
  571. /// Initialize copy of provided Packet.
  572. ///
  573. /// - parameter packet: Packet to copy
  574. init(packet: Packet) {
  575. channel = packet.channel
  576. checksum = packet.checksum
  577. magic = packet.magic
  578. length = packet.length
  579. sequence = packet.sequence
  580. systemId = packet.systemId
  581. componentId = packet.componentId
  582. messageId = packet.messageId
  583. payload = packet.payload
  584. message = packet.message
  585. }
  586. /// Initialize packet with provided `message` for sending.
  587. ///
  588. /// - parameter message: Message to send.
  589. /// - parameter systemId: Id of the sending (this) system.
  590. /// - parameter componentId: Id of the sending component.
  591. /// - parameter channel: Id of the current channel.
  592. init(message: Message, systemId: UInt8, componentId: UInt8, channel: Channel) {
  593. self.magic = Constant.packetStx
  594. self.systemId = systemId
  595. self.componentId = componentId
  596. self.messageId = type(of: message).id
  597. self.length = type(of: message).payloadLength
  598. self.message = message
  599. self.channel = channel
  600. }
  601. init() { }
  602. /// Finalize a MAVLink packet with sequence assignment. Returns data that
  603. /// could be sent to the aircraft. This function calculates the checksum and
  604. /// sets length and aircraft id correctly. It assumes that the packet is
  605. /// already correctly initialized with appropriate `message`, `length`,
  606. /// `systemId`, `componentId`.
  607. /// Could be used to send packets without `MAVLink` object, in this case you
  608. /// should take care of `sequence` counter manually.
  609. ///
  610. /// - parameter sequence: Each channel counts up its send sequence. It allows
  611. /// to detect packet loss.
  612. ///
  613. /// - throws: Throws `PackError`.
  614. ///
  615. /// - returns: Data
  616. public func finalize(sequence: UInt8) throws -> Data {
  617. guard let message = message else {
  618. throw PackError.messageNotSet
  619. }
  620. guard let crcExtra = messageCRCsExtra[messageId] else {
  621. throw PackError.crcExtraNotFound(messageId: type(of: message).id)
  622. }
  623. self.sequence = sequence
  624. let coreHeader = [length, sequence, systemId, componentId, messageId]
  625. let header = [Constant.packetStx] + coreHeader
  626. let payload = try message.pack()
  627. checksum.start()
  628. checksum.accumulate(coreHeader)
  629. checksum.accumulate(payload)
  630. checksum.accumulate(crcExtra)
  631. let checksumBytes = [checksum.lowByte, checksum.highByte]
  632. var packetData = Data(capacity: payload.count + Constant.numberOfHeaderBytes)
  633. packetData.append(header, count: header.count)
  634. packetData.append(payload)
  635. packetData.append(checksumBytes, count: checksumBytes.count)
  636. return packetData
  637. }
  638. }
  639. /// Struct for storing and calculating checksum.
  640. public struct Checksum {
  641. struct Constants {
  642. static let x25InitCRCValue: UInt16 = 0xFFFF
  643. }
  644. public var lowByte: UInt8 {
  645. return UInt8(truncatingBitPattern: value)
  646. }
  647. public var highByte: UInt8 {
  648. return UInt8(truncatingBitPattern: value >> 8)
  649. }
  650. public private(set) var value: UInt16 = 0
  651. init() {
  652. start()
  653. }
  654. /// Initialize the buffer for the X.25 CRC.
  655. mutating func start() {
  656. value = Constants.x25InitCRCValue
  657. }
  658. /// Accumulate the X.25 CRC by adding one char at a time. The checksum
  659. /// function adds the hash of one char at a time to the 16 bit checksum
  660. /// `value` (`UInt16`).
  661. ///
  662. /// - parameter char: New char to hash
  663. mutating func accumulate(_ char: UInt8) {
  664. var tmp: UInt8 = char ^ UInt8(truncatingBitPattern: value)
  665. tmp ^= (tmp << 4)
  666. value = (UInt16(value) >> 8) ^ (UInt16(tmp) << 8) ^ (UInt16(tmp) << 3) ^ (UInt16(tmp) >> 4)
  667. }
  668. /// Accumulate the X.25 CRC by adding `buffer` bytes.
  669. ///
  670. /// - parameter buffer: Sequence of bytes to hash
  671. mutating func accumulate<T: Sequence>(_ buffer: T) where T.Iterator.Element == UInt8 {
  672. buffer.forEach { accumulate($0) }
  673. }
  674. }
  675. // MARK: - CF independent host system byte order determination
  676. public enum ByteOrder: UInt32 {
  677. case unknown
  678. case littleEndian
  679. case bigEndian
  680. }
  681. public func hostByteOrder() -> ByteOrder {
  682. var bigAndLittleEndian: UInt32 = (ByteOrder.bigEndian.rawValue << 24) | ByteOrder.littleEndian.rawValue
  683. let firstByte: UInt8 = withUnsafePointer(to: &bigAndLittleEndian) { numberPointer in
  684. let bufferPointer = numberPointer.withMemoryRebound(to: UInt8.self, capacity: 4) { pointer in
  685. return UnsafeBufferPointer(start: pointer, count: 4)
  686. }
  687. return bufferPointer[0]
  688. }
  689. return ByteOrder(rawValue: UInt32(firstByte)) ?? .unknown
  690. }
  691. // MARK: - Data extensions
  692. protocol MAVLinkNumber { }
  693. extension UInt8: MAVLinkNumber { }
  694. extension Int8: MAVLinkNumber { }
  695. extension UInt16: MAVLinkNumber { }
  696. extension Int16: MAVLinkNumber { }
  697. extension UInt32: MAVLinkNumber { }
  698. extension Int32: MAVLinkNumber { }
  699. extension UInt64: MAVLinkNumber { }
  700. extension Int64: MAVLinkNumber { }
  701. extension Float: MAVLinkNumber { }
  702. extension Double: MAVLinkNumber { }
  703. /// Methods for getting properly typed field values from received data.
  704. extension Data {
  705. /// Returns number value (integer or floating point) from receiver's data.
  706. ///
  707. /// - parameter offset: Offset in receiver's bytes.
  708. /// - parameter byteOrder: Current system endianness.
  709. ///
  710. /// - throws: Throws `ParseError`.
  711. ///
  712. /// - returns: Returns `MAVLinkNumber` (UInt8, Int8, UInt16, Int16, UInt32,
  713. /// Int32, UInt64, Int64, Float, Double).
  714. func number<T: MAVLinkNumber>(at offset: Data.Index, byteOrder: ByteOrder = hostByteOrder()) throws -> T {
  715. let size = MemoryLayout<T>.stride
  716. let range: Range<Int> = offset ..< offset + size
  717. guard range.upperBound <= count else {
  718. throw ParseError.valueSizeOutOfBounds(offset: offset, size: size, upperBound: count)
  719. }
  720. var bytes = subdata(in: range)
  721. if byteOrder != .littleEndian {
  722. bytes.reverse()
  723. }
  724. return bytes.withUnsafeBytes { $0.pointee }
  725. }
  726. /// Returns typed array from receiver's data.
  727. ///
  728. /// - parameter offset: Offset in receiver's bytes.
  729. /// - parameter capacity: Expected number of elements in array.
  730. ///
  731. /// - throws: Throws `ParseError`.
  732. ///
  733. /// - returns: `Array<T>`
  734. func array<T: MAVLinkNumber>(at offset: Data.Index, capacity: Int) throws -> [T] {
  735. var offset = offset
  736. var array = [T]()
  737. for _ in 0 ..< capacity {
  738. array.append(try number(at: offset))
  739. offset += MemoryLayout<T>.stride
  740. }
  741. return array
  742. }
  743. /// Returns ASCII String from receiver's data.
  744. ///
  745. /// - parameter offset: Offset in receiver's bytes.
  746. /// - parameter length: Expected length of string to read.
  747. ///
  748. /// - throws: Throws `ParseError`.
  749. ///
  750. /// - returns: `String`
  751. func string(at offset: Data.Index, length: Int) throws -> String {
  752. let range: Range<Int> = offset ..< offset + length
  753. guard range.upperBound <= count else {
  754. throw ParseError.valueSizeOutOfBounds(offset: offset, size: length, upperBound: count)
  755. }
  756. let bytes = subdata(in: range)
  757. let emptySubSequence = Data.SubSequence(base: Data(), bounds: 0 ..< 0)
  758. let firstSubSequence = bytes.split(separator: 0x0, maxSplits: 1, omittingEmptySubsequences: false).first ?? emptySubSequence
  759. guard let string = String(bytes: firstSubSequence, encoding: .ascii) else {
  760. throw ParseError.invalidStringEncoding(offset: offset, length: length)
  761. }
  762. return string
  763. }
  764. /// Returns proper typed `Enumeration` subtype value from data or throws
  765. /// `ParserEnumError` or `ParseError` error.
  766. ///
  767. /// - parameter offset: Offset in receiver's bytes.
  768. ///
  769. /// - throws: Throws `ParserEnumError`, `ParseError`.
  770. ///
  771. /// - returns: Properly typed `Enumeration` subtype value.
  772. func enumeration<T: Enumeration>(at offset: Data.Index) throws -> T where T.RawValue: MAVLinkNumber {
  773. let rawValue: T.RawValue = try number(at: offset)
  774. guard let enumerationCase = T(rawValue: rawValue) else {
  775. throw ParseEnumError.unknownValue(enumType: T.self, rawValue: rawValue, valueOffset: offset)
  776. }
  777. return enumerationCase
  778. }
  779. }
  780. /// Methods for filling `Data` with properly formatted field values.
  781. extension Data {
  782. /// Sets properly swapped `number` bytes starting from `offset` in
  783. /// receiver's bytes.
  784. ///
  785. /// - warning: Supports only version 1.0 of MAVLink wire protocol
  786. /// (little-endian byte order).
  787. ///
  788. /// - parameter number: Number value to set.
  789. /// - parameter offset: Offset in receiver's bytes.
  790. /// - parameter byteOrder: Current system endianness.
  791. ///
  792. /// - throws: Throws `PackError`.
  793. mutating func set<T: MAVLinkNumber>(_ number: T, at offset: Data.Index, byteOrder: ByteOrder = hostByteOrder()) throws {
  794. let size = MemoryLayout<T>.stride
  795. let range = offset ..< offset + size
  796. guard range.endIndex <= count else {
  797. throw PackError.valueSizeOutOfBounds(offset: offset, size: size, upperBound: count)
  798. }
  799. var number = number
  800. var bytes: Data = withUnsafePointer(to: &number) { numberPointer in
  801. let bufferPointer = numberPointer.withMemoryRebound(to: UInt8.self, capacity: size) { pointer in
  802. return UnsafeBufferPointer(start: pointer, count: size)
  803. }
  804. return Data(bufferPointer)
  805. }
  806. if byteOrder != .littleEndian {
  807. bytes.reverse()
  808. }
  809. replaceSubrange(range, with: bytes)
  810. }
  811. /// Sets `array` of `MAVLinkNumber` values at `offset` with `capacity` validation.
  812. ///
  813. /// - parameter array: Array of values to set.
  814. /// - parameter offset: Offset in receiver's bytes.
  815. /// - parameter capacity: Maximum allowed count of elements in `array`.
  816. ///
  817. /// - throws: Throws `PackError`.
  818. mutating func set<T: MAVLinkNumber>(_ array: [T], at offset: Data.Index, capacity: Int) throws {
  819. guard array.count <= capacity else {
  820. throw PackError.invalidValueLength(offset: offset, providedValueLength: array.count, allowedLength: capacity)
  821. }
  822. let elementSize = MemoryLayout<T>.stride
  823. let arraySize = elementSize * array.count
  824. guard offset + arraySize <= count else {
  825. throw PackError.valueSizeOutOfBounds(offset: offset, size: arraySize, upperBound: count)
  826. }
  827. for (index, item) in array.enumerated() {
  828. try set(item, at: offset + index * elementSize)
  829. }
  830. }
  831. /// Sets correctly encoded `string` value at `offset` limited to `length` or
  832. /// throws `PackError`.
  833. ///
  834. /// - precondition: `string` value must be ASCII compatible.
  835. ///
  836. /// - parameter string: Value to set.
  837. /// - parameter offset: Offset in receiver's bytes.
  838. /// - parameter length: Maximum allowed length of `string`.
  839. ///
  840. /// - throws: Throws `PackError`.
  841. mutating func set(_ string: String, at offset: Data.Index, length: Int) throws {
  842. var bytes = string.data(using: .ascii) ?? Data()
  843. if bytes.isEmpty && string.unicodeScalars.count > 0 {
  844. throw PackError.invalidStringEncoding(offset: offset, string: string)
  845. }
  846. // Add optional null-termination if provided string is shorter than
  847. // expectedlength
  848. if bytes.count < length {
  849. bytes.append(0x0)
  850. }
  851. let asciiCharacters = bytes.withUnsafeBytes { Array(UnsafeBufferPointer<UInt8>(start: $0, count: bytes.count)) }
  852. try set(asciiCharacters, at: offset, capacity: length)
  853. }
  854. /// Sets correctly formated `enumeration` raw value at `offset` or throws
  855. /// `PackError`.
  856. ///
  857. /// - parameter enumeration: Value to set.
  858. /// - parameter offset: Offset in receiver's bytes.
  859. ///
  860. /// - throws: Throws `PackError`.
  861. mutating func set<T: Enumeration>(_ enumeration: T, at offset: Data.Index) throws where T.RawValue: MAVLinkNumber {
  862. try set(enumeration.rawValue, at: offset)
  863. }
  864. }
  865. // MARK: - Additional MAVLink service info