CompareWithCImpTests.swift 6.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167
  1. //
  2. // CompareWithCImpTest.swift
  3. // MAVLink
  4. //
  5. // Created by Max Odnovolyk on 10/29/16.
  6. // Copyright © 2016 Build Apps. All rights reserved.
  7. //
  8. import Foundation
  9. import XCTest
  10. import MAVLink_C
  11. @testable import MAVLink
  12. class CompareWithCImplementationResultsTest: XCTestCase {
  13. func testSwiftParserImplementationDidReturnSameFloatValuesAsCImplementation() {
  14. let data = testAttitudeData
  15. let mavLink = MAVLink()
  16. var attitudeMessageSwift: Attitude!
  17. mavLink.parse(data: data, channel: 0) { message, _ in
  18. attitudeMessageSwift = message as! Attitude
  19. }
  20. XCTAssert(attitudeMessageSwift != nil, "Expects to receive valid Attitude message from provided data")
  21. var messageC = mavlink_message_t()
  22. var statusC = mavlink_status_t()
  23. var attitudeMessageC = mavlink_attitude_t()
  24. data.forEach { mavlink_parse_char(0, $0, &messageC, &statusC) }
  25. mavlink_msg_attitude_decode(&messageC, &attitudeMessageC)
  26. XCTAssert(attitudeMessageSwift.timeBootMs == attitudeMessageC.time_boot_ms)
  27. XCTAssert(attitudeMessageSwift.roll == attitudeMessageC.roll)
  28. XCTAssert(attitudeMessageSwift.pitch == attitudeMessageC.pitch)
  29. XCTAssert(attitudeMessageSwift.yaw == attitudeMessageC.yaw)
  30. XCTAssert(attitudeMessageSwift.rollspeed == attitudeMessageC.rollspeed)
  31. XCTAssert(attitudeMessageSwift.pitchspeed == attitudeMessageC.pitchspeed)
  32. XCTAssert(attitudeMessageSwift.yawspeed == attitudeMessageC.yawspeed)
  33. }
  34. /// Test MAVLink parser on the real world data and compare results with C code results
  35. /// on the same data set. This test could take significant amount of time (tlog
  36. /// contains about 163000 messages).
  37. /// You can disable this test in test scheme configuration to save time.
  38. /// Tlog file was downloaded from https://github.com/dronekit/dronekit-la-testdata.
  39. /// APM:Copter V3.4-dev (bdddfae5)
  40. func testSwiftParserImplementationDidReturnSameNumberOfMessagesAsCImplementation() {
  41. // Load data from test tlog file
  42. let data = testTlogData
  43. // Message and error counters
  44. var messageCountSwift = 0
  45. var messageCountC = 0
  46. var errors: [String: Int] = [:]
  47. // Delegated messages handler
  48. let delegate = Delegate(didParse: { _, _, _, _ in
  49. messageCountSwift += 1
  50. }, didFailToParseMessage: { _, error, _, _ in
  51. // Сonsidering ParseError.valueSizeOutOfBounds, ParseError.invalidStringEncoding,
  52. // ParseEnumError.unknownValue which are not handled in C implementation.
  53. if let count = errors[error.description] {
  54. errors[error.description] = count + 1
  55. } else {
  56. errors[error.description] = 1
  57. }
  58. })
  59. // Parse data with MAVLink class instance (pure Swift implementation)
  60. let mavLink = MAVLink()
  61. mavLink.delegate = delegate
  62. mavLink.parse(data: data, channel: 0)
  63. let typesErrorCountSwift = errors.reduce(0) { result, item in result + item.1 }
  64. // Process data with C mavlink_parse_char function
  65. var message = mavlink_message_t()
  66. var status = mavlink_status_t()
  67. data.forEach { byte in
  68. if mavlink_parse_char(0, byte, &message, &status) == UInt8(MAVLINK_FRAMING_OK.rawValue) {
  69. messageCountC += 1
  70. }
  71. }
  72. // Compare results
  73. XCTAssert(messageCountSwift == messageCountC - typesErrorCountSwift, "Number of messages parsed in MAVLink instance should match messageCountC minus number of errors which is not handled in C code")
  74. }
  75. /// Test that generated by MAVLink data can be parsed in C implementation.
  76. /// Tlog file was downloaded from https://github.com/dronekit/dronekit-la-testdata.
  77. /// APM:Copter V3.4-dev (bdddfae5)
  78. func testCImplementationDidParseSwiftMAVLinkOutput() {
  79. continueAfterFailure = false
  80. // Load data from test tlog file
  81. let data = testTlogData
  82. var messagesCount = 0
  83. // Delegated messages handler
  84. let delegate = Delegate(didParse: { message, packet, _, link in
  85. let data = try! packet.finalize(sequence: 0)
  86. var message = mavlink_message_t()
  87. var status = mavlink_status_t()
  88. var result = UInt8(MAVLINK_FRAMING_INCOMPLETE.rawValue)
  89. data.forEach { byte in
  90. result = mavlink_parse_char(0, byte, &message, &status)
  91. }
  92. XCTAssert(result == UInt8(MAVLINK_FRAMING_OK.rawValue), "C Implementation should be able to parse finalized by MAVLink message if they both use the same definitions and settings")
  93. messagesCount += 1
  94. })
  95. // Parse data with MAVLink class instance (pure Swift implementation)
  96. let mavLink = MAVLink()
  97. mavLink.delegate = delegate
  98. mavLink.parse(data: data, channel: 0)
  99. XCTAssert(messagesCount > 0, "Unable to parse any method from test data")
  100. }
  101. func testCImplementationDidParseMessageThatStartsRightAfterCorruptedMessageIdByte() {
  102. let unknownMessageId = UInt8(0xC7)
  103. var data = Data(testHeartbeatData.prefix(upTo: 5))
  104. data.append(unknownMessageId)
  105. data.append(testStatustextData)
  106. var message = mavlink_message_t()
  107. var status = mavlink_status_t()
  108. var result = UInt8(MAVLINK_FRAMING_INCOMPLETE.rawValue)
  109. data.forEach { byte in
  110. result = mavlink_parse_char(0, byte, &message, &status)
  111. }
  112. XCTAssert(result == UInt8(MAVLINK_FRAMING_OK.rawValue))
  113. }
  114. func testCImplementationDidParseMessageThatStartsRightAfterCorruptedCRCByte() {
  115. let corruptedByte = UInt8(0x00)
  116. var data = testHeartbeatData
  117. data.removeLast(2)
  118. data.append(corruptedByte)
  119. data.append(testStatustextData)
  120. var message = mavlink_message_t()
  121. var status = mavlink_status_t()
  122. var result = UInt8(MAVLINK_FRAMING_INCOMPLETE.rawValue)
  123. data.forEach { byte in
  124. result = mavlink_parse_char(0, byte, &message, &status)
  125. }
  126. XCTAssert(result == UInt8(MAVLINK_FRAMING_OK.rawValue))
  127. }
  128. }