diff --git a/Cartfile b/Cartfile index 4a70c42..51b9a65 100644 --- a/Cartfile +++ b/Cartfile @@ -1,3 +1,3 @@ github "jonasvautherin/grpc-swift" "master" github "ReactiveX/RxSwift" == 5.0.1 -binary "https://s3.eu-central-1.amazonaws.com/dronecode-sdk/backend.json" == 0.18.3 +binary "https://s3.eu-central-1.amazonaws.com/dronecode-sdk/backend.json" == 0.20.0 diff --git a/Cartfile.resolved b/Cartfile.resolved index fae0b1b..eb9cdba 100644 --- a/Cartfile.resolved +++ b/Cartfile.resolved @@ -1,3 +1,3 @@ -binary "https://s3.eu-central-1.amazonaws.com/dronecode-sdk/backend.json" "0.18.3" +binary "https://s3.eu-central-1.amazonaws.com/dronecode-sdk/backend.json" "0.20.0" github "ReactiveX/RxSwift" "5.0.1" github "jonasvautherin/grpc-swift" "820730e24b9cf035b2889b30d2fe87411e041720" diff --git a/Package.resolved b/Package.resolved index 92d325d..8234303 100644 --- a/Package.resolved +++ b/Package.resolved @@ -64,15 +64,6 @@ "version": "1.0.0" } }, - { - "package": "swift-nio-ssl-support", - "repositoryURL": "https://github.com/apple/swift-nio-ssl-support.git", - "state": { - "branch": null, - "revision": "c02eec4e0e6d351cd092938cf44195a8e669f555", - "version": "1.0.0" - } - }, { "package": "swift-nio-zlib-support", "repositoryURL": "https://github.com/apple/swift-nio-zlib-support.git", @@ -87,8 +78,8 @@ "repositoryURL": "https://github.com/apple/swift-protobuf.git", "state": { "branch": null, - "revision": "7bf52ab1f5ee87aeb89f2a6b9bfc6369408476f7", - "version": "1.5.0" + "revision": "da75a93ac017534e0028e83c0e4fc4610d2acf48", + "version": "1.7.0" } } ] diff --git a/Sources/MAVSDK-Swift/Generated/Gimbal.swift b/Sources/MAVSDK-Swift/Generated/Gimbal.swift index 1bc0d82..1c4faff 100644 --- a/Sources/MAVSDK-Swift/Generated/Gimbal.swift +++ b/Sources/MAVSDK-Swift/Generated/Gimbal.swift @@ -71,22 +71,22 @@ public class Gimbal { public enum Result: Equatable { + case unknown case success case error case timeout - case unknown case UNRECOGNIZED(Int) internal var rpcResult: Mavsdk_Rpc_Gimbal_GimbalResult.Result { switch self { + case .unknown: + return .unknown case .success: return .success case .error: return .error case .timeout: return .timeout - case .unknown: - return .unknown case .UNRECOGNIZED(let i): return .UNRECOGNIZED(i) } @@ -94,14 +94,14 @@ public class Gimbal { internal static func translateFromRpc(_ rpcResult: Mavsdk_Rpc_Gimbal_GimbalResult.Result) -> Result { switch rpcResult { + case .unknown: + return .unknown case .success: return .success case .error: return .error case .timeout: return .timeout - case .unknown: - return .unknown case .UNRECOGNIZED(let i): return .UNRECOGNIZED(i) } diff --git a/Sources/MAVSDK-Swift/Generated/Telemetry.swift b/Sources/MAVSDK-Swift/Generated/Telemetry.swift index 45655be..ce82fb0 100644 --- a/Sources/MAVSDK-Swift/Generated/Telemetry.swift +++ b/Sources/MAVSDK-Swift/Generated/Telemetry.swift @@ -145,6 +145,49 @@ public class Telemetry { } } + public enum LandedState: Equatable { + case landedStateUnknown + case landedStateOnGround + case landedStateInAir + case landedStateTakingOff + case landedStateLanding + case UNRECOGNIZED(Int) + + internal var rpcLandedState: Mavsdk_Rpc_Telemetry_LandedState { + switch self { + case .landedStateUnknown: + return .unknown + case .landedStateOnGround: + return .onGround + case .landedStateInAir: + return .inAir + case .landedStateTakingOff: + return .takingOff + case .landedStateLanding: + return .landing + case .UNRECOGNIZED(let i): + return .UNRECOGNIZED(i) + } + } + + internal static func translateFromRpc(_ rpcLandedState: Mavsdk_Rpc_Telemetry_LandedState) -> LandedState { + switch rpcLandedState { + case .unknown: + return .landedStateUnknown + case .onGround: + return .landedStateOnGround + case .inAir: + return .landedStateInAir + case .takingOff: + return .landedStateTakingOff + case .landing: + return .landedStateLanding + case .UNRECOGNIZED(let i): + return .UNRECOGNIZED(i) + } + } + } + public struct Position: Equatable { public let latitudeDeg: Double @@ -297,6 +340,51 @@ public class Telemetry { } } + public struct AngularVelocityBody: Equatable { + public let rollRadS: Float + public let pitchRadS: Float + public let yawRadS: Float + + + + public init(rollRadS: Float, pitchRadS: Float, yawRadS: Float) { + self.rollRadS = rollRadS + self.pitchRadS = pitchRadS + self.yawRadS = yawRadS + } + + internal var rpcAngularVelocityBody: Mavsdk_Rpc_Telemetry_AngularVelocityBody { + var rpcAngularVelocityBody = Mavsdk_Rpc_Telemetry_AngularVelocityBody() + + + rpcAngularVelocityBody.rollRadS = rollRadS + + + + + rpcAngularVelocityBody.pitchRadS = pitchRadS + + + + + rpcAngularVelocityBody.yawRadS = yawRadS + + + + return rpcAngularVelocityBody + } + + internal static func translateFromRpc(_ rpcAngularVelocityBody: Mavsdk_Rpc_Telemetry_AngularVelocityBody) -> AngularVelocityBody { + return AngularVelocityBody(rollRadS: rpcAngularVelocityBody.rollRadS, pitchRadS: rpcAngularVelocityBody.pitchRadS, yawRadS: rpcAngularVelocityBody.yawRadS) + } + + public static func == (lhs: AngularVelocityBody, rhs: AngularVelocityBody) -> Bool { + return lhs.rollRadS == rhs.rollRadS + && lhs.pitchRadS == rhs.pitchRadS + && lhs.yawRadS == rhs.yawRadS + } + } + public struct SpeedNed: Equatable { public let velocityNorthMS: Float public let velocityEastMS: Float @@ -610,6 +698,332 @@ public class Telemetry { } } + public struct ActuatorControlTarget: Equatable { + public let group: Int32 + public let controls: [Float] + + + + public init(group: Int32, controls: [Float]) { + self.group = group + self.controls = controls + } + + internal var rpcActuatorControlTarget: Mavsdk_Rpc_Telemetry_ActuatorControlTarget { + var rpcActuatorControlTarget = Mavsdk_Rpc_Telemetry_ActuatorControlTarget() + + + rpcActuatorControlTarget.group = group + + + + + rpcActuatorControlTarget.controls = controls + + + + return rpcActuatorControlTarget + } + + internal static func translateFromRpc(_ rpcActuatorControlTarget: Mavsdk_Rpc_Telemetry_ActuatorControlTarget) -> ActuatorControlTarget { + return ActuatorControlTarget(group: rpcActuatorControlTarget.group, controls: rpcActuatorControlTarget.controls) + } + + public static func == (lhs: ActuatorControlTarget, rhs: ActuatorControlTarget) -> Bool { + return lhs.group == rhs.group + && lhs.controls == rhs.controls + } + } + + public struct ActuatorOutputStatus: Equatable { + public let active: UInt32 + public let actuator: [Float] + + + + public init(active: UInt32, actuator: [Float]) { + self.active = active + self.actuator = actuator + } + + internal var rpcActuatorOutputStatus: Mavsdk_Rpc_Telemetry_ActuatorOutputStatus { + var rpcActuatorOutputStatus = Mavsdk_Rpc_Telemetry_ActuatorOutputStatus() + + + rpcActuatorOutputStatus.active = active + + + + + rpcActuatorOutputStatus.actuator = actuator + + + + return rpcActuatorOutputStatus + } + + internal static func translateFromRpc(_ rpcActuatorOutputStatus: Mavsdk_Rpc_Telemetry_ActuatorOutputStatus) -> ActuatorOutputStatus { + return ActuatorOutputStatus(active: rpcActuatorOutputStatus.active, actuator: rpcActuatorOutputStatus.actuator) + } + + public static func == (lhs: ActuatorOutputStatus, rhs: ActuatorOutputStatus) -> Bool { + return lhs.active == rhs.active + && lhs.actuator == rhs.actuator + } + } + + public struct Odometry: Equatable { + public let timeUsec: UInt64 + public let frameID: MavFrame + public let childFrameID: MavFrame + public let positionBody: PositionBody + public let q: Quaternion + public let speedBody: SpeedBody + public let angularVelocityBody: AngularVelocityBody + public let poseCovariance: Covariance + public let velocityCovariance: Covariance + + + + + public enum MavFrame: Equatable { + case undef + case bodyNed + case visionNed + case estimNed + case UNRECOGNIZED(Int) + + internal var rpcMavFrame: Mavsdk_Rpc_Telemetry_Odometry.MavFrame { + switch self { + case .undef: + return .undef + case .bodyNed: + return .bodyNed + case .visionNed: + return .visionNed + case .estimNed: + return .estimNed + case .UNRECOGNIZED(let i): + return .UNRECOGNIZED(i) + } + } + + internal static func translateFromRpc(_ rpcMavFrame: Mavsdk_Rpc_Telemetry_Odometry.MavFrame) -> MavFrame { + switch rpcMavFrame { + case .undef: + return .undef + case .bodyNed: + return .bodyNed + case .visionNed: + return .visionNed + case .estimNed: + return .estimNed + case .UNRECOGNIZED(let i): + return .UNRECOGNIZED(i) + } + } + } + + + public init(timeUsec: UInt64, frameID: MavFrame, childFrameID: MavFrame, positionBody: PositionBody, q: Quaternion, speedBody: SpeedBody, angularVelocityBody: AngularVelocityBody, poseCovariance: Covariance, velocityCovariance: Covariance) { + self.timeUsec = timeUsec + self.frameID = frameID + self.childFrameID = childFrameID + self.positionBody = positionBody + self.q = q + self.speedBody = speedBody + self.angularVelocityBody = angularVelocityBody + self.poseCovariance = poseCovariance + self.velocityCovariance = velocityCovariance + } + + internal var rpcOdometry: Mavsdk_Rpc_Telemetry_Odometry { + var rpcOdometry = Mavsdk_Rpc_Telemetry_Odometry() + + + rpcOdometry.timeUsec = timeUsec + + + + + rpcOdometry.frameID = frameID.rpcMavFrame + + + + + rpcOdometry.childFrameID = childFrameID.rpcMavFrame + + + + + rpcOdometry.positionBody = positionBody.rpcPositionBody + + + + + rpcOdometry.q = q.rpcQuaternion + + + + + rpcOdometry.speedBody = speedBody.rpcSpeedBody + + + + + rpcOdometry.angularVelocityBody = angularVelocityBody.rpcAngularVelocityBody + + + + + rpcOdometry.poseCovariance = poseCovariance.rpcCovariance + + + + + rpcOdometry.velocityCovariance = velocityCovariance.rpcCovariance + + + + return rpcOdometry + } + + internal static func translateFromRpc(_ rpcOdometry: Mavsdk_Rpc_Telemetry_Odometry) -> Odometry { + return Odometry(timeUsec: rpcOdometry.timeUsec, frameID: MavFrame.translateFromRpc(rpcOdometry.frameID), childFrameID: MavFrame.translateFromRpc(rpcOdometry.childFrameID), positionBody: PositionBody.translateFromRpc(rpcOdometry.positionBody), q: Quaternion.translateFromRpc(rpcOdometry.q), speedBody: SpeedBody.translateFromRpc(rpcOdometry.speedBody), angularVelocityBody: AngularVelocityBody.translateFromRpc(rpcOdometry.angularVelocityBody), poseCovariance: Covariance.translateFromRpc(rpcOdometry.poseCovariance), velocityCovariance: Covariance.translateFromRpc(rpcOdometry.velocityCovariance)) + } + + public static func == (lhs: Odometry, rhs: Odometry) -> Bool { + return lhs.timeUsec == rhs.timeUsec + && lhs.frameID == rhs.frameID + && lhs.childFrameID == rhs.childFrameID + && lhs.positionBody == rhs.positionBody + && lhs.q == rhs.q + && lhs.speedBody == rhs.speedBody + && lhs.angularVelocityBody == rhs.angularVelocityBody + && lhs.poseCovariance == rhs.poseCovariance + && lhs.velocityCovariance == rhs.velocityCovariance + } + } + + public struct Covariance: Equatable { + public let covarianceMatrix: [Float] + + + + public init(covarianceMatrix: [Float]) { + self.covarianceMatrix = covarianceMatrix + } + + internal var rpcCovariance: Mavsdk_Rpc_Telemetry_Covariance { + var rpcCovariance = Mavsdk_Rpc_Telemetry_Covariance() + + + rpcCovariance.covarianceMatrix = covarianceMatrix + + + + return rpcCovariance + } + + internal static func translateFromRpc(_ rpcCovariance: Mavsdk_Rpc_Telemetry_Covariance) -> Covariance { + return Covariance(covarianceMatrix: rpcCovariance.covarianceMatrix) + } + + public static func == (lhs: Covariance, rhs: Covariance) -> Bool { + return lhs.covarianceMatrix == rhs.covarianceMatrix + } + } + + public struct SpeedBody: Equatable { + public let velocityXMS: Float + public let velocityYMS: Float + public let velocityZMS: Float + + + + public init(velocityXMS: Float, velocityYMS: Float, velocityZMS: Float) { + self.velocityXMS = velocityXMS + self.velocityYMS = velocityYMS + self.velocityZMS = velocityZMS + } + + internal var rpcSpeedBody: Mavsdk_Rpc_Telemetry_SpeedBody { + var rpcSpeedBody = Mavsdk_Rpc_Telemetry_SpeedBody() + + + rpcSpeedBody.velocityXMS = velocityXMS + + + + + rpcSpeedBody.velocityYMS = velocityYMS + + + + + rpcSpeedBody.velocityZMS = velocityZMS + + + + return rpcSpeedBody + } + + internal static func translateFromRpc(_ rpcSpeedBody: Mavsdk_Rpc_Telemetry_SpeedBody) -> SpeedBody { + return SpeedBody(velocityXMS: rpcSpeedBody.velocityXMS, velocityYMS: rpcSpeedBody.velocityYMS, velocityZMS: rpcSpeedBody.velocityZMS) + } + + public static func == (lhs: SpeedBody, rhs: SpeedBody) -> Bool { + return lhs.velocityXMS == rhs.velocityXMS + && lhs.velocityYMS == rhs.velocityYMS + && lhs.velocityZMS == rhs.velocityZMS + } + } + + public struct PositionBody: Equatable { + public let xM: Float + public let yM: Float + public let zM: Float + + + + public init(xM: Float, yM: Float, zM: Float) { + self.xM = xM + self.yM = yM + self.zM = zM + } + + internal var rpcPositionBody: Mavsdk_Rpc_Telemetry_PositionBody { + var rpcPositionBody = Mavsdk_Rpc_Telemetry_PositionBody() + + + rpcPositionBody.xM = xM + + + + + rpcPositionBody.yM = yM + + + + + rpcPositionBody.zM = zM + + + + return rpcPositionBody + } + + internal static func translateFromRpc(_ rpcPositionBody: Mavsdk_Rpc_Telemetry_PositionBody) -> PositionBody { + return PositionBody(xM: rpcPositionBody.xM, yM: rpcPositionBody.yM, zM: rpcPositionBody.zM) + } + + public static func == (lhs: PositionBody, rhs: PositionBody) -> Bool { + return lhs.xM == rhs.xM + && lhs.yM == rhs.yM + && lhs.zM == rhs.zM + } + } + public lazy var position: Observable = createPositionObservable() @@ -765,6 +1179,57 @@ public class Telemetry { .share(replay: 1) } + public lazy var landedState: Observable = createLandedStateObservable() + + private func createLandedStateObservable() -> Observable { + return Observable.create { observer in + let request = Mavsdk_Rpc_Telemetry_SubscribeLandedStateRequest() + + + + do { + let call = try self.service.subscribeLandedState(request, completion: { (callResult) in + if callResult.statusCode == .ok || callResult.statusCode == .cancelled { + observer.onCompleted() + } else { + observer.onError(RuntimeTelemetryError(callResult.statusMessage!)) + } + }) + + let disposable = self.scheduler.schedule(0, action: { _ in + + while let response = try? call.receive() { + + + let landedState = LandedState.translateFromRpc(response.landedState) + + + + observer.onNext(landedState) + + } + + + return Disposables.create() + }) + + return Disposables.create { + call.cancel() + disposable.dispose() + } + } catch { + observer.onError(error) + return Disposables.create() + } + } + .retryWhen { error in + error.map { + guard $0 is RuntimeTelemetryError else { throw $0 } + } + } + .share(replay: 1) + } + public lazy var armed: Observable = createArmedObservable() private func createArmedObservable() -> Observable { @@ -919,6 +1384,57 @@ public class Telemetry { .share(replay: 1) } + public lazy var attitudeAngularVelocityBody: Observable = createAttitudeAngularVelocityBodyObservable() + + private func createAttitudeAngularVelocityBodyObservable() -> Observable { + return Observable.create { observer in + let request = Mavsdk_Rpc_Telemetry_SubscribeAttitudeAngularVelocityBodyRequest() + + + + do { + let call = try self.service.subscribeAttitudeAngularVelocityBody(request, completion: { (callResult) in + if callResult.statusCode == .ok || callResult.statusCode == .cancelled { + observer.onCompleted() + } else { + observer.onError(RuntimeTelemetryError(callResult.statusMessage!)) + } + }) + + let disposable = self.scheduler.schedule(0, action: { _ in + + while let response = try? call.receive() { + + + let attitudeAngularVelocityBody = AngularVelocityBody.translateFromRpc(response.attitudeAngularVelocityBody) + + + + observer.onNext(attitudeAngularVelocityBody) + + } + + + return Disposables.create() + }) + + return Disposables.create { + call.cancel() + disposable.dispose() + } + } catch { + observer.onError(error) + return Disposables.create() + } + } + .retryWhen { error in + error.map { + guard $0 is RuntimeTelemetryError else { throw $0 } + } + } + .share(replay: 1) + } + public lazy var cameraAttitudeQuaternion: Observable = createCameraAttitudeQuaternionObservable() private func createCameraAttitudeQuaternionObservable() -> Observable { @@ -1377,4 +1893,157 @@ public class Telemetry { } .share(replay: 1) } + + public lazy var actuatorControlTarget: Observable = createActuatorControlTargetObservable() + + private func createActuatorControlTargetObservable() -> Observable { + return Observable.create { observer in + let request = Mavsdk_Rpc_Telemetry_SubscribeActuatorControlTargetRequest() + + + + do { + let call = try self.service.subscribeActuatorControlTarget(request, completion: { (callResult) in + if callResult.statusCode == .ok || callResult.statusCode == .cancelled { + observer.onCompleted() + } else { + observer.onError(RuntimeTelemetryError(callResult.statusMessage!)) + } + }) + + let disposable = self.scheduler.schedule(0, action: { _ in + + while let response = try? call.receive() { + + + let actuatorControlTarget = ActuatorControlTarget.translateFromRpc(response.actuatorControlTarget) + + + + observer.onNext(actuatorControlTarget) + + } + + + return Disposables.create() + }) + + return Disposables.create { + call.cancel() + disposable.dispose() + } + } catch { + observer.onError(error) + return Disposables.create() + } + } + .retryWhen { error in + error.map { + guard $0 is RuntimeTelemetryError else { throw $0 } + } + } + .share(replay: 1) + } + + public lazy var actuatorOutputStatus: Observable = createActuatorOutputStatusObservable() + + private func createActuatorOutputStatusObservable() -> Observable { + return Observable.create { observer in + let request = Mavsdk_Rpc_Telemetry_SubscribeActuatorOutputStatusRequest() + + + + do { + let call = try self.service.subscribeActuatorOutputStatus(request, completion: { (callResult) in + if callResult.statusCode == .ok || callResult.statusCode == .cancelled { + observer.onCompleted() + } else { + observer.onError(RuntimeTelemetryError(callResult.statusMessage!)) + } + }) + + let disposable = self.scheduler.schedule(0, action: { _ in + + while let response = try? call.receive() { + + + let actuatorOutputStatus = ActuatorOutputStatus.translateFromRpc(response.actuatorOutputStatus) + + + + observer.onNext(actuatorOutputStatus) + + } + + + return Disposables.create() + }) + + return Disposables.create { + call.cancel() + disposable.dispose() + } + } catch { + observer.onError(error) + return Disposables.create() + } + } + .retryWhen { error in + error.map { + guard $0 is RuntimeTelemetryError else { throw $0 } + } + } + .share(replay: 1) + } + + public lazy var odometry: Observable = createOdometryObservable() + + private func createOdometryObservable() -> Observable { + return Observable.create { observer in + let request = Mavsdk_Rpc_Telemetry_SubscribeOdometryRequest() + + + + do { + let call = try self.service.subscribeOdometry(request, completion: { (callResult) in + if callResult.statusCode == .ok || callResult.statusCode == .cancelled { + observer.onCompleted() + } else { + observer.onError(RuntimeTelemetryError(callResult.statusMessage!)) + } + }) + + let disposable = self.scheduler.schedule(0, action: { _ in + + while let response = try? call.receive() { + + + let odometry = Odometry.translateFromRpc(response.odometry) + + + + observer.onNext(odometry) + + } + + + return Disposables.create() + }) + + return Disposables.create { + call.cancel() + disposable.dispose() + } + } catch { + observer.onError(error) + return Disposables.create() + } + } + .retryWhen { error in + error.map { + guard $0 is RuntimeTelemetryError else { throw $0 } + } + } + .share(replay: 1) + } } \ No newline at end of file diff --git a/Sources/MAVSDK-Swift/Generated/action.pb.swift b/Sources/MAVSDK-Swift/Generated/action.pb.swift index e63242d..6a9e713 100644 --- a/Sources/MAVSDK-Swift/Generated/action.pb.swift +++ b/Sources/MAVSDK-Swift/Generated/action.pb.swift @@ -322,6 +322,7 @@ struct Mavsdk_Rpc_Action_GetTakeoffAltitudeResponse { /// Clears the value of `actionResult`. Subsequent reads from it will return its default value. mutating func clearActionResult() {_uniqueStorage()._actionResult = nil} + /// Takeoff altitude relative to ground/takeoff location (in meters) var altitude: Float { get {return _storage._altitude} set {_uniqueStorage()._altitude = newValue} @@ -339,6 +340,7 @@ struct Mavsdk_Rpc_Action_SetTakeoffAltitudeRequest { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Takeoff altitude relative to ground/takeoff location (in meters) var altitude: Float = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -391,6 +393,7 @@ struct Mavsdk_Rpc_Action_GetMaximumSpeedResponse { /// Clears the value of `actionResult`. Subsequent reads from it will return its default value. mutating func clearActionResult() {_uniqueStorage()._actionResult = nil} + /// Maximum speed (in metres/second) var speed: Float { get {return _storage._speed} set {_uniqueStorage()._speed = newValue} @@ -408,6 +411,7 @@ struct Mavsdk_Rpc_Action_SetMaximumSpeedRequest { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Maximum speed (in metres/second) var speed: Float = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -460,6 +464,7 @@ struct Mavsdk_Rpc_Action_GetReturnToLaunchAltitudeResponse { /// Clears the value of `actionResult`. Subsequent reads from it will return its default value. mutating func clearActionResult() {_uniqueStorage()._actionResult = nil} + /// Return altitude relative to takeoff location (in meters) var relativeAltitudeM: Float { get {return _storage._relativeAltitudeM} set {_uniqueStorage()._relativeAltitudeM = newValue} @@ -477,6 +482,7 @@ struct Mavsdk_Rpc_Action_SetReturnToLaunchAltitudeRequest { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Return altitude relative to takeoff location (in meters) var relativeAltitudeM: Float = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -505,30 +511,58 @@ struct Mavsdk_Rpc_Action_SetReturnToLaunchAltitudeResponse { fileprivate var _storage = _StorageClass.defaultInstance } +/// Result type. struct Mavsdk_Rpc_Action_ActionResult { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Result enum value var result: Mavsdk_Rpc_Action_ActionResult.Result = .unknown + /// Human-readable English string describing the result var resultStr: String = String() var unknownFields = SwiftProtobuf.UnknownStorage() + /// Possible results returned for action requests. enum Result: SwiftProtobuf.Enum { typealias RawValue = Int + + /// Unknown error case unknown // = 0 + + /// Success: the action command was accepted by the vehicle case success // = 1 + + /// No system is connected case noSystem // = 2 + + /// Connection error case connectionError // = 3 + + /// Vehicle is busy case busy // = 4 + + /// Command refused by vehicle case commandDenied // = 5 + + /// Command refused because landed state is unknown case commandDeniedLandedStateUnknown // = 6 + + /// Command refused because vehicle not landed case commandDeniedNotLanded // = 7 + + /// Request timed out case timeout // = 8 + + /// Hybrid/VTOL transition refused because VTOL support is unknown case vtolTransitionSupportUnknown // = 9 + + /// Vehicle does not support hybrid/VTOL transitions case noVtolTransitionSupport // = 10 + + /// Error getting or setting parameter case parameterError // = 11 case UNRECOGNIZED(Int) diff --git a/Sources/MAVSDK-Swift/Generated/calibration.pb.swift b/Sources/MAVSDK-Swift/Generated/calibration.pb.swift index 02ff0df..104c442 100644 --- a/Sources/MAVSDK-Swift/Generated/calibration.pb.swift +++ b/Sources/MAVSDK-Swift/Generated/calibration.pb.swift @@ -43,6 +43,7 @@ struct Mavsdk_Rpc_Calibration_CalibrateGyroResponse { /// Clears the value of `calibrationResult`. Subsequent reads from it will return its default value. mutating func clearCalibrationResult() {_uniqueStorage()._calibrationResult = nil} + /// Progress data var progressData: Mavsdk_Rpc_Calibration_ProgressData { get {return _storage._progressData ?? Mavsdk_Rpc_Calibration_ProgressData()} set {_uniqueStorage()._progressData = newValue} @@ -83,6 +84,7 @@ struct Mavsdk_Rpc_Calibration_CalibrateAccelerometerResponse { /// Clears the value of `calibrationResult`. Subsequent reads from it will return its default value. mutating func clearCalibrationResult() {_uniqueStorage()._calibrationResult = nil} + /// Progress data var progressData: Mavsdk_Rpc_Calibration_ProgressData { get {return _storage._progressData ?? Mavsdk_Rpc_Calibration_ProgressData()} set {_uniqueStorage()._progressData = newValue} @@ -123,6 +125,7 @@ struct Mavsdk_Rpc_Calibration_CalibrateMagnetometerResponse { /// Clears the value of `calibrationResult`. Subsequent reads from it will return its default value. mutating func clearCalibrationResult() {_uniqueStorage()._calibrationResult = nil} + /// Progress data var progressData: Mavsdk_Rpc_Calibration_ProgressData { get {return _storage._progressData ?? Mavsdk_Rpc_Calibration_ProgressData()} set {_uniqueStorage()._progressData = newValue} @@ -163,6 +166,7 @@ struct Mavsdk_Rpc_Calibration_CalibrateGimbalAccelerometerResponse { /// Clears the value of `calibrationResult`. Subsequent reads from it will return its default value. mutating func clearCalibrationResult() {_uniqueStorage()._calibrationResult = nil} + /// Progress data var progressData: Mavsdk_Rpc_Calibration_ProgressData { get {return _storage._progressData ?? Mavsdk_Rpc_Calibration_ProgressData()} set {_uniqueStorage()._progressData = newValue} @@ -199,29 +203,55 @@ struct Mavsdk_Rpc_Calibration_CancelResponse { init() {} } +/// Result type. struct Mavsdk_Rpc_Calibration_CalibrationResult { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Result enum value var result: Mavsdk_Rpc_Calibration_CalibrationResult.Result = .unknown + /// Human-readable English string describing the result var resultStr: String = String() var unknownFields = SwiftProtobuf.UnknownStorage() + /// Possible results returned for calibration commands enum Result: SwiftProtobuf.Enum { typealias RawValue = Int + + /// Unknown error case unknown // = 0 + + /// The calibration process succeeded case success // = 1 + + /// Intermediate message showing progress of the calibration process case inProgress // = 2 + + /// Intermediate message giving instructions on the next steps required by the process case instruction // = 3 + + /// Calibration failed case failed // = 4 + + /// No system is connected case noSystem // = 5 + + /// Connection error case connectionError // = 6 + + /// Vehicle is busy case busy // = 7 + + /// Command refused by vehicle case commandDenied // = 8 + + /// Command timed out case timeout // = 9 + + /// Calibration process got cancelled case cancelled // = 10 case UNRECOGNIZED(Int) @@ -289,6 +319,10 @@ extension Mavsdk_Rpc_Calibration_CalibrationResult.Result: CaseIterable { #endif // swift(>=4.2) +/// +/// Progress data coming from calibration. +/// +/// Can be a progress percentage, or an instruction text. struct Mavsdk_Rpc_Calibration_ProgressData { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for @@ -296,10 +330,12 @@ struct Mavsdk_Rpc_Calibration_ProgressData { var hasProgress_p: Bool = false + /// Progress (percentage) var progress: Float = 0 var hasStatusText_p: Bool = false + /// Instruction text var statusText: String = String() var unknownFields = SwiftProtobuf.UnknownStorage() diff --git a/Sources/MAVSDK-Swift/Generated/camera.pb.swift b/Sources/MAVSDK-Swift/Generated/camera.pb.swift index 92fbf7b..5e44ee9 100644 --- a/Sources/MAVSDK-Swift/Generated/camera.pb.swift +++ b/Sources/MAVSDK-Swift/Generated/camera.pb.swift @@ -19,10 +19,17 @@ fileprivate struct _GeneratedWithProtocGenSwiftVersion: SwiftProtobuf.ProtobufAP typealias Version = _2 } +/// Camera mode type. enum Mavsdk_Rpc_Camera_CameraMode: SwiftProtobuf.Enum { typealias RawValue = Int + + /// Unknown case unknown // = 0 + + /// Photo mode case photo // = 1 + + /// Video mode case video // = 2 case UNRECOGNIZED(Int) @@ -99,6 +106,7 @@ struct Mavsdk_Rpc_Camera_StartPhotoIntervalRequest { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Interval between photos (in seconds) var intervalS: Float = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -287,6 +295,7 @@ struct Mavsdk_Rpc_Camera_SetModeRequest { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Camera mode to set var cameraMode: Mavsdk_Rpc_Camera_CameraMode = .unknown var unknownFields = SwiftProtobuf.UnknownStorage() @@ -330,6 +339,7 @@ struct Mavsdk_Rpc_Camera_ModeResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Camera mode var cameraMode: Mavsdk_Rpc_Camera_CameraMode = .unknown var unknownFields = SwiftProtobuf.UnknownStorage() @@ -352,6 +362,7 @@ struct Mavsdk_Rpc_Camera_VideoStreamInfoResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Video stream info var videoStreamInfo: Mavsdk_Rpc_Camera_VideoStreamInfo { get {return _storage._videoStreamInfo ?? Mavsdk_Rpc_Camera_VideoStreamInfo()} set {_uniqueStorage()._videoStreamInfo = newValue} @@ -383,6 +394,7 @@ struct Mavsdk_Rpc_Camera_CaptureInfoResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Capture info var captureInfo: Mavsdk_Rpc_Camera_CaptureInfo { get {return _storage._captureInfo ?? Mavsdk_Rpc_Camera_CaptureInfo()} set {_uniqueStorage()._captureInfo = newValue} @@ -414,6 +426,7 @@ struct Mavsdk_Rpc_Camera_CameraStatusResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Camera status var cameraStatus: Mavsdk_Rpc_Camera_CameraStatus { get {return _storage._cameraStatus ?? Mavsdk_Rpc_Camera_CameraStatus()} set {_uniqueStorage()._cameraStatus = newValue} @@ -445,6 +458,7 @@ struct Mavsdk_Rpc_Camera_CurrentSettingsResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// List of current settings var currentSettings: [Mavsdk_Rpc_Camera_Setting] = [] var unknownFields = SwiftProtobuf.UnknownStorage() @@ -467,6 +481,7 @@ struct Mavsdk_Rpc_Camera_PossibleSettingOptionsResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// List of settings that can be changed var settingOptions: [Mavsdk_Rpc_Camera_SettingOptions] = [] var unknownFields = SwiftProtobuf.UnknownStorage() @@ -479,6 +494,7 @@ struct Mavsdk_Rpc_Camera_SetSettingRequest { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Desired setting var setting: Mavsdk_Rpc_Camera_Setting { get {return _storage._setting ?? Mavsdk_Rpc_Camera_Setting()} set {_uniqueStorage()._setting = newValue} @@ -516,26 +532,46 @@ struct Mavsdk_Rpc_Camera_SetSettingResponse { fileprivate var _storage = _StorageClass.defaultInstance } +/// Result type. struct Mavsdk_Rpc_Camera_CameraResult { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Result enum value var result: Mavsdk_Rpc_Camera_CameraResult.Result = .unknown + /// Human-readable English string describing the result var resultStr: String = String() var unknownFields = SwiftProtobuf.UnknownStorage() + /// Possible results returned for camera commands enum Result: SwiftProtobuf.Enum { typealias RawValue = Int + + /// Unknown error case unknown // = 0 + + /// Command executed successfully case success // = 1 + + /// Command in progress case inProgress // = 2 + + /// Camera is busy and rejected command case busy // = 3 + + /// Camera denied the command case denied // = 4 + + /// An error has occured while executing the command case error // = 5 + + /// Command timed out case timeout // = 6 + + /// Command has wrong argument(s) case wrongArgument // = 7 case UNRECOGNIZED(Int) @@ -594,11 +630,13 @@ extension Mavsdk_Rpc_Camera_CameraResult.Result: CaseIterable { #endif // swift(>=4.2) +/// Information about a picture just captured. struct Mavsdk_Rpc_Camera_CaptureInfo { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Location where the picture was taken var position: Mavsdk_Rpc_Camera_Position { get {return _storage._position ?? Mavsdk_Rpc_Camera_Position()} set {_uniqueStorage()._position = newValue} @@ -608,6 +646,7 @@ struct Mavsdk_Rpc_Camera_CaptureInfo { /// Clears the value of `position`. Subsequent reads from it will return its default value. mutating func clearPosition() {_uniqueStorage()._position = nil} + /// Attitude of the camera when the picture was taken (quaternion) var attitudeQuaternion: Mavsdk_Rpc_Camera_Quaternion { get {return _storage._attitudeQuaternion ?? Mavsdk_Rpc_Camera_Quaternion()} set {_uniqueStorage()._attitudeQuaternion = newValue} @@ -617,6 +656,7 @@ struct Mavsdk_Rpc_Camera_CaptureInfo { /// Clears the value of `attitudeQuaternion`. Subsequent reads from it will return its default value. mutating func clearAttitudeQuaternion() {_uniqueStorage()._attitudeQuaternion = nil} + /// Attitude of the camera when the picture was taken (euler angle) var attitudeEulerAngle: Mavsdk_Rpc_Camera_EulerAngle { get {return _storage._attitudeEulerAngle ?? Mavsdk_Rpc_Camera_EulerAngle()} set {_uniqueStorage()._attitudeEulerAngle = newValue} @@ -626,21 +666,25 @@ struct Mavsdk_Rpc_Camera_CaptureInfo { /// Clears the value of `attitudeEulerAngle`. Subsequent reads from it will return its default value. mutating func clearAttitudeEulerAngle() {_uniqueStorage()._attitudeEulerAngle = nil} + /// Timestamp in UTC (since UNIX epoch) in microseconds var timeUtcUs: UInt64 { get {return _storage._timeUtcUs} set {_uniqueStorage()._timeUtcUs = newValue} } + /// True if the capture was successful var isSuccess: Bool { get {return _storage._isSuccess} set {_uniqueStorage()._isSuccess = newValue} } + /// Zero-based index of this image since vehicle was armed var index: Int32 { get {return _storage._index} set {_uniqueStorage()._index = newValue} } + /// Download URL of this image var fileURL: String { get {return _storage._fileURL} set {_uniqueStorage()._fileURL = newValue} @@ -653,17 +697,22 @@ struct Mavsdk_Rpc_Camera_CaptureInfo { fileprivate var _storage = _StorageClass.defaultInstance } +/// Position type in global coordinates. struct Mavsdk_Rpc_Camera_Position { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Latitude in degrees (range: -90 to +90) var latitudeDeg: Double = 0 + /// Longitude in degrees (range: -180 to +180) var longitudeDeg: Double = 0 + /// Altitude AMSL (above mean sea level) in metres var absoluteAltitudeM: Float = 0 + /// Altitude relative to takeoff altitude in metres var relativeAltitudeM: Float = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -671,17 +720,30 @@ struct Mavsdk_Rpc_Camera_Position { init() {} } +/// +/// Quaternion type. +/// +/// All rotations and axis systems follow the right-hand rule. +/// The Hamilton quaternion product definition is used. +/// A zero-rotation quaternion is represented by (1,0,0,0). +/// The quaternion could also be written as w + xi + yj + zk. +/// +/// For more info see: https://en.wikipedia.org/wiki/Quaternion struct Mavsdk_Rpc_Camera_Quaternion { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Quaternion entry 0, also denoted as a var w: Float = 0 + /// Quaternion entry 1, also denoted as b var x: Float = 0 + /// Quaternion entry 2, also denoted as c var y: Float = 0 + /// Quaternion entry 3, also denoted as d var z: Float = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -689,15 +751,25 @@ struct Mavsdk_Rpc_Camera_Quaternion { init() {} } +/// +/// Euler angle type. +/// +/// All rotations and axis systems follow the right-hand rule. +/// The Euler angles follow the convention of a 3-2-1 intrinsic Tait-Bryan rotation sequence. +/// +/// For more info see https://en.wikipedia.org/wiki/Euler_angles struct Mavsdk_Rpc_Camera_EulerAngle { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Roll angle in degrees, positive is banking to the right var rollDeg: Float = 0 + /// Pitch angle in degrees, positive is pitching nose up var pitchDeg: Float = 0 + /// Yaw angle in degrees, positive is clock-wise seen from above var yawDeg: Float = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -705,21 +777,28 @@ struct Mavsdk_Rpc_Camera_EulerAngle { init() {} } +/// Type for video stream settings. struct Mavsdk_Rpc_Camera_VideoStreamSettings { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Frames per second var frameRateHz: Float = 0 + /// Horizontal resolution (in pixels) var horizontalResolutionPix: UInt32 = 0 + /// Vertical resolution (in pixels) var verticalResolutionPix: UInt32 = 0 + /// Bit rate (in bits per second) var bitRateBS: UInt32 = 0 + /// Video image rotation (clockwise, 0-359 degrees) var rotationDeg: UInt32 = 0 + /// Video stream URI var uri: String = String() var unknownFields = SwiftProtobuf.UnknownStorage() @@ -727,11 +806,13 @@ struct Mavsdk_Rpc_Camera_VideoStreamSettings { init() {} } +/// Information about the video stream. struct Mavsdk_Rpc_Camera_VideoStreamInfo { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Video stream settings var videoStreamSettings: Mavsdk_Rpc_Camera_VideoStreamSettings { get {return _storage._videoStreamSettings ?? Mavsdk_Rpc_Camera_VideoStreamSettings()} set {_uniqueStorage()._videoStreamSettings = newValue} @@ -741,6 +822,7 @@ struct Mavsdk_Rpc_Camera_VideoStreamInfo { /// Clears the value of `videoStreamSettings`. Subsequent reads from it will return its default value. mutating func clearVideoStreamSettings() {_uniqueStorage()._videoStreamSettings = nil} + /// Current status of video streaming var videoStreamStatus: Mavsdk_Rpc_Camera_VideoStreamInfo.VideoStreamStatus { get {return _storage._videoStreamStatus} set {_uniqueStorage()._videoStreamStatus = newValue} @@ -750,7 +832,11 @@ struct Mavsdk_Rpc_Camera_VideoStreamInfo { enum VideoStreamStatus: SwiftProtobuf.Enum { typealias RawValue = Int + + /// Video stream is not running. case notRunning // = 0 + + /// Video stream is running. case inProgress // = 1 case UNRECOGNIZED(Int) @@ -793,6 +879,7 @@ extension Mavsdk_Rpc_Camera_VideoStreamInfo.VideoStreamStatus: CaseIterable { #endif // swift(>=4.2) +/// Information about the camera status. struct Mavsdk_Rpc_Camera_CameraStatus { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for @@ -802,24 +889,37 @@ struct Mavsdk_Rpc_Camera_CameraStatus { var photoIntervalOn: Bool = false + /// Used storage (in MiB) var usedStorageMib: Float = 0 + /// Available storage (in MiB) var availableStorageMib: Float = 0 + /// Total storage (in MiB) var totalStorageMib: Float = 0 + /// Elapsed time since starting the video recording (in seconds) var recordingTimeS: Float = 0 + /// Current folder name where media are saved var mediaFolderName: String = String() + /// Storage status var storageStatus: Mavsdk_Rpc_Camera_CameraStatus.StorageStatus = .notAvailable var unknownFields = SwiftProtobuf.UnknownStorage() + /// Storage status type. enum StorageStatus: SwiftProtobuf.Enum { typealias RawValue = Int + + /// Status not available case notAvailable // = 0 + + /// Storage is not formatted (i.e. has no recognized file system) case unformatted // = 1 + + /// Storage is formatted (i.e. has recognized a file system) case formatted // = 2 case UNRECOGNIZED(Int) @@ -863,21 +963,25 @@ extension Mavsdk_Rpc_Camera_CameraStatus.StorageStatus: CaseIterable { #endif // swift(>=4.2) +/// Type to represent a setting with a selected option. struct Mavsdk_Rpc_Camera_Setting { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Name of a setting (machine readable) var settingID: String { get {return _storage._settingID} set {_uniqueStorage()._settingID = newValue} } + /// Description of the setting (human readable) var settingDescription: String { get {return _storage._settingDescription} set {_uniqueStorage()._settingDescription = newValue} } + /// Selected option var option: Mavsdk_Rpc_Camera_Option { get {return _storage._option ?? Mavsdk_Rpc_Camera_Option()} set {_uniqueStorage()._option = newValue} @@ -894,13 +998,16 @@ struct Mavsdk_Rpc_Camera_Setting { fileprivate var _storage = _StorageClass.defaultInstance } +/// Type to represent a setting option. struct Mavsdk_Rpc_Camera_Option { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Name of the option (machine readable) var optionID: String = String() + /// Description of the option (human readable) var optionDescription: String = String() var unknownFields = SwiftProtobuf.UnknownStorage() @@ -908,15 +1015,19 @@ struct Mavsdk_Rpc_Camera_Option { init() {} } +/// Type to represent a setting with a list of options to choose from. struct Mavsdk_Rpc_Camera_SettingOptions { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Name of the setting (machine readable) var settingID: String = String() + /// Description of the setting (human readable) var settingDescription: String = String() + /// List of options var options: [Mavsdk_Rpc_Camera_Option] = [] var unknownFields = SwiftProtobuf.UnknownStorage() diff --git a/Sources/MAVSDK-Swift/Generated/core.pb.swift b/Sources/MAVSDK-Swift/Generated/core.pb.swift index f726f99..37fbc02 100644 --- a/Sources/MAVSDK-Swift/Generated/core.pb.swift +++ b/Sources/MAVSDK-Swift/Generated/core.pb.swift @@ -34,6 +34,7 @@ struct Mavsdk_Rpc_Core_ConnectionStateResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Connection state var connectionState: Mavsdk_Rpc_Core_ConnectionState { get {return _storage._connectionState ?? Mavsdk_Rpc_Core_ConnectionState()} set {_uniqueStorage()._connectionState = newValue} @@ -65,6 +66,7 @@ struct Mavsdk_Rpc_Core_ListRunningPluginsResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Plugin info var pluginInfo: [Mavsdk_Rpc_Core_PluginInfo] = [] var unknownFields = SwiftProtobuf.UnknownStorage() @@ -72,13 +74,16 @@ struct Mavsdk_Rpc_Core_ListRunningPluginsResponse { init() {} } +/// Connection state type. struct Mavsdk_Rpc_Core_ConnectionState { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// UUID of the vehicle var uuid: UInt64 = 0 + /// Whether the vehicle got connected or disconnected var isConnected: Bool = false var unknownFields = SwiftProtobuf.UnknownStorage() @@ -86,15 +91,19 @@ struct Mavsdk_Rpc_Core_ConnectionState { init() {} } +/// Plugin info type. struct Mavsdk_Rpc_Core_PluginInfo { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Name of the plugin var name: String = String() + /// Address where the plugin is running var address: String = String() + /// Port where the plugin is running var port: Int32 = 0 var unknownFields = SwiftProtobuf.UnknownStorage() diff --git a/Sources/MAVSDK-Swift/Generated/gimbal.pb.swift b/Sources/MAVSDK-Swift/Generated/gimbal.pb.swift index b7f7571..76b52d5 100644 --- a/Sources/MAVSDK-Swift/Generated/gimbal.pb.swift +++ b/Sources/MAVSDK-Swift/Generated/gimbal.pb.swift @@ -19,9 +19,14 @@ fileprivate struct _GeneratedWithProtocGenSwiftVersion: SwiftProtobuf.ProtobufAP typealias Version = _2 } +/// Gimbal mode type. enum Mavsdk_Rpc_Gimbal_GimbalMode: SwiftProtobuf.Enum { typealias RawValue = Int + + /// Yaw follow will point the gimbal to the vehicle heading case yawFollow // = 0 + + /// Yaw lock will fix the gimbal poiting to an absolute direction case yawLock // = 1 case UNRECOGNIZED(Int) @@ -64,8 +69,10 @@ struct Mavsdk_Rpc_Gimbal_SetPitchAndYawRequest { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Pitch angle in degrees (negative points down) var pitchDeg: Float = 0 + /// Yaw angle in degrees (positive is clock-wise, range: -180 to 180 or 0 to 360) var yawDeg: Float = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -99,6 +106,7 @@ struct Mavsdk_Rpc_Gimbal_SetModeRequest { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// The mode to be set. var gimbalMode: Mavsdk_Rpc_Gimbal_GimbalMode = .yawFollow var unknownFields = SwiftProtobuf.UnknownStorage() @@ -127,45 +135,57 @@ struct Mavsdk_Rpc_Gimbal_SetModeResponse { fileprivate var _storage = _StorageClass.defaultInstance } +/// Result type. struct Mavsdk_Rpc_Gimbal_GimbalResult { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. - var result: Mavsdk_Rpc_Gimbal_GimbalResult.Result = .success + /// Result enum value + var result: Mavsdk_Rpc_Gimbal_GimbalResult.Result = .unknown + /// Human-readable English string describing the result var resultStr: String = String() var unknownFields = SwiftProtobuf.UnknownStorage() + /// Possible results returned for gimbal commands. enum Result: SwiftProtobuf.Enum { typealias RawValue = Int - case success // = 0 - case error // = 1 - case timeout // = 2 - case unknown // = 1000 + + /// Unknown error + case unknown // = 0 + + /// Command was accepted + case success // = 1 + + /// Error occurred sending the command + case error // = 2 + + /// Command timed out + case timeout // = 3 case UNRECOGNIZED(Int) init() { - self = .success + self = .unknown } init?(rawValue: Int) { switch rawValue { - case 0: self = .success - case 1: self = .error - case 2: self = .timeout - case 1000: self = .unknown + case 0: self = .unknown + case 1: self = .success + case 2: self = .error + case 3: self = .timeout default: self = .UNRECOGNIZED(rawValue) } } var rawValue: Int { switch self { - case .success: return 0 - case .error: return 1 - case .timeout: return 2 - case .unknown: return 1000 + case .unknown: return 0 + case .success: return 1 + case .error: return 2 + case .timeout: return 3 case .UNRECOGNIZED(let i): return i } } @@ -180,10 +200,10 @@ struct Mavsdk_Rpc_Gimbal_GimbalResult { extension Mavsdk_Rpc_Gimbal_GimbalResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. static var allCases: [Mavsdk_Rpc_Gimbal_GimbalResult.Result] = [ + .unknown, .success, .error, .timeout, - .unknown, ] } @@ -404,7 +424,7 @@ extension Mavsdk_Rpc_Gimbal_GimbalResult: SwiftProtobuf.Message, SwiftProtobuf._ } func traverse(visitor: inout V) throws { - if self.result != .success { + if self.result != .unknown { try visitor.visitSingularEnumField(value: self.result, fieldNumber: 1) } if !self.resultStr.isEmpty { @@ -423,9 +443,9 @@ extension Mavsdk_Rpc_Gimbal_GimbalResult: SwiftProtobuf.Message, SwiftProtobuf._ extension Mavsdk_Rpc_Gimbal_GimbalResult.Result: SwiftProtobuf._ProtoNameProviding { static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ - 0: .same(proto: "SUCCESS"), - 1: .same(proto: "ERROR"), - 2: .same(proto: "TIMEOUT"), - 1000: .same(proto: "UNKNOWN"), + 0: .same(proto: "UNKNOWN"), + 1: .same(proto: "SUCCESS"), + 2: .same(proto: "ERROR"), + 3: .same(proto: "TIMEOUT"), ] } diff --git a/Sources/MAVSDK-Swift/Generated/info.pb.swift b/Sources/MAVSDK-Swift/Generated/info.pb.swift index 3f316d5..e6dcb05 100644 --- a/Sources/MAVSDK-Swift/Generated/info.pb.swift +++ b/Sources/MAVSDK-Swift/Generated/info.pb.swift @@ -19,27 +19,37 @@ fileprivate struct _GeneratedWithProtocGenSwiftVersion: SwiftProtobuf.ProtobufAP typealias Version = _2 } +/// System version information. struct Mavsdk_Rpc_Info_Version { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Flight software major version var flightSwMajor: Int32 = 0 + /// Flight software minor version var flightSwMinor: Int32 = 0 + /// Flight software patch version var flightSwPatch: Int32 = 0 + /// Flight software vendor major version var flightSwVendorMajor: Int32 = 0 + /// Flight software vendor minor version var flightSwVendorMinor: Int32 = 0 + /// Flight software vendor patch version var flightSwVendorPatch: Int32 = 0 + /// Operating system software major version var osSwMajor: Int32 = 0 + /// Operating system software minor version var osSwMinor: Int32 = 0 + /// Operating system software patch version var osSwPatch: Int32 = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -71,6 +81,7 @@ struct Mavsdk_Rpc_Info_GetVersionResponse { /// Clears the value of `infoResult`. Subsequent reads from it will return its default value. mutating func clearInfoResult() {_uniqueStorage()._infoResult = nil} + /// Version information about the system var version: Mavsdk_Rpc_Info_Version { get {return _storage._version ?? Mavsdk_Rpc_Info_Version()} set {_uniqueStorage()._version = newValue} @@ -87,21 +98,31 @@ struct Mavsdk_Rpc_Info_GetVersionResponse { fileprivate var _storage = _StorageClass.defaultInstance } +/// Result type. struct Mavsdk_Rpc_Info_InfoResult { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Result enum value var result: Mavsdk_Rpc_Info_InfoResult.Result = .unknown + /// Human-readable English string describing the result var resultStr: String = String() var unknownFields = SwiftProtobuf.UnknownStorage() + /// Possible results returned for info requests. enum Result: SwiftProtobuf.Enum { typealias RawValue = Int + + /// Unknown error case unknown // = 0 + + /// Request succeeded case success // = 1 + + /// Information has not been received yet case informationNotReceivedYet // = 2 case UNRECOGNIZED(Int) diff --git a/Sources/MAVSDK-Swift/Generated/mission.pb.swift b/Sources/MAVSDK-Swift/Generated/mission.pb.swift index 14b4aa4..e508544 100644 --- a/Sources/MAVSDK-Swift/Generated/mission.pb.swift +++ b/Sources/MAVSDK-Swift/Generated/mission.pb.swift @@ -24,6 +24,7 @@ struct Mavsdk_Rpc_Mission_UploadMissionRequest { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// List of mission items var missionItems: [Mavsdk_Rpc_Mission_MissionItem] = [] var unknownFields = SwiftProtobuf.UnknownStorage() @@ -96,6 +97,7 @@ struct Mavsdk_Rpc_Mission_DownloadMissionResponse { /// Clears the value of `missionResult`. Subsequent reads from it will return its default value. mutating func clearMissionResult() {_uniqueStorage()._missionResult = nil} + /// List of downloaded mission items var missionItems: [Mavsdk_Rpc_Mission_MissionItem] { get {return _storage._missionItems} set {_uniqueStorage()._missionItems = newValue} @@ -226,6 +228,7 @@ struct Mavsdk_Rpc_Mission_SetCurrentMissionItemIndexRequest { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Index of the mission item to be set as the next one (0-based) var index: Int32 = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -269,6 +272,7 @@ struct Mavsdk_Rpc_Mission_IsMissionFinishedResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// True if the mission is finished and the last mission item has been reached var isFinished: Bool = false var unknownFields = SwiftProtobuf.UnknownStorage() @@ -291,6 +295,7 @@ struct Mavsdk_Rpc_Mission_MissionProgressResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Mission progress var missionProgress: Mavsdk_Rpc_Mission_MissionProgress { get {return _storage._missionProgress ?? Mavsdk_Rpc_Mission_MissionProgress()} set {_uniqueStorage()._missionProgress = newValue} @@ -322,6 +327,7 @@ struct Mavsdk_Rpc_Mission_GetReturnToLaunchAfterMissionResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// If true, trigger an RTL at the end of the mission var enable: Bool = false var unknownFields = SwiftProtobuf.UnknownStorage() @@ -334,6 +340,7 @@ struct Mavsdk_Rpc_Mission_SetReturnToLaunchAfterMissionRequest { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// If true, trigger an RTL at the end of the mission var enable: Bool = false var unknownFields = SwiftProtobuf.UnknownStorage() @@ -351,40 +358,70 @@ struct Mavsdk_Rpc_Mission_SetReturnToLaunchAfterMissionResponse { init() {} } +/// +/// Type representing a mission item. +/// +/// A MissionItem can contain a position and/or actions. +/// Mission items are building blocks to assemble a mission, +/// which can be sent to (or received from) a system. +/// They cannot be used independently. struct Mavsdk_Rpc_Mission_MissionItem { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Latitude in degrees (range: -90 to +90) var latitudeDeg: Double = 0 + /// Longitude in degrees (range: -180 to +180) var longitudeDeg: Double = 0 + /// Altitude relative to takeoff altitude in metres var relativeAltitudeM: Float = 0 + /// Speed to use after this mission item (in metres/second) var speedMS: Float = 0 + /// True will make the drone fly through without stopping, while false will make the drone stop on the waypoint var isFlyThrough: Bool = false + /// Gimbal pitch (in degrees) var gimbalPitchDeg: Float = 0 + /// Gimbal yaw (in degrees) var gimbalYawDeg: Float = 0 + /// Camera action to trigger at this mission item var cameraAction: Mavsdk_Rpc_Mission_MissionItem.CameraAction = .none + /// Loiter time (in seconds) var loiterTimeS: Float = 0 + /// Camera photo interval to use after this mission item (in seconds) var cameraPhotoIntervalS: Double = 0 var unknownFields = SwiftProtobuf.UnknownStorage() + /// Possible camera actions at a mission item. enum CameraAction: SwiftProtobuf.Enum { typealias RawValue = Int + + /// No action case none // = 0 + + /// Take a single photo case takePhoto // = 1 + + /// Start capturing photos at regular intervals case startPhotoInterval // = 2 + + /// Stop capturing photos at regular intervals case stopPhotoInterval // = 3 + + /// Start capturing video case startVideo // = 4 + + /// Stop capturing video case stopVideo // = 5 case UNRECOGNIZED(Int) @@ -437,13 +474,16 @@ extension Mavsdk_Rpc_Mission_MissionItem.CameraAction: CaseIterable { #endif // swift(>=4.2) +/// Mission progress type. struct Mavsdk_Rpc_Mission_MissionProgress { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Current mission item index (0-based) var currentItemIndex: Int32 = 0 + /// Total number of mission items var missionCount: Int32 = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -451,31 +491,61 @@ struct Mavsdk_Rpc_Mission_MissionProgress { init() {} } +/// Result type. struct Mavsdk_Rpc_Mission_MissionResult { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Result enum value var result: Mavsdk_Rpc_Mission_MissionResult.Result = .unknown + /// Human-readable English string describing the result var resultStr: String = String() var unknownFields = SwiftProtobuf.UnknownStorage() + /// Possible results returned for action requests. enum Result: SwiftProtobuf.Enum { typealias RawValue = Int + + /// Unknown error case unknown // = 0 + + /// Request succeeded case success // = 1 + + /// Error case error // = 2 + + /// Too many mission items in the mission case tooManyMissionItems // = 3 + + /// Vehicle is busy case busy // = 4 + + /// Request timed out case timeout // = 5 + + /// Invalid argument case invalidArgument // = 6 + + /// Mission downloaded from the system is not supported case unsupported // = 7 + + /// No mission available on the system case noMissionAvailable // = 8 + + /// Failed to open the QGroundControl plan case failedToOpenQgcPlan // = 9 + + /// Failed to parse the QGroundControl plan case failedToParseQgcPlan // = 10 + + /// Unsupported mission command case unsupportedMissionCmd // = 11 + + /// Mission transfer (upload or download) has been cancelled case transferCancelled // = 12 case UNRECOGNIZED(Int) diff --git a/Sources/MAVSDK-Swift/Generated/offboard.pb.swift b/Sources/MAVSDK-Swift/Generated/offboard.pb.swift index 82407bd..5303a71 100644 --- a/Sources/MAVSDK-Swift/Generated/offboard.pb.swift +++ b/Sources/MAVSDK-Swift/Generated/offboard.pb.swift @@ -96,6 +96,7 @@ struct Mavsdk_Rpc_Offboard_IsActiveResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// True if offboard is active var isActive: Bool = false var unknownFields = SwiftProtobuf.UnknownStorage() @@ -108,6 +109,7 @@ struct Mavsdk_Rpc_Offboard_SetAttitudeRequest { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Attitude roll, pitch and yaw along with thrust var attitude: Mavsdk_Rpc_Offboard_Attitude { get {return _storage._attitude ?? Mavsdk_Rpc_Offboard_Attitude()} set {_uniqueStorage()._attitude = newValue} @@ -139,6 +141,7 @@ struct Mavsdk_Rpc_Offboard_SetActuatorControlRequest { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Actuator control values var actuatorControl: Mavsdk_Rpc_Offboard_ActuatorControl { get {return _storage._actuatorControl ?? Mavsdk_Rpc_Offboard_ActuatorControl()} set {_uniqueStorage()._actuatorControl = newValue} @@ -170,6 +173,7 @@ struct Mavsdk_Rpc_Offboard_SetAttitudeRateRequest { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Attitude rate roll, pitch and yaw angular rate along with thrust var attitudeRate: Mavsdk_Rpc_Offboard_AttitudeRate { get {return _storage._attitudeRate ?? Mavsdk_Rpc_Offboard_AttitudeRate()} set {_uniqueStorage()._attitudeRate = newValue} @@ -201,6 +205,7 @@ struct Mavsdk_Rpc_Offboard_SetPositionNedRequest { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Position and yaw var positionNedYaw: Mavsdk_Rpc_Offboard_PositionNedYaw { get {return _storage._positionNedYaw ?? Mavsdk_Rpc_Offboard_PositionNedYaw()} set {_uniqueStorage()._positionNedYaw = newValue} @@ -232,6 +237,7 @@ struct Mavsdk_Rpc_Offboard_SetVelocityBodyRequest { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Velocity and yaw angular rate var velocityBodyYawspeed: Mavsdk_Rpc_Offboard_VelocityBodyYawspeed { get {return _storage._velocityBodyYawspeed ?? Mavsdk_Rpc_Offboard_VelocityBodyYawspeed()} set {_uniqueStorage()._velocityBodyYawspeed = newValue} @@ -263,6 +269,7 @@ struct Mavsdk_Rpc_Offboard_SetVelocityNedRequest { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Velocity and yaw var velocityNedYaw: Mavsdk_Rpc_Offboard_VelocityNedYaw { get {return _storage._velocityNedYaw ?? Mavsdk_Rpc_Offboard_VelocityNedYaw()} set {_uniqueStorage()._velocityNedYaw = newValue} @@ -289,17 +296,22 @@ struct Mavsdk_Rpc_Offboard_SetVelocityNedResponse { init() {} } +/// Type for attitude body angles in NED reference frame (roll, pitch, yaw and thrust) struct Mavsdk_Rpc_Offboard_Attitude { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Roll angle (in degrees, positive is right side down) var rollDeg: Float = 0 + /// Pitch angle (in degrees, positive is nose up) var pitchDeg: Float = 0 + /// Yaw angle (in degrees, positive is move nose to the right) var yawDeg: Float = 0 + /// Thrust (range: 0 to 1) var thrustValue: Float = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -307,11 +319,15 @@ struct Mavsdk_Rpc_Offboard_Attitude { init() {} } +/// +/// Eight controls that will be given to the group. Each control is a normalized +/// (-1..+1) command value, which will be mapped and scaled through the mixer. struct Mavsdk_Rpc_Offboard_ActuatorControlGroup { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Controls in the group var controls: [Float] = [] var unknownFields = SwiftProtobuf.UnknownStorage() @@ -319,11 +335,28 @@ struct Mavsdk_Rpc_Offboard_ActuatorControlGroup { init() {} } +/// +/// Type for actuator control. +/// +/// Control members should be normed to -1..+1 where 0 is neutral position. +/// Throttle for single rotation direction motors is 0..1, negative range for reverse direction. +/// +/// One group support eight controls. +/// +/// Up to 16 actuator controls can be set. To ignore an output group, set all it conrols to NaN. +/// If one or more controls in group is not NaN, then all NaN controls will sent as zero. +/// The first 8 actuator controls internally map to control group 0, the latter 8 actuator +/// controls map to control group 1. Depending on what controls are set (instead of NaN) 1 or 2 +/// MAVLink messages are actually sent. +/// +/// In PX4 v1.9.0 Only first four Control Groups are supported +/// (https://github.com/PX4/Firmware/blob/v1.9.0/src/modules/mavlink/mavlink_receiver.cpp#L980). struct Mavsdk_Rpc_Offboard_ActuatorControl { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Control groups. var groups: [Mavsdk_Rpc_Offboard_ActuatorControlGroup] = [] var unknownFields = SwiftProtobuf.UnknownStorage() @@ -331,17 +364,22 @@ struct Mavsdk_Rpc_Offboard_ActuatorControl { init() {} } +/// Type for attitude rate commands in body coordinates (roll, pitch, yaw angular rate and thrust) struct Mavsdk_Rpc_Offboard_AttitudeRate { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Roll angular rate (in degrees/second, positive for clock-wise looking from front) var rollDegS: Float = 0 + /// Pitch angular rate (in degrees/second, positive for head/front moving up) var pitchDegS: Float = 0 + /// Yaw angular rate (in degrees/second, positive for clock-wise looking from above) var yawDegS: Float = 0 + /// Thrust (range: 0 to 1) var thrustValue: Float = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -349,17 +387,22 @@ struct Mavsdk_Rpc_Offboard_AttitudeRate { init() {} } +/// Type for position commands in NED (North East Down) coordinates and yaw. struct Mavsdk_Rpc_Offboard_PositionNedYaw { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Position North (in metres) var northM: Float = 0 + /// Position East (in metres) var eastM: Float = 0 + /// Position Down (in metres) var downM: Float = 0 + /// Yaw in degrees (0 North, positive is clock-wise looking from above) var yawDeg: Float = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -367,17 +410,22 @@ struct Mavsdk_Rpc_Offboard_PositionNedYaw { init() {} } +/// Type for velocity commands in body coordinates. struct Mavsdk_Rpc_Offboard_VelocityBodyYawspeed { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Velocity forward (in metres/second) var forwardMS: Float = 0 + /// Velocity right (in metres/second) var rightMS: Float = 0 + /// Velocity down (in metres/second) var downMS: Float = 0 + /// Yaw angular rate (in degrees/second, positive for clock-wise looking from above) var yawspeedDegS: Float = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -385,17 +433,22 @@ struct Mavsdk_Rpc_Offboard_VelocityBodyYawspeed { init() {} } +/// Type for velocity commands in NED (North East Down) coordinates and yaw. struct Mavsdk_Rpc_Offboard_VelocityNedYaw { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Velocity North (in metres/second) var northMS: Float = 0 + /// Velocity East (in metres/second) var eastMS: Float = 0 + /// Velocity Down (in metres/second) var downMS: Float = 0 + /// Yaw in degrees (0 North, positive is clock-wise looking from above) var yawDeg: Float = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -403,26 +456,46 @@ struct Mavsdk_Rpc_Offboard_VelocityNedYaw { init() {} } +/// Result type. struct Mavsdk_Rpc_Offboard_OffboardResult { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Result enum value var result: Mavsdk_Rpc_Offboard_OffboardResult.Result = .unknown + /// Human-readable English string describing the result var resultStr: String = String() var unknownFields = SwiftProtobuf.UnknownStorage() + /// Possible results returned for offboard requests enum Result: SwiftProtobuf.Enum { typealias RawValue = Int + + /// Unknown error case unknown // = 0 + + /// Request succeeded case success // = 1 + + /// No system is connected case noSystem // = 2 + + /// Connection error case connectionError // = 3 + + /// Vehicle is busy case busy // = 4 + + /// Command denied case commandDenied // = 5 + + /// Request timed out case timeout // = 6 + + /// Cannot start without setpoint set case noSetpointSet // = 7 case UNRECOGNIZED(Int) diff --git a/Sources/MAVSDK-Swift/Generated/param.pb.swift b/Sources/MAVSDK-Swift/Generated/param.pb.swift index 40f18eb..da046c8 100644 --- a/Sources/MAVSDK-Swift/Generated/param.pb.swift +++ b/Sources/MAVSDK-Swift/Generated/param.pb.swift @@ -24,6 +24,7 @@ struct Mavsdk_Rpc_Param_GetIntParamRequest { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Name of the parameter var name: String = String() var unknownFields = SwiftProtobuf.UnknownStorage() @@ -45,6 +46,7 @@ struct Mavsdk_Rpc_Param_GetIntParamResponse { /// Clears the value of `paramResult`. Subsequent reads from it will return its default value. mutating func clearParamResult() {_uniqueStorage()._paramResult = nil} + /// Value of the requested parameter var value: Int32 { get {return _storage._value} set {_uniqueStorage()._value = newValue} @@ -62,8 +64,10 @@ struct Mavsdk_Rpc_Param_SetIntParamRequest { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Name of the parameter to set var name: String = String() + /// Value the parameter should be set to var value: Int32 = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -97,6 +101,7 @@ struct Mavsdk_Rpc_Param_GetFloatParamRequest { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Name of the parameter var name: String = String() var unknownFields = SwiftProtobuf.UnknownStorage() @@ -118,6 +123,7 @@ struct Mavsdk_Rpc_Param_GetFloatParamResponse { /// Clears the value of `paramResult`. Subsequent reads from it will return its default value. mutating func clearParamResult() {_uniqueStorage()._paramResult = nil} + /// Value of the requested parameter var value: Float { get {return _storage._value} set {_uniqueStorage()._value = newValue} @@ -135,8 +141,10 @@ struct Mavsdk_Rpc_Param_SetFloatParamRequest { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Name of the parameter to set var name: String = String() + /// Value the parameter should be set to var value: Float = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -165,24 +173,40 @@ struct Mavsdk_Rpc_Param_SetFloatParamResponse { fileprivate var _storage = _StorageClass.defaultInstance } +/// Result type. struct Mavsdk_Rpc_Param_ParamResult { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Result enum value var result: Mavsdk_Rpc_Param_ParamResult.Result = .unknown + /// Human-readable English string describing the result var resultStr: String = String() var unknownFields = SwiftProtobuf.UnknownStorage() + /// Possible results returned for param requests. enum Result: SwiftProtobuf.Enum { typealias RawValue = Int + + /// Unknown error case unknown // = 0 + + /// Request succeeded case success // = 1 + + /// Request timed out case timeout // = 2 + + /// Connection error case connectionError // = 3 + + /// Wrong type case wrongType // = 4 + + /// Parameter name too long (> 16) case paramNameTooLong // = 5 case UNRECOGNIZED(Int) diff --git a/Sources/MAVSDK-Swift/Generated/telemetry.grpc.swift b/Sources/MAVSDK-Swift/Generated/telemetry.grpc.swift index b87b349..930d3f2 100644 --- a/Sources/MAVSDK-Swift/Generated/telemetry.grpc.swift +++ b/Sources/MAVSDK-Swift/Generated/telemetry.grpc.swift @@ -73,6 +73,22 @@ fileprivate final class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeInAirCallB override class var method: String { return "/mavsdk.rpc.telemetry.TelemetryService/SubscribeInAir" } } +internal protocol Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeLandedStateCall: ClientCallServerStreaming { + /// Do not call this directly, call `receive()` in the protocol extension below instead. + func _receive(timeout: DispatchTime) throws -> Mavsdk_Rpc_Telemetry_LandedStateResponse? + /// Call this to wait for a result. Nonblocking. + func receive(completion: @escaping (ResultOrRPCError) -> Void) throws +} + +internal extension Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeLandedStateCall { + /// Call this to wait for a result. Blocking. + func receive(timeout: DispatchTime = .distantFuture) throws -> Mavsdk_Rpc_Telemetry_LandedStateResponse? { return try self._receive(timeout: timeout) } +} + +fileprivate final class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeLandedStateCallBase: ClientCallServerStreamingBase, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeLandedStateCall { + override class var method: String { return "/mavsdk.rpc.telemetry.TelemetryService/SubscribeLandedState" } +} + internal protocol Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeArmedCall: ClientCallServerStreaming { /// Do not call this directly, call `receive()` in the protocol extension below instead. func _receive(timeout: DispatchTime) throws -> Mavsdk_Rpc_Telemetry_ArmedResponse? @@ -121,6 +137,22 @@ fileprivate final class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeEu override class var method: String { return "/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeEuler" } } +internal protocol Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeAngularVelocityBodyCall: ClientCallServerStreaming { + /// Do not call this directly, call `receive()` in the protocol extension below instead. + func _receive(timeout: DispatchTime) throws -> Mavsdk_Rpc_Telemetry_AttitudeAngularVelocityBodyResponse? + /// Call this to wait for a result. Nonblocking. + func receive(completion: @escaping (ResultOrRPCError) -> Void) throws +} + +internal extension Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeAngularVelocityBodyCall { + /// Call this to wait for a result. Blocking. + func receive(timeout: DispatchTime = .distantFuture) throws -> Mavsdk_Rpc_Telemetry_AttitudeAngularVelocityBodyResponse? { return try self._receive(timeout: timeout) } +} + +fileprivate final class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeAngularVelocityBodyCallBase: ClientCallServerStreamingBase, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeAngularVelocityBodyCall { + override class var method: String { return "/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeAngularVelocityBody" } +} + internal protocol Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeCameraAttitudeQuaternionCall: ClientCallServerStreaming { /// Do not call this directly, call `receive()` in the protocol extension below instead. func _receive(timeout: DispatchTime) throws -> Mavsdk_Rpc_Telemetry_CameraAttitudeQuaternionResponse? @@ -265,6 +297,54 @@ fileprivate final class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeStatusText override class var method: String { return "/mavsdk.rpc.telemetry.TelemetryService/SubscribeStatusText" } } +internal protocol Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorControlTargetCall: ClientCallServerStreaming { + /// Do not call this directly, call `receive()` in the protocol extension below instead. + func _receive(timeout: DispatchTime) throws -> Mavsdk_Rpc_Telemetry_ActuatorControlTargetResponse? + /// Call this to wait for a result. Nonblocking. + func receive(completion: @escaping (ResultOrRPCError) -> Void) throws +} + +internal extension Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorControlTargetCall { + /// Call this to wait for a result. Blocking. + func receive(timeout: DispatchTime = .distantFuture) throws -> Mavsdk_Rpc_Telemetry_ActuatorControlTargetResponse? { return try self._receive(timeout: timeout) } +} + +fileprivate final class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorControlTargetCallBase: ClientCallServerStreamingBase, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorControlTargetCall { + override class var method: String { return "/mavsdk.rpc.telemetry.TelemetryService/SubscribeActuatorControlTarget" } +} + +internal protocol Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorOutputStatusCall: ClientCallServerStreaming { + /// Do not call this directly, call `receive()` in the protocol extension below instead. + func _receive(timeout: DispatchTime) throws -> Mavsdk_Rpc_Telemetry_ActuatorOutputStatusResponse? + /// Call this to wait for a result. Nonblocking. + func receive(completion: @escaping (ResultOrRPCError) -> Void) throws +} + +internal extension Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorOutputStatusCall { + /// Call this to wait for a result. Blocking. + func receive(timeout: DispatchTime = .distantFuture) throws -> Mavsdk_Rpc_Telemetry_ActuatorOutputStatusResponse? { return try self._receive(timeout: timeout) } +} + +fileprivate final class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorOutputStatusCallBase: ClientCallServerStreamingBase, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorOutputStatusCall { + override class var method: String { return "/mavsdk.rpc.telemetry.TelemetryService/SubscribeActuatorOutputStatus" } +} + +internal protocol Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeOdometryCall: ClientCallServerStreaming { + /// Do not call this directly, call `receive()` in the protocol extension below instead. + func _receive(timeout: DispatchTime) throws -> Mavsdk_Rpc_Telemetry_OdometryResponse? + /// Call this to wait for a result. Nonblocking. + func receive(completion: @escaping (ResultOrRPCError) -> Void) throws +} + +internal extension Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeOdometryCall { + /// Call this to wait for a result. Blocking. + func receive(timeout: DispatchTime = .distantFuture) throws -> Mavsdk_Rpc_Telemetry_OdometryResponse? { return try self._receive(timeout: timeout) } +} + +fileprivate final class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeOdometryCallBase: ClientCallServerStreamingBase, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeOdometryCall { + override class var method: String { return "/mavsdk.rpc.telemetry.TelemetryService/SubscribeOdometry" } +} + /// Instantiate Mavsdk_Rpc_Telemetry_TelemetryServiceServiceClient, then call methods of this protocol to make API calls. internal protocol Mavsdk_Rpc_Telemetry_TelemetryServiceService: ServiceClient { @@ -283,6 +363,11 @@ internal protocol Mavsdk_Rpc_Telemetry_TelemetryServiceService: ServiceClient { /// Use methods on the returned object to get streamed responses. func subscribeInAir(_ request: Mavsdk_Rpc_Telemetry_SubscribeInAirRequest, metadata customMetadata: Metadata, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeInAirCall + /// Asynchronous. Server-streaming. + /// Send the initial message. + /// Use methods on the returned object to get streamed responses. + func subscribeLandedState(_ request: Mavsdk_Rpc_Telemetry_SubscribeLandedStateRequest, metadata customMetadata: Metadata, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeLandedStateCall + /// Asynchronous. Server-streaming. /// Send the initial message. /// Use methods on the returned object to get streamed responses. @@ -298,6 +383,11 @@ internal protocol Mavsdk_Rpc_Telemetry_TelemetryServiceService: ServiceClient { /// Use methods on the returned object to get streamed responses. func subscribeAttitudeEuler(_ request: Mavsdk_Rpc_Telemetry_SubscribeAttitudeEulerRequest, metadata customMetadata: Metadata, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeEulerCall + /// Asynchronous. Server-streaming. + /// Send the initial message. + /// Use methods on the returned object to get streamed responses. + func subscribeAttitudeAngularVelocityBody(_ request: Mavsdk_Rpc_Telemetry_SubscribeAttitudeAngularVelocityBodyRequest, metadata customMetadata: Metadata, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeAngularVelocityBodyCall + /// Asynchronous. Server-streaming. /// Send the initial message. /// Use methods on the returned object to get streamed responses. @@ -343,6 +433,21 @@ internal protocol Mavsdk_Rpc_Telemetry_TelemetryServiceService: ServiceClient { /// Use methods on the returned object to get streamed responses. func subscribeStatusText(_ request: Mavsdk_Rpc_Telemetry_SubscribeStatusTextRequest, metadata customMetadata: Metadata, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeStatusTextCall + /// Asynchronous. Server-streaming. + /// Send the initial message. + /// Use methods on the returned object to get streamed responses. + func subscribeActuatorControlTarget(_ request: Mavsdk_Rpc_Telemetry_SubscribeActuatorControlTargetRequest, metadata customMetadata: Metadata, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorControlTargetCall + + /// Asynchronous. Server-streaming. + /// Send the initial message. + /// Use methods on the returned object to get streamed responses. + func subscribeActuatorOutputStatus(_ request: Mavsdk_Rpc_Telemetry_SubscribeActuatorOutputStatusRequest, metadata customMetadata: Metadata, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorOutputStatusCall + + /// Asynchronous. Server-streaming. + /// Send the initial message. + /// Use methods on the returned object to get streamed responses. + func subscribeOdometry(_ request: Mavsdk_Rpc_Telemetry_SubscribeOdometryRequest, metadata customMetadata: Metadata, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeOdometryCall + } internal extension Mavsdk_Rpc_Telemetry_TelemetryServiceService { @@ -361,6 +466,11 @@ internal extension Mavsdk_Rpc_Telemetry_TelemetryServiceService { return try self.subscribeInAir(request, metadata: self.metadata, completion: completion) } + /// Asynchronous. Server-streaming. + func subscribeLandedState(_ request: Mavsdk_Rpc_Telemetry_SubscribeLandedStateRequest, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeLandedStateCall { + return try self.subscribeLandedState(request, metadata: self.metadata, completion: completion) + } + /// Asynchronous. Server-streaming. func subscribeArmed(_ request: Mavsdk_Rpc_Telemetry_SubscribeArmedRequest, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeArmedCall { return try self.subscribeArmed(request, metadata: self.metadata, completion: completion) @@ -376,6 +486,11 @@ internal extension Mavsdk_Rpc_Telemetry_TelemetryServiceService { return try self.subscribeAttitudeEuler(request, metadata: self.metadata, completion: completion) } + /// Asynchronous. Server-streaming. + func subscribeAttitudeAngularVelocityBody(_ request: Mavsdk_Rpc_Telemetry_SubscribeAttitudeAngularVelocityBodyRequest, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeAngularVelocityBodyCall { + return try self.subscribeAttitudeAngularVelocityBody(request, metadata: self.metadata, completion: completion) + } + /// Asynchronous. Server-streaming. func subscribeCameraAttitudeQuaternion(_ request: Mavsdk_Rpc_Telemetry_SubscribeCameraAttitudeQuaternionRequest, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeCameraAttitudeQuaternionCall { return try self.subscribeCameraAttitudeQuaternion(request, metadata: self.metadata, completion: completion) @@ -421,6 +536,21 @@ internal extension Mavsdk_Rpc_Telemetry_TelemetryServiceService { return try self.subscribeStatusText(request, metadata: self.metadata, completion: completion) } + /// Asynchronous. Server-streaming. + func subscribeActuatorControlTarget(_ request: Mavsdk_Rpc_Telemetry_SubscribeActuatorControlTargetRequest, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorControlTargetCall { + return try self.subscribeActuatorControlTarget(request, metadata: self.metadata, completion: completion) + } + + /// Asynchronous. Server-streaming. + func subscribeActuatorOutputStatus(_ request: Mavsdk_Rpc_Telemetry_SubscribeActuatorOutputStatusRequest, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorOutputStatusCall { + return try self.subscribeActuatorOutputStatus(request, metadata: self.metadata, completion: completion) + } + + /// Asynchronous. Server-streaming. + func subscribeOdometry(_ request: Mavsdk_Rpc_Telemetry_SubscribeOdometryRequest, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeOdometryCall { + return try self.subscribeOdometry(request, metadata: self.metadata, completion: completion) + } + } internal final class Mavsdk_Rpc_Telemetry_TelemetryServiceServiceClient: ServiceClientBase, Mavsdk_Rpc_Telemetry_TelemetryServiceService { @@ -448,6 +578,14 @@ internal final class Mavsdk_Rpc_Telemetry_TelemetryServiceServiceClient: Service .start(request: request, metadata: customMetadata, completion: completion) } + /// Asynchronous. Server-streaming. + /// Send the initial message. + /// Use methods on the returned object to get streamed responses. + internal func subscribeLandedState(_ request: Mavsdk_Rpc_Telemetry_SubscribeLandedStateRequest, metadata customMetadata: Metadata, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeLandedStateCall { + return try Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeLandedStateCallBase(channel) + .start(request: request, metadata: customMetadata, completion: completion) + } + /// Asynchronous. Server-streaming. /// Send the initial message. /// Use methods on the returned object to get streamed responses. @@ -472,6 +610,14 @@ internal final class Mavsdk_Rpc_Telemetry_TelemetryServiceServiceClient: Service .start(request: request, metadata: customMetadata, completion: completion) } + /// Asynchronous. Server-streaming. + /// Send the initial message. + /// Use methods on the returned object to get streamed responses. + internal func subscribeAttitudeAngularVelocityBody(_ request: Mavsdk_Rpc_Telemetry_SubscribeAttitudeAngularVelocityBodyRequest, metadata customMetadata: Metadata, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeAngularVelocityBodyCall { + return try Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeAngularVelocityBodyCallBase(channel) + .start(request: request, metadata: customMetadata, completion: completion) + } + /// Asynchronous. Server-streaming. /// Send the initial message. /// Use methods on the returned object to get streamed responses. @@ -544,6 +690,30 @@ internal final class Mavsdk_Rpc_Telemetry_TelemetryServiceServiceClient: Service .start(request: request, metadata: customMetadata, completion: completion) } + /// Asynchronous. Server-streaming. + /// Send the initial message. + /// Use methods on the returned object to get streamed responses. + internal func subscribeActuatorControlTarget(_ request: Mavsdk_Rpc_Telemetry_SubscribeActuatorControlTargetRequest, metadata customMetadata: Metadata, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorControlTargetCall { + return try Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorControlTargetCallBase(channel) + .start(request: request, metadata: customMetadata, completion: completion) + } + + /// Asynchronous. Server-streaming. + /// Send the initial message. + /// Use methods on the returned object to get streamed responses. + internal func subscribeActuatorOutputStatus(_ request: Mavsdk_Rpc_Telemetry_SubscribeActuatorOutputStatusRequest, metadata customMetadata: Metadata, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorOutputStatusCall { + return try Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorOutputStatusCallBase(channel) + .start(request: request, metadata: customMetadata, completion: completion) + } + + /// Asynchronous. Server-streaming. + /// Send the initial message. + /// Use methods on the returned object to get streamed responses. + internal func subscribeOdometry(_ request: Mavsdk_Rpc_Telemetry_SubscribeOdometryRequest, metadata customMetadata: Metadata, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeOdometryCall { + return try Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeOdometryCallBase(channel) + .start(request: request, metadata: customMetadata, completion: completion) + } + } class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribePositionCallTestStub: ClientCallServerStreamingTestStub, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribePositionCall { @@ -558,6 +728,10 @@ class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeInAirCallTestStub: ClientCal override class var method: String { return "/mavsdk.rpc.telemetry.TelemetryService/SubscribeInAir" } } +class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeLandedStateCallTestStub: ClientCallServerStreamingTestStub, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeLandedStateCall { + override class var method: String { return "/mavsdk.rpc.telemetry.TelemetryService/SubscribeLandedState" } +} + class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeArmedCallTestStub: ClientCallServerStreamingTestStub, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeArmedCall { override class var method: String { return "/mavsdk.rpc.telemetry.TelemetryService/SubscribeArmed" } } @@ -570,6 +744,10 @@ class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeEulerCallTestStub: C override class var method: String { return "/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeEuler" } } +class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeAngularVelocityBodyCallTestStub: ClientCallServerStreamingTestStub, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeAngularVelocityBodyCall { + override class var method: String { return "/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeAngularVelocityBody" } +} + class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeCameraAttitudeQuaternionCallTestStub: ClientCallServerStreamingTestStub, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeCameraAttitudeQuaternionCall { override class var method: String { return "/mavsdk.rpc.telemetry.TelemetryService/SubscribeCameraAttitudeQuaternion" } } @@ -606,6 +784,18 @@ class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeStatusTextCallTestStub: Clie override class var method: String { return "/mavsdk.rpc.telemetry.TelemetryService/SubscribeStatusText" } } +class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorControlTargetCallTestStub: ClientCallServerStreamingTestStub, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorControlTargetCall { + override class var method: String { return "/mavsdk.rpc.telemetry.TelemetryService/SubscribeActuatorControlTarget" } +} + +class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorOutputStatusCallTestStub: ClientCallServerStreamingTestStub, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorOutputStatusCall { + override class var method: String { return "/mavsdk.rpc.telemetry.TelemetryService/SubscribeActuatorOutputStatus" } +} + +class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeOdometryCallTestStub: ClientCallServerStreamingTestStub, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeOdometryCall { + override class var method: String { return "/mavsdk.rpc.telemetry.TelemetryService/SubscribeOdometry" } +} + class Mavsdk_Rpc_Telemetry_TelemetryServiceServiceTestStub: ServiceClientTestStubBase, Mavsdk_Rpc_Telemetry_TelemetryServiceService { var subscribePositionRequests: [Mavsdk_Rpc_Telemetry_SubscribePositionRequest] = [] var subscribePositionCalls: [Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribePositionCall] = [] @@ -631,6 +821,14 @@ class Mavsdk_Rpc_Telemetry_TelemetryServiceServiceTestStub: ServiceClientTestStu return subscribeInAirCalls.first! } + var subscribeLandedStateRequests: [Mavsdk_Rpc_Telemetry_SubscribeLandedStateRequest] = [] + var subscribeLandedStateCalls: [Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeLandedStateCall] = [] + func subscribeLandedState(_ request: Mavsdk_Rpc_Telemetry_SubscribeLandedStateRequest, metadata customMetadata: Metadata, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeLandedStateCall { + subscribeLandedStateRequests.append(request) + defer { subscribeLandedStateCalls.removeFirst() } + return subscribeLandedStateCalls.first! + } + var subscribeArmedRequests: [Mavsdk_Rpc_Telemetry_SubscribeArmedRequest] = [] var subscribeArmedCalls: [Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeArmedCall] = [] func subscribeArmed(_ request: Mavsdk_Rpc_Telemetry_SubscribeArmedRequest, metadata customMetadata: Metadata, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeArmedCall { @@ -655,6 +853,14 @@ class Mavsdk_Rpc_Telemetry_TelemetryServiceServiceTestStub: ServiceClientTestStu return subscribeAttitudeEulerCalls.first! } + var subscribeAttitudeAngularVelocityBodyRequests: [Mavsdk_Rpc_Telemetry_SubscribeAttitudeAngularVelocityBodyRequest] = [] + var subscribeAttitudeAngularVelocityBodyCalls: [Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeAngularVelocityBodyCall] = [] + func subscribeAttitudeAngularVelocityBody(_ request: Mavsdk_Rpc_Telemetry_SubscribeAttitudeAngularVelocityBodyRequest, metadata customMetadata: Metadata, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeAngularVelocityBodyCall { + subscribeAttitudeAngularVelocityBodyRequests.append(request) + defer { subscribeAttitudeAngularVelocityBodyCalls.removeFirst() } + return subscribeAttitudeAngularVelocityBodyCalls.first! + } + var subscribeCameraAttitudeQuaternionRequests: [Mavsdk_Rpc_Telemetry_SubscribeCameraAttitudeQuaternionRequest] = [] var subscribeCameraAttitudeQuaternionCalls: [Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeCameraAttitudeQuaternionCall] = [] func subscribeCameraAttitudeQuaternion(_ request: Mavsdk_Rpc_Telemetry_SubscribeCameraAttitudeQuaternionRequest, metadata customMetadata: Metadata, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeCameraAttitudeQuaternionCall { @@ -727,6 +933,30 @@ class Mavsdk_Rpc_Telemetry_TelemetryServiceServiceTestStub: ServiceClientTestStu return subscribeStatusTextCalls.first! } + var subscribeActuatorControlTargetRequests: [Mavsdk_Rpc_Telemetry_SubscribeActuatorControlTargetRequest] = [] + var subscribeActuatorControlTargetCalls: [Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorControlTargetCall] = [] + func subscribeActuatorControlTarget(_ request: Mavsdk_Rpc_Telemetry_SubscribeActuatorControlTargetRequest, metadata customMetadata: Metadata, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorControlTargetCall { + subscribeActuatorControlTargetRequests.append(request) + defer { subscribeActuatorControlTargetCalls.removeFirst() } + return subscribeActuatorControlTargetCalls.first! + } + + var subscribeActuatorOutputStatusRequests: [Mavsdk_Rpc_Telemetry_SubscribeActuatorOutputStatusRequest] = [] + var subscribeActuatorOutputStatusCalls: [Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorOutputStatusCall] = [] + func subscribeActuatorOutputStatus(_ request: Mavsdk_Rpc_Telemetry_SubscribeActuatorOutputStatusRequest, metadata customMetadata: Metadata, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorOutputStatusCall { + subscribeActuatorOutputStatusRequests.append(request) + defer { subscribeActuatorOutputStatusCalls.removeFirst() } + return subscribeActuatorOutputStatusCalls.first! + } + + var subscribeOdometryRequests: [Mavsdk_Rpc_Telemetry_SubscribeOdometryRequest] = [] + var subscribeOdometryCalls: [Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeOdometryCall] = [] + func subscribeOdometry(_ request: Mavsdk_Rpc_Telemetry_SubscribeOdometryRequest, metadata customMetadata: Metadata, completion: ((CallResult) -> Void)?) throws -> Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeOdometryCall { + subscribeOdometryRequests.append(request) + defer { subscribeOdometryCalls.removeFirst() } + return subscribeOdometryCalls.first! + } + } /// To build a server, implement a class that conforms to this protocol. @@ -736,9 +966,11 @@ internal protocol Mavsdk_Rpc_Telemetry_TelemetryServiceProvider: ServiceProvider func subscribePosition(request: Mavsdk_Rpc_Telemetry_SubscribePositionRequest, session: Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribePositionSession) throws -> ServerStatus? func subscribeHome(request: Mavsdk_Rpc_Telemetry_SubscribeHomeRequest, session: Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeHomeSession) throws -> ServerStatus? func subscribeInAir(request: Mavsdk_Rpc_Telemetry_SubscribeInAirRequest, session: Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeInAirSession) throws -> ServerStatus? + func subscribeLandedState(request: Mavsdk_Rpc_Telemetry_SubscribeLandedStateRequest, session: Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeLandedStateSession) throws -> ServerStatus? func subscribeArmed(request: Mavsdk_Rpc_Telemetry_SubscribeArmedRequest, session: Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeArmedSession) throws -> ServerStatus? func subscribeAttitudeQuaternion(request: Mavsdk_Rpc_Telemetry_SubscribeAttitudeQuaternionRequest, session: Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeQuaternionSession) throws -> ServerStatus? func subscribeAttitudeEuler(request: Mavsdk_Rpc_Telemetry_SubscribeAttitudeEulerRequest, session: Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeEulerSession) throws -> ServerStatus? + func subscribeAttitudeAngularVelocityBody(request: Mavsdk_Rpc_Telemetry_SubscribeAttitudeAngularVelocityBodyRequest, session: Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeAngularVelocityBodySession) throws -> ServerStatus? func subscribeCameraAttitudeQuaternion(request: Mavsdk_Rpc_Telemetry_SubscribeCameraAttitudeQuaternionRequest, session: Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeCameraAttitudeQuaternionSession) throws -> ServerStatus? func subscribeCameraAttitudeEuler(request: Mavsdk_Rpc_Telemetry_SubscribeCameraAttitudeEulerRequest, session: Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeCameraAttitudeEulerSession) throws -> ServerStatus? func subscribeGroundSpeedNed(request: Mavsdk_Rpc_Telemetry_SubscribeGroundSpeedNedRequest, session: Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeGroundSpeedNedSession) throws -> ServerStatus? @@ -748,6 +980,9 @@ internal protocol Mavsdk_Rpc_Telemetry_TelemetryServiceProvider: ServiceProvider func subscribeHealth(request: Mavsdk_Rpc_Telemetry_SubscribeHealthRequest, session: Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeHealthSession) throws -> ServerStatus? func subscribeRcStatus(request: Mavsdk_Rpc_Telemetry_SubscribeRcStatusRequest, session: Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeRcStatusSession) throws -> ServerStatus? func subscribeStatusText(request: Mavsdk_Rpc_Telemetry_SubscribeStatusTextRequest, session: Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeStatusTextSession) throws -> ServerStatus? + func subscribeActuatorControlTarget(request: Mavsdk_Rpc_Telemetry_SubscribeActuatorControlTargetRequest, session: Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorControlTargetSession) throws -> ServerStatus? + func subscribeActuatorOutputStatus(request: Mavsdk_Rpc_Telemetry_SubscribeActuatorOutputStatusRequest, session: Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorOutputStatusSession) throws -> ServerStatus? + func subscribeOdometry(request: Mavsdk_Rpc_Telemetry_SubscribeOdometryRequest, session: Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeOdometrySession) throws -> ServerStatus? } extension Mavsdk_Rpc_Telemetry_TelemetryServiceProvider { @@ -772,6 +1007,11 @@ extension Mavsdk_Rpc_Telemetry_TelemetryServiceProvider { handler: handler, providerBlock: { try self.subscribeInAir(request: $0, session: $1 as! Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeInAirSessionBase) }) .run() + case "/mavsdk.rpc.telemetry.TelemetryService/SubscribeLandedState": + return try Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeLandedStateSessionBase( + handler: handler, + providerBlock: { try self.subscribeLandedState(request: $0, session: $1 as! Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeLandedStateSessionBase) }) + .run() case "/mavsdk.rpc.telemetry.TelemetryService/SubscribeArmed": return try Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeArmedSessionBase( handler: handler, @@ -787,6 +1027,11 @@ extension Mavsdk_Rpc_Telemetry_TelemetryServiceProvider { handler: handler, providerBlock: { try self.subscribeAttitudeEuler(request: $0, session: $1 as! Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeEulerSessionBase) }) .run() + case "/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeAngularVelocityBody": + return try Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeAngularVelocityBodySessionBase( + handler: handler, + providerBlock: { try self.subscribeAttitudeAngularVelocityBody(request: $0, session: $1 as! Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeAngularVelocityBodySessionBase) }) + .run() case "/mavsdk.rpc.telemetry.TelemetryService/SubscribeCameraAttitudeQuaternion": return try Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeCameraAttitudeQuaternionSessionBase( handler: handler, @@ -832,6 +1077,21 @@ extension Mavsdk_Rpc_Telemetry_TelemetryServiceProvider { handler: handler, providerBlock: { try self.subscribeStatusText(request: $0, session: $1 as! Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeStatusTextSessionBase) }) .run() + case "/mavsdk.rpc.telemetry.TelemetryService/SubscribeActuatorControlTarget": + return try Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorControlTargetSessionBase( + handler: handler, + providerBlock: { try self.subscribeActuatorControlTarget(request: $0, session: $1 as! Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorControlTargetSessionBase) }) + .run() + case "/mavsdk.rpc.telemetry.TelemetryService/SubscribeActuatorOutputStatus": + return try Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorOutputStatusSessionBase( + handler: handler, + providerBlock: { try self.subscribeActuatorOutputStatus(request: $0, session: $1 as! Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorOutputStatusSessionBase) }) + .run() + case "/mavsdk.rpc.telemetry.TelemetryService/SubscribeOdometry": + return try Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeOdometrySessionBase( + handler: handler, + providerBlock: { try self.subscribeOdometry(request: $0, session: $1 as! Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeOdometrySessionBase) }) + .run() default: throw HandleMethodError.unknownMethod } @@ -901,6 +1161,27 @@ fileprivate final class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeInAirSessi class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeInAirSessionTestStub: ServerSessionServerStreamingTestStub, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeInAirSession {} +internal protocol Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeLandedStateSession: ServerSessionServerStreaming { + /// Send a message to the stream. Nonblocking. + func send(_ message: Mavsdk_Rpc_Telemetry_LandedStateResponse, completion: @escaping (Error?) -> Void) throws + /// Do not call this directly, call `send()` in the protocol extension below instead. + func _send(_ message: Mavsdk_Rpc_Telemetry_LandedStateResponse, timeout: DispatchTime) throws + + /// Close the connection and send the status. Non-blocking. + /// This method should be called if and only if your request handler returns a nil value instead of a server status; + /// otherwise SwiftGRPC will take care of sending the status for you. + func close(withStatus status: ServerStatus, completion: (() -> Void)?) throws +} + +internal extension Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeLandedStateSession { + /// Send a message to the stream and wait for the send operation to finish. Blocking. + func send(_ message: Mavsdk_Rpc_Telemetry_LandedStateResponse, timeout: DispatchTime = .distantFuture) throws { try self._send(message, timeout: timeout) } +} + +fileprivate final class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeLandedStateSessionBase: ServerSessionServerStreamingBase, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeLandedStateSession {} + +class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeLandedStateSessionTestStub: ServerSessionServerStreamingTestStub, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeLandedStateSession {} + internal protocol Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeArmedSession: ServerSessionServerStreaming { /// Send a message to the stream. Nonblocking. func send(_ message: Mavsdk_Rpc_Telemetry_ArmedResponse, completion: @escaping (Error?) -> Void) throws @@ -964,6 +1245,27 @@ fileprivate final class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeEu class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeEulerSessionTestStub: ServerSessionServerStreamingTestStub, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeEulerSession {} +internal protocol Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeAngularVelocityBodySession: ServerSessionServerStreaming { + /// Send a message to the stream. Nonblocking. + func send(_ message: Mavsdk_Rpc_Telemetry_AttitudeAngularVelocityBodyResponse, completion: @escaping (Error?) -> Void) throws + /// Do not call this directly, call `send()` in the protocol extension below instead. + func _send(_ message: Mavsdk_Rpc_Telemetry_AttitudeAngularVelocityBodyResponse, timeout: DispatchTime) throws + + /// Close the connection and send the status. Non-blocking. + /// This method should be called if and only if your request handler returns a nil value instead of a server status; + /// otherwise SwiftGRPC will take care of sending the status for you. + func close(withStatus status: ServerStatus, completion: (() -> Void)?) throws +} + +internal extension Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeAngularVelocityBodySession { + /// Send a message to the stream and wait for the send operation to finish. Blocking. + func send(_ message: Mavsdk_Rpc_Telemetry_AttitudeAngularVelocityBodyResponse, timeout: DispatchTime = .distantFuture) throws { try self._send(message, timeout: timeout) } +} + +fileprivate final class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeAngularVelocityBodySessionBase: ServerSessionServerStreamingBase, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeAngularVelocityBodySession {} + +class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeAngularVelocityBodySessionTestStub: ServerSessionServerStreamingTestStub, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeAttitudeAngularVelocityBodySession {} + internal protocol Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeCameraAttitudeQuaternionSession: ServerSessionServerStreaming { /// Send a message to the stream. Nonblocking. func send(_ message: Mavsdk_Rpc_Telemetry_CameraAttitudeQuaternionResponse, completion: @escaping (Error?) -> Void) throws @@ -1153,3 +1455,66 @@ fileprivate final class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeStatusText class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeStatusTextSessionTestStub: ServerSessionServerStreamingTestStub, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeStatusTextSession {} +internal protocol Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorControlTargetSession: ServerSessionServerStreaming { + /// Send a message to the stream. Nonblocking. + func send(_ message: Mavsdk_Rpc_Telemetry_ActuatorControlTargetResponse, completion: @escaping (Error?) -> Void) throws + /// Do not call this directly, call `send()` in the protocol extension below instead. + func _send(_ message: Mavsdk_Rpc_Telemetry_ActuatorControlTargetResponse, timeout: DispatchTime) throws + + /// Close the connection and send the status. Non-blocking. + /// This method should be called if and only if your request handler returns a nil value instead of a server status; + /// otherwise SwiftGRPC will take care of sending the status for you. + func close(withStatus status: ServerStatus, completion: (() -> Void)?) throws +} + +internal extension Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorControlTargetSession { + /// Send a message to the stream and wait for the send operation to finish. Blocking. + func send(_ message: Mavsdk_Rpc_Telemetry_ActuatorControlTargetResponse, timeout: DispatchTime = .distantFuture) throws { try self._send(message, timeout: timeout) } +} + +fileprivate final class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorControlTargetSessionBase: ServerSessionServerStreamingBase, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorControlTargetSession {} + +class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorControlTargetSessionTestStub: ServerSessionServerStreamingTestStub, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorControlTargetSession {} + +internal protocol Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorOutputStatusSession: ServerSessionServerStreaming { + /// Send a message to the stream. Nonblocking. + func send(_ message: Mavsdk_Rpc_Telemetry_ActuatorOutputStatusResponse, completion: @escaping (Error?) -> Void) throws + /// Do not call this directly, call `send()` in the protocol extension below instead. + func _send(_ message: Mavsdk_Rpc_Telemetry_ActuatorOutputStatusResponse, timeout: DispatchTime) throws + + /// Close the connection and send the status. Non-blocking. + /// This method should be called if and only if your request handler returns a nil value instead of a server status; + /// otherwise SwiftGRPC will take care of sending the status for you. + func close(withStatus status: ServerStatus, completion: (() -> Void)?) throws +} + +internal extension Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorOutputStatusSession { + /// Send a message to the stream and wait for the send operation to finish. Blocking. + func send(_ message: Mavsdk_Rpc_Telemetry_ActuatorOutputStatusResponse, timeout: DispatchTime = .distantFuture) throws { try self._send(message, timeout: timeout) } +} + +fileprivate final class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorOutputStatusSessionBase: ServerSessionServerStreamingBase, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorOutputStatusSession {} + +class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorOutputStatusSessionTestStub: ServerSessionServerStreamingTestStub, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeActuatorOutputStatusSession {} + +internal protocol Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeOdometrySession: ServerSessionServerStreaming { + /// Send a message to the stream. Nonblocking. + func send(_ message: Mavsdk_Rpc_Telemetry_OdometryResponse, completion: @escaping (Error?) -> Void) throws + /// Do not call this directly, call `send()` in the protocol extension below instead. + func _send(_ message: Mavsdk_Rpc_Telemetry_OdometryResponse, timeout: DispatchTime) throws + + /// Close the connection and send the status. Non-blocking. + /// This method should be called if and only if your request handler returns a nil value instead of a server status; + /// otherwise SwiftGRPC will take care of sending the status for you. + func close(withStatus status: ServerStatus, completion: (() -> Void)?) throws +} + +internal extension Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeOdometrySession { + /// Send a message to the stream and wait for the send operation to finish. Blocking. + func send(_ message: Mavsdk_Rpc_Telemetry_OdometryResponse, timeout: DispatchTime = .distantFuture) throws { try self._send(message, timeout: timeout) } +} + +fileprivate final class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeOdometrySessionBase: ServerSessionServerStreamingBase, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeOdometrySession {} + +class Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeOdometrySessionTestStub: ServerSessionServerStreamingTestStub, Mavsdk_Rpc_Telemetry_TelemetryServiceSubscribeOdometrySession {} + diff --git a/Sources/MAVSDK-Swift/Generated/telemetry.pb.swift b/Sources/MAVSDK-Swift/Generated/telemetry.pb.swift index bad769f..1ed7be8 100644 --- a/Sources/MAVSDK-Swift/Generated/telemetry.pb.swift +++ b/Sources/MAVSDK-Swift/Generated/telemetry.pb.swift @@ -19,14 +19,29 @@ fileprivate struct _GeneratedWithProtocGenSwiftVersion: SwiftProtobuf.ProtobufAP typealias Version = _2 } +/// Fix type. enum Mavsdk_Rpc_Telemetry_FixType: SwiftProtobuf.Enum { typealias RawValue = Int + + /// No GPS connected case noGps // = 0 + + /// No position information, GPS is connected case noFix // = 1 + + /// 2D position case fix2D // = 2 + + /// 3D position case fix3D // = 3 + + /// DGPS/SBAS aided 3D position case fixDgps // = 4 + + /// RTK float, 3D position case rtkFloat // = 5 + + /// RTK Fixed, 3D position case rtkFixed // = 6 case UNRECOGNIZED(Int) @@ -79,16 +94,39 @@ extension Mavsdk_Rpc_Telemetry_FixType: CaseIterable { #endif // swift(>=4.2) +/// +/// Flight modes. +/// +/// For more information about flight modes, check out +/// https://docs.px4.io/en/config/flight_mode.html. enum Mavsdk_Rpc_Telemetry_FlightMode: SwiftProtobuf.Enum { typealias RawValue = Int + + /// Mode not known case unknown // = 0 + + /// Armed and ready to take off case ready // = 1 + + /// Taking off case takeoff // = 2 + + /// Holding (hovering in place (or circling for fixed-wing vehicles) case hold // = 3 + + /// In mission case mission // = 4 + + /// Returning to launch position (then landing) case returnToLaunch // = 5 + + /// Landing case land // = 6 + + /// In 'offboard' mode case offboard // = 7 + + /// In 'follow-me' mode case followMe // = 8 case UNRECOGNIZED(Int) @@ -147,6 +185,59 @@ extension Mavsdk_Rpc_Telemetry_FlightMode: CaseIterable { #endif // swift(>=4.2) +/// Landed State enumeration +enum Mavsdk_Rpc_Telemetry_LandedState: SwiftProtobuf.Enum { + typealias RawValue = Int + case unknown // = 0 + case onGround // = 1 + case inAir // = 2 + case takingOff // = 3 + case landing // = 4 + case UNRECOGNIZED(Int) + + init() { + self = .unknown + } + + init?(rawValue: Int) { + switch rawValue { + case 0: self = .unknown + case 1: self = .onGround + case 2: self = .inAir + case 3: self = .takingOff + case 4: self = .landing + default: self = .UNRECOGNIZED(rawValue) + } + } + + var rawValue: Int { + switch self { + case .unknown: return 0 + case .onGround: return 1 + case .inAir: return 2 + case .takingOff: return 3 + case .landing: return 4 + case .UNRECOGNIZED(let i): return i + } + } + +} + +#if swift(>=4.2) + +extension Mavsdk_Rpc_Telemetry_LandedState: CaseIterable { + // The compiler won't synthesize support with the UNRECOGNIZED case. + static var allCases: [Mavsdk_Rpc_Telemetry_LandedState] = [ + .unknown, + .onGround, + .inAir, + .takingOff, + .landing, + ] +} + +#endif // swift(>=4.2) + struct Mavsdk_Rpc_Telemetry_SubscribePositionRequest { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for @@ -162,6 +253,7 @@ struct Mavsdk_Rpc_Telemetry_PositionResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// The next position var position: Mavsdk_Rpc_Telemetry_Position { get {return _storage._position ?? Mavsdk_Rpc_Telemetry_Position()} set {_uniqueStorage()._position = newValue} @@ -193,6 +285,7 @@ struct Mavsdk_Rpc_Telemetry_HomeResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// The next home position var home: Mavsdk_Rpc_Telemetry_Position { get {return _storage._home ?? Mavsdk_Rpc_Telemetry_Position()} set {_uniqueStorage()._home = newValue} @@ -224,6 +317,7 @@ struct Mavsdk_Rpc_Telemetry_InAirResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// The next 'in-air' state var isInAir: Bool = false var unknownFields = SwiftProtobuf.UnknownStorage() @@ -231,6 +325,28 @@ struct Mavsdk_Rpc_Telemetry_InAirResponse { init() {} } +struct Mavsdk_Rpc_Telemetry_SubscribeLandedStateRequest { + // SwiftProtobuf.Message conformance is added in an extension below. See the + // `Message` and `Message+*Additions` files in the SwiftProtobuf library for + // methods supported on all messages. + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} +} + +struct Mavsdk_Rpc_Telemetry_LandedStateResponse { + // SwiftProtobuf.Message conformance is added in an extension below. See the + // `Message` and `Message+*Additions` files in the SwiftProtobuf library for + // methods supported on all messages. + + var landedState: Mavsdk_Rpc_Telemetry_LandedState = .unknown + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} +} + struct Mavsdk_Rpc_Telemetry_SubscribeArmedRequest { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for @@ -246,6 +362,7 @@ struct Mavsdk_Rpc_Telemetry_ArmedResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// The next 'armed' state var isArmed: Bool = false var unknownFields = SwiftProtobuf.UnknownStorage() @@ -268,6 +385,7 @@ struct Mavsdk_Rpc_Telemetry_AttitudeQuaternionResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// The next attitude (quaternion) var attitudeQuaternion: Mavsdk_Rpc_Telemetry_Quaternion { get {return _storage._attitudeQuaternion ?? Mavsdk_Rpc_Telemetry_Quaternion()} set {_uniqueStorage()._attitudeQuaternion = newValue} @@ -299,6 +417,7 @@ struct Mavsdk_Rpc_Telemetry_AttitudeEulerResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// The next attitude (euler) var attitudeEuler: Mavsdk_Rpc_Telemetry_EulerAngle { get {return _storage._attitudeEuler ?? Mavsdk_Rpc_Telemetry_EulerAngle()} set {_uniqueStorage()._attitudeEuler = newValue} @@ -315,6 +434,38 @@ struct Mavsdk_Rpc_Telemetry_AttitudeEulerResponse { fileprivate var _storage = _StorageClass.defaultInstance } +struct Mavsdk_Rpc_Telemetry_SubscribeAttitudeAngularVelocityBodyRequest { + // SwiftProtobuf.Message conformance is added in an extension below. See the + // `Message` and `Message+*Additions` files in the SwiftProtobuf library for + // methods supported on all messages. + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} +} + +struct Mavsdk_Rpc_Telemetry_AttitudeAngularVelocityBodyResponse { + // SwiftProtobuf.Message conformance is added in an extension below. See the + // `Message` and `Message+*Additions` files in the SwiftProtobuf library for + // methods supported on all messages. + + /// The next angular velocity (rad/s) + var attitudeAngularVelocityBody: Mavsdk_Rpc_Telemetry_AngularVelocityBody { + get {return _storage._attitudeAngularVelocityBody ?? Mavsdk_Rpc_Telemetry_AngularVelocityBody()} + set {_uniqueStorage()._attitudeAngularVelocityBody = newValue} + } + /// Returns true if `attitudeAngularVelocityBody` has been explicitly set. + var hasAttitudeAngularVelocityBody: Bool {return _storage._attitudeAngularVelocityBody != nil} + /// Clears the value of `attitudeAngularVelocityBody`. Subsequent reads from it will return its default value. + mutating func clearAttitudeAngularVelocityBody() {_uniqueStorage()._attitudeAngularVelocityBody = nil} + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} + + fileprivate var _storage = _StorageClass.defaultInstance +} + struct Mavsdk_Rpc_Telemetry_SubscribeCameraAttitudeQuaternionRequest { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for @@ -330,6 +481,7 @@ struct Mavsdk_Rpc_Telemetry_CameraAttitudeQuaternionResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// The next camera attitude (quaternion) var attitudeQuaternion: Mavsdk_Rpc_Telemetry_Quaternion { get {return _storage._attitudeQuaternion ?? Mavsdk_Rpc_Telemetry_Quaternion()} set {_uniqueStorage()._attitudeQuaternion = newValue} @@ -361,6 +513,7 @@ struct Mavsdk_Rpc_Telemetry_CameraAttitudeEulerResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// The next camera attitude (euler) var attitudeEuler: Mavsdk_Rpc_Telemetry_EulerAngle { get {return _storage._attitudeEuler ?? Mavsdk_Rpc_Telemetry_EulerAngle()} set {_uniqueStorage()._attitudeEuler = newValue} @@ -392,6 +545,7 @@ struct Mavsdk_Rpc_Telemetry_GroundSpeedNedResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// The next ground speed (NED) var groundSpeedNed: Mavsdk_Rpc_Telemetry_SpeedNed { get {return _storage._groundSpeedNed ?? Mavsdk_Rpc_Telemetry_SpeedNed()} set {_uniqueStorage()._groundSpeedNed = newValue} @@ -423,6 +577,7 @@ struct Mavsdk_Rpc_Telemetry_GpsInfoResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// The next 'GPS info' state var gpsInfo: Mavsdk_Rpc_Telemetry_GpsInfo { get {return _storage._gpsInfo ?? Mavsdk_Rpc_Telemetry_GpsInfo()} set {_uniqueStorage()._gpsInfo = newValue} @@ -454,6 +609,7 @@ struct Mavsdk_Rpc_Telemetry_BatteryResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// The next 'battery' state var battery: Mavsdk_Rpc_Telemetry_Battery { get {return _storage._battery ?? Mavsdk_Rpc_Telemetry_Battery()} set {_uniqueStorage()._battery = newValue} @@ -485,6 +641,7 @@ struct Mavsdk_Rpc_Telemetry_FlightModeResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// The next flight mode var flightMode: Mavsdk_Rpc_Telemetry_FlightMode = .unknown var unknownFields = SwiftProtobuf.UnknownStorage() @@ -507,6 +664,7 @@ struct Mavsdk_Rpc_Telemetry_HealthResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// The next 'health' state var health: Mavsdk_Rpc_Telemetry_Health { get {return _storage._health ?? Mavsdk_Rpc_Telemetry_Health()} set {_uniqueStorage()._health = newValue} @@ -538,6 +696,7 @@ struct Mavsdk_Rpc_Telemetry_RcStatusResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// The next RC status var rcStatus: Mavsdk_Rpc_Telemetry_RcStatus { get {return _storage._rcStatus ?? Mavsdk_Rpc_Telemetry_RcStatus()} set {_uniqueStorage()._rcStatus = newValue} @@ -569,6 +728,7 @@ struct Mavsdk_Rpc_Telemetry_StatusTextResponse { // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// The next 'status text' var statusText: Mavsdk_Rpc_Telemetry_StatusText { get {return _storage._statusText ?? Mavsdk_Rpc_Telemetry_StatusText()} set {_uniqueStorage()._statusText = newValue} @@ -585,17 +745,118 @@ struct Mavsdk_Rpc_Telemetry_StatusTextResponse { fileprivate var _storage = _StorageClass.defaultInstance } +struct Mavsdk_Rpc_Telemetry_SubscribeActuatorControlTargetRequest { + // SwiftProtobuf.Message conformance is added in an extension below. See the + // `Message` and `Message+*Additions` files in the SwiftProtobuf library for + // methods supported on all messages. + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} +} + +struct Mavsdk_Rpc_Telemetry_ActuatorControlTargetResponse { + // SwiftProtobuf.Message conformance is added in an extension below. See the + // `Message` and `Message+*Additions` files in the SwiftProtobuf library for + // methods supported on all messages. + + /// Actuator control target + var actuatorControlTarget: Mavsdk_Rpc_Telemetry_ActuatorControlTarget { + get {return _storage._actuatorControlTarget ?? Mavsdk_Rpc_Telemetry_ActuatorControlTarget()} + set {_uniqueStorage()._actuatorControlTarget = newValue} + } + /// Returns true if `actuatorControlTarget` has been explicitly set. + var hasActuatorControlTarget: Bool {return _storage._actuatorControlTarget != nil} + /// Clears the value of `actuatorControlTarget`. Subsequent reads from it will return its default value. + mutating func clearActuatorControlTarget() {_uniqueStorage()._actuatorControlTarget = nil} + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} + + fileprivate var _storage = _StorageClass.defaultInstance +} + +struct Mavsdk_Rpc_Telemetry_SubscribeActuatorOutputStatusRequest { + // SwiftProtobuf.Message conformance is added in an extension below. See the + // `Message` and `Message+*Additions` files in the SwiftProtobuf library for + // methods supported on all messages. + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} +} + +struct Mavsdk_Rpc_Telemetry_ActuatorOutputStatusResponse { + // SwiftProtobuf.Message conformance is added in an extension below. See the + // `Message` and `Message+*Additions` files in the SwiftProtobuf library for + // methods supported on all messages. + + /// Actuator output status + var actuatorOutputStatus: Mavsdk_Rpc_Telemetry_ActuatorOutputStatus { + get {return _storage._actuatorOutputStatus ?? Mavsdk_Rpc_Telemetry_ActuatorOutputStatus()} + set {_uniqueStorage()._actuatorOutputStatus = newValue} + } + /// Returns true if `actuatorOutputStatus` has been explicitly set. + var hasActuatorOutputStatus: Bool {return _storage._actuatorOutputStatus != nil} + /// Clears the value of `actuatorOutputStatus`. Subsequent reads from it will return its default value. + mutating func clearActuatorOutputStatus() {_uniqueStorage()._actuatorOutputStatus = nil} + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} + + fileprivate var _storage = _StorageClass.defaultInstance +} + +struct Mavsdk_Rpc_Telemetry_SubscribeOdometryRequest { + // SwiftProtobuf.Message conformance is added in an extension below. See the + // `Message` and `Message+*Additions` files in the SwiftProtobuf library for + // methods supported on all messages. + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} +} + +struct Mavsdk_Rpc_Telemetry_OdometryResponse { + // SwiftProtobuf.Message conformance is added in an extension below. See the + // `Message` and `Message+*Additions` files in the SwiftProtobuf library for + // methods supported on all messages. + + /// Odometry + var odometry: Mavsdk_Rpc_Telemetry_Odometry { + get {return _storage._odometry ?? Mavsdk_Rpc_Telemetry_Odometry()} + set {_uniqueStorage()._odometry = newValue} + } + /// Returns true if `odometry` has been explicitly set. + var hasOdometry: Bool {return _storage._odometry != nil} + /// Clears the value of `odometry`. Subsequent reads from it will return its default value. + mutating func clearOdometry() {_uniqueStorage()._odometry = nil} + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} + + fileprivate var _storage = _StorageClass.defaultInstance +} + +/// Position type in global coordinates. struct Mavsdk_Rpc_Telemetry_Position { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Latitude in degrees (range: -90 to +90) var latitudeDeg: Double = 0 + /// Longitude in degrees (range: -180 to +180) var longitudeDeg: Double = 0 + /// Altitude AMSL (above mean sea level) in metres var absoluteAltitudeM: Float = 0 + /// Altitude relative to takeoff altitude in metres var relativeAltitudeM: Float = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -603,17 +864,30 @@ struct Mavsdk_Rpc_Telemetry_Position { init() {} } +/// +/// Quaternion type. +/// +/// All rotations and axis systems follow the right-hand rule. +/// The Hamilton quaternion product definition is used. +/// A zero-rotation quaternion is represented by (1,0,0,0). +/// The quaternion could also be written as w + xi + yj + zk. +/// +/// For more info see: https://en.wikipedia.org/wiki/Quaternion struct Mavsdk_Rpc_Telemetry_Quaternion { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Quaternion entry 0, also denoted as a var w: Float = 0 + /// Quaternion entry 1, also denoted as b var x: Float = 0 + /// Quaternion entry 2, also denoted as c var y: Float = 0 + /// Quaternion entry 3, also denoted as d var z: Float = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -621,15 +895,25 @@ struct Mavsdk_Rpc_Telemetry_Quaternion { init() {} } +/// +/// Euler angle type. +/// +/// All rotations and axis systems follow the right-hand rule. +/// The Euler angles follow the convention of a 3-2-1 intrinsic Tait-Bryan rotation sequence. +/// +/// For more info see https://en.wikipedia.org/wiki/Euler_angles struct Mavsdk_Rpc_Telemetry_EulerAngle { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Roll angle in degrees, positive is banking to the right var rollDeg: Float = 0 + /// Pitch angle in degrees, positive is pitching nose up var pitchDeg: Float = 0 + /// Yaw angle in degrees, positive is clock-wise seen from above var yawDeg: Float = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -637,15 +921,39 @@ struct Mavsdk_Rpc_Telemetry_EulerAngle { init() {} } +/// Angular velocity type +struct Mavsdk_Rpc_Telemetry_AngularVelocityBody { + // SwiftProtobuf.Message conformance is added in an extension below. See the + // `Message` and `Message+*Additions` files in the SwiftProtobuf library for + // methods supported on all messages. + + /// Roll angular velocity + var rollRadS: Float = 0 + + /// Pitch angular velocity + var pitchRadS: Float = 0 + + /// Yaw angular velocity + var yawRadS: Float = 0 + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} +} + +/// Speed type, represented in the NED (North East Down) frame and in metres/second. struct Mavsdk_Rpc_Telemetry_SpeedNed { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Velocity in North direction in metres/second var velocityNorthMS: Float = 0 + /// Velocity in East direction in metres/second var velocityEastMS: Float = 0 + /// Velocity in Down direction in metres/second var velocityDownMS: Float = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -653,13 +961,16 @@ struct Mavsdk_Rpc_Telemetry_SpeedNed { init() {} } +/// GPS information type. struct Mavsdk_Rpc_Telemetry_GpsInfo { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Number of visible satellites in use var numSatellites: Int32 = 0 + /// Fix type var fixType: Mavsdk_Rpc_Telemetry_FixType = .noGps var unknownFields = SwiftProtobuf.UnknownStorage() @@ -667,13 +978,16 @@ struct Mavsdk_Rpc_Telemetry_GpsInfo { init() {} } +/// Battery type. struct Mavsdk_Rpc_Telemetry_Battery { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Voltage in volts var voltageV: Float = 0 + /// Estimated battery remaining (range: 0.0 to 1.0) var remainingPercent: Float = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -681,23 +995,31 @@ struct Mavsdk_Rpc_Telemetry_Battery { init() {} } +/// Health type. struct Mavsdk_Rpc_Telemetry_Health { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// True if the gyrometer is calibrated var isGyrometerCalibrationOk: Bool = false + /// True if the accelerometer is calibrated var isAccelerometerCalibrationOk: Bool = false + /// True if the magnetometer is calibrated var isMagnetometerCalibrationOk: Bool = false + /// True if the vehicle has a valid level calibration var isLevelCalibrationOk: Bool = false + /// True if the local position estimate is good enough to fly in 'position control' mode var isLocalPositionOk: Bool = false + /// True if the global position estimate is good enough to fly in 'position control' mode var isGlobalPositionOk: Bool = false + /// True if the home position has been initialized properly var isHomePositionOk: Bool = false var unknownFields = SwiftProtobuf.UnknownStorage() @@ -705,15 +1027,19 @@ struct Mavsdk_Rpc_Telemetry_Health { init() {} } +/// Remote control status type. struct Mavsdk_Rpc_Telemetry_RcStatus { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// True if an RC signal has been available once var wasAvailableOnce: Bool = false + /// True if the RC signal is available now var isAvailable: Bool = false + /// Signal strength (range: 0 to 100) var signalStrengthPercent: Float = 0 var unknownFields = SwiftProtobuf.UnknownStorage() @@ -721,21 +1047,31 @@ struct Mavsdk_Rpc_Telemetry_RcStatus { init() {} } +/// StatusText information type. struct Mavsdk_Rpc_Telemetry_StatusText { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for // methods supported on all messages. + /// Message type var type: Mavsdk_Rpc_Telemetry_StatusText.StatusType = .info + /// MAVLink status message var text: String = String() var unknownFields = SwiftProtobuf.UnknownStorage() + /// Status types. enum StatusType: SwiftProtobuf.Enum { typealias RawValue = Int + + /// Information or other case info // = 0 + + /// Warning case warning // = 1 + + /// Critical case critical // = 2 case UNRECOGNIZED(Int) @@ -779,89 +1115,329 @@ extension Mavsdk_Rpc_Telemetry_StatusText.StatusType: CaseIterable { #endif // swift(>=4.2) -// MARK: - Code below here is support for the SwiftProtobuf runtime. +struct Mavsdk_Rpc_Telemetry_ActuatorControlTarget { + // SwiftProtobuf.Message conformance is added in an extension below. See the + // `Message` and `Message+*Additions` files in the SwiftProtobuf library for + // methods supported on all messages. -fileprivate let _protobuf_package = "mavsdk.rpc.telemetry" + var group: Int32 = 0 -extension Mavsdk_Rpc_Telemetry_FixType: SwiftProtobuf._ProtoNameProviding { - static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ - 0: .same(proto: "NO_GPS"), - 1: .same(proto: "NO_FIX"), - 2: .same(proto: "FIX_2D"), - 3: .same(proto: "FIX_3D"), - 4: .same(proto: "FIX_DGPS"), - 5: .same(proto: "RTK_FLOAT"), - 6: .same(proto: "RTK_FIXED"), - ] + var controls: [Float] = [] + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} } -extension Mavsdk_Rpc_Telemetry_FlightMode: SwiftProtobuf._ProtoNameProviding { - static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ - 0: .same(proto: "UNKNOWN"), - 1: .same(proto: "READY"), - 2: .same(proto: "TAKEOFF"), - 3: .same(proto: "HOLD"), - 4: .same(proto: "MISSION"), - 5: .same(proto: "RETURN_TO_LAUNCH"), - 6: .same(proto: "LAND"), - 7: .same(proto: "OFFBOARD"), - 8: .same(proto: "FOLLOW_ME"), - ] +struct Mavsdk_Rpc_Telemetry_ActuatorOutputStatus { + // SwiftProtobuf.Message conformance is added in an extension below. See the + // `Message` and `Message+*Additions` files in the SwiftProtobuf library for + // methods supported on all messages. + + var active: UInt32 = 0 + + var actuator: [Float] = [] + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} } -extension Mavsdk_Rpc_Telemetry_SubscribePositionRequest: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { - static let protoMessageName: String = _protobuf_package + ".SubscribePositionRequest" - static let _protobuf_nameMap = SwiftProtobuf._NameMap() +/// Odometry message type. +struct Mavsdk_Rpc_Telemetry_Odometry { + // SwiftProtobuf.Message conformance is added in an extension below. See the + // `Message` and `Message+*Additions` files in the SwiftProtobuf library for + // methods supported on all messages. - mutating func decodeMessage(decoder: inout D) throws { - while let _ = try decoder.nextFieldNumber() { - } + /// Timestamp (0 to use Backend timestamp). + var timeUsec: UInt64 { + get {return _storage._timeUsec} + set {_uniqueStorage()._timeUsec = newValue} } - func traverse(visitor: inout V) throws { - try unknownFields.traverse(visitor: &visitor) + /// Coordinate frame of reference for the pose data. + var frameID: Mavsdk_Rpc_Telemetry_Odometry.MavFrame { + get {return _storage._frameID} + set {_uniqueStorage()._frameID = newValue} } - static func ==(lhs: Mavsdk_Rpc_Telemetry_SubscribePositionRequest, rhs: Mavsdk_Rpc_Telemetry_SubscribePositionRequest) -> Bool { - if lhs.unknownFields != rhs.unknownFields {return false} - return true + /// Coordinate frame of reference for the velocity in free space (twist) data. + var childFrameID: Mavsdk_Rpc_Telemetry_Odometry.MavFrame { + get {return _storage._childFrameID} + set {_uniqueStorage()._childFrameID = newValue} } -} -extension Mavsdk_Rpc_Telemetry_PositionResponse: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { - static let protoMessageName: String = _protobuf_package + ".PositionResponse" - static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ - 1: .same(proto: "position"), - ] + /// Position. + var positionBody: Mavsdk_Rpc_Telemetry_PositionBody { + get {return _storage._positionBody ?? Mavsdk_Rpc_Telemetry_PositionBody()} + set {_uniqueStorage()._positionBody = newValue} + } + /// Returns true if `positionBody` has been explicitly set. + var hasPositionBody: Bool {return _storage._positionBody != nil} + /// Clears the value of `positionBody`. Subsequent reads from it will return its default value. + mutating func clearPositionBody() {_uniqueStorage()._positionBody = nil} - fileprivate class _StorageClass { - var _position: Mavsdk_Rpc_Telemetry_Position? = nil + /// Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). + var q: Mavsdk_Rpc_Telemetry_Quaternion { + get {return _storage._q ?? Mavsdk_Rpc_Telemetry_Quaternion()} + set {_uniqueStorage()._q = newValue} + } + /// Returns true if `q` has been explicitly set. + var hasQ: Bool {return _storage._q != nil} + /// Clears the value of `q`. Subsequent reads from it will return its default value. + mutating func clearQ() {_uniqueStorage()._q = nil} - static let defaultInstance = _StorageClass() + /// Linear speed (m/s). + var speedBody: Mavsdk_Rpc_Telemetry_SpeedBody { + get {return _storage._speedBody ?? Mavsdk_Rpc_Telemetry_SpeedBody()} + set {_uniqueStorage()._speedBody = newValue} + } + /// Returns true if `speedBody` has been explicitly set. + var hasSpeedBody: Bool {return _storage._speedBody != nil} + /// Clears the value of `speedBody`. Subsequent reads from it will return its default value. + mutating func clearSpeedBody() {_uniqueStorage()._speedBody = nil} - private init() {} + /// Angular speed (rad/s). + var angularVelocityBody: Mavsdk_Rpc_Telemetry_AngularVelocityBody { + get {return _storage._angularVelocityBody ?? Mavsdk_Rpc_Telemetry_AngularVelocityBody()} + set {_uniqueStorage()._angularVelocityBody = newValue} + } + /// Returns true if `angularVelocityBody` has been explicitly set. + var hasAngularVelocityBody: Bool {return _storage._angularVelocityBody != nil} + /// Clears the value of `angularVelocityBody`. Subsequent reads from it will return its default value. + mutating func clearAngularVelocityBody() {_uniqueStorage()._angularVelocityBody = nil} - init(copying source: _StorageClass) { - _position = source._position - } + /// Pose cross-covariance matrix. + var poseCovariance: Mavsdk_Rpc_Telemetry_Covariance { + get {return _storage._poseCovariance ?? Mavsdk_Rpc_Telemetry_Covariance()} + set {_uniqueStorage()._poseCovariance = newValue} } + /// Returns true if `poseCovariance` has been explicitly set. + var hasPoseCovariance: Bool {return _storage._poseCovariance != nil} + /// Clears the value of `poseCovariance`. Subsequent reads from it will return its default value. + mutating func clearPoseCovariance() {_uniqueStorage()._poseCovariance = nil} - fileprivate mutating func _uniqueStorage() -> _StorageClass { - if !isKnownUniquelyReferenced(&_storage) { - _storage = _StorageClass(copying: _storage) - } - return _storage + /// Velocity cross-covariance matrix. + var velocityCovariance: Mavsdk_Rpc_Telemetry_Covariance { + get {return _storage._velocityCovariance ?? Mavsdk_Rpc_Telemetry_Covariance()} + set {_uniqueStorage()._velocityCovariance = newValue} } + /// Returns true if `velocityCovariance` has been explicitly set. + var hasVelocityCovariance: Bool {return _storage._velocityCovariance != nil} + /// Clears the value of `velocityCovariance`. Subsequent reads from it will return its default value. + mutating func clearVelocityCovariance() {_uniqueStorage()._velocityCovariance = nil} - mutating func decodeMessage(decoder: inout D) throws { - _ = _uniqueStorage() - try withExtendedLifetime(_storage) { (_storage: _StorageClass) in - while let fieldNumber = try decoder.nextFieldNumber() { - switch fieldNumber { - case 1: try decoder.decodeSingularMessageField(value: &_storage._position) - default: break - } - } + var unknownFields = SwiftProtobuf.UnknownStorage() + + /// Mavlink frame id + enum MavFrame: SwiftProtobuf.Enum { + typealias RawValue = Int + case undef // = 0 + + /// Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right. + case bodyNed // = 8 + + /// Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: north, y: east, z: down). + case visionNed // = 16 + + /// Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: north, y: east, z: down). + case estimNed // = 18 + case UNRECOGNIZED(Int) + + init() { + self = .undef + } + + init?(rawValue: Int) { + switch rawValue { + case 0: self = .undef + case 8: self = .bodyNed + case 16: self = .visionNed + case 18: self = .estimNed + default: self = .UNRECOGNIZED(rawValue) + } + } + + var rawValue: Int { + switch self { + case .undef: return 0 + case .bodyNed: return 8 + case .visionNed: return 16 + case .estimNed: return 18 + case .UNRECOGNIZED(let i): return i + } + } + + } + + init() {} + + fileprivate var _storage = _StorageClass.defaultInstance +} + +#if swift(>=4.2) + +extension Mavsdk_Rpc_Telemetry_Odometry.MavFrame: CaseIterable { + // The compiler won't synthesize support with the UNRECOGNIZED case. + static var allCases: [Mavsdk_Rpc_Telemetry_Odometry.MavFrame] = [ + .undef, + .bodyNed, + .visionNed, + .estimNed, + ] +} + +#endif // swift(>=4.2) + +/// Covariance type. +/// Row-major representation of a 6x6 cross-covariance matrix +/// upper right triangle. +/// Set first to NaN if unknown. +struct Mavsdk_Rpc_Telemetry_Covariance { + // SwiftProtobuf.Message conformance is added in an extension below. See the + // `Message` and `Message+*Additions` files in the SwiftProtobuf library for + // methods supported on all messages. + + var covarianceMatrix: [Float] = [] + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} +} + +/// Speed type, represented in the Body (X Y Z) frame and in metres/second. +struct Mavsdk_Rpc_Telemetry_SpeedBody { + // SwiftProtobuf.Message conformance is added in an extension below. See the + // `Message` and `Message+*Additions` files in the SwiftProtobuf library for + // methods supported on all messages. + + /// Velocity in X in metres/second + var velocityXMS: Float = 0 + + /// Velocity in Y in metres/second + var velocityYMS: Float = 0 + + /// Velocity in Z in metres/second + var velocityZMS: Float = 0 + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} +} + +/// Position type, represented in the Body (X Y Z) frame +struct Mavsdk_Rpc_Telemetry_PositionBody { + // SwiftProtobuf.Message conformance is added in an extension below. See the + // `Message` and `Message+*Additions` files in the SwiftProtobuf library for + // methods supported on all messages. + + /// X Position in metres. + var xM: Float = 0 + + /// Y Position in metres. + var yM: Float = 0 + + /// Z Position in metres. + var zM: Float = 0 + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} +} + +// MARK: - Code below here is support for the SwiftProtobuf runtime. + +fileprivate let _protobuf_package = "mavsdk.rpc.telemetry" + +extension Mavsdk_Rpc_Telemetry_FixType: SwiftProtobuf._ProtoNameProviding { + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 0: .same(proto: "NO_GPS"), + 1: .same(proto: "NO_FIX"), + 2: .same(proto: "FIX_2D"), + 3: .same(proto: "FIX_3D"), + 4: .same(proto: "FIX_DGPS"), + 5: .same(proto: "RTK_FLOAT"), + 6: .same(proto: "RTK_FIXED"), + ] +} + +extension Mavsdk_Rpc_Telemetry_FlightMode: SwiftProtobuf._ProtoNameProviding { + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 0: .same(proto: "UNKNOWN"), + 1: .same(proto: "READY"), + 2: .same(proto: "TAKEOFF"), + 3: .same(proto: "HOLD"), + 4: .same(proto: "MISSION"), + 5: .same(proto: "RETURN_TO_LAUNCH"), + 6: .same(proto: "LAND"), + 7: .same(proto: "OFFBOARD"), + 8: .same(proto: "FOLLOW_ME"), + ] +} + +extension Mavsdk_Rpc_Telemetry_LandedState: SwiftProtobuf._ProtoNameProviding { + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 0: .same(proto: "LANDED_STATE_UNKNOWN"), + 1: .same(proto: "LANDED_STATE_ON_GROUND"), + 2: .same(proto: "LANDED_STATE_IN_AIR"), + 3: .same(proto: "LANDED_STATE_TAKING_OFF"), + 4: .same(proto: "LANDED_STATE_LANDING"), + ] +} + +extension Mavsdk_Rpc_Telemetry_SubscribePositionRequest: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".SubscribePositionRequest" + static let _protobuf_nameMap = SwiftProtobuf._NameMap() + + mutating func decodeMessage(decoder: inout D) throws { + while let _ = try decoder.nextFieldNumber() { + } + } + + func traverse(visitor: inout V) throws { + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Telemetry_SubscribePositionRequest, rhs: Mavsdk_Rpc_Telemetry_SubscribePositionRequest) -> Bool { + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + +extension Mavsdk_Rpc_Telemetry_PositionResponse: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".PositionResponse" + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 1: .same(proto: "position"), + ] + + fileprivate class _StorageClass { + var _position: Mavsdk_Rpc_Telemetry_Position? = nil + + static let defaultInstance = _StorageClass() + + private init() {} + + init(copying source: _StorageClass) { + _position = source._position + } + } + + fileprivate mutating func _uniqueStorage() -> _StorageClass { + if !isKnownUniquelyReferenced(&_storage) { + _storage = _StorageClass(copying: _storage) + } + return _storage + } + + mutating func decodeMessage(decoder: inout D) throws { + _ = _uniqueStorage() + try withExtendedLifetime(_storage) { (_storage: _StorageClass) in + while let fieldNumber = try decoder.nextFieldNumber() { + switch fieldNumber { + case 1: try decoder.decodeSingularMessageField(value: &_storage._position) + default: break + } + } } } @@ -1017,6 +1593,54 @@ extension Mavsdk_Rpc_Telemetry_InAirResponse: SwiftProtobuf.Message, SwiftProtob } } +extension Mavsdk_Rpc_Telemetry_SubscribeLandedStateRequest: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".SubscribeLandedStateRequest" + static let _protobuf_nameMap = SwiftProtobuf._NameMap() + + mutating func decodeMessage(decoder: inout D) throws { + while let _ = try decoder.nextFieldNumber() { + } + } + + func traverse(visitor: inout V) throws { + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Telemetry_SubscribeLandedStateRequest, rhs: Mavsdk_Rpc_Telemetry_SubscribeLandedStateRequest) -> Bool { + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + +extension Mavsdk_Rpc_Telemetry_LandedStateResponse: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".LandedStateResponse" + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 1: .standard(proto: "landed_state"), + ] + + mutating func decodeMessage(decoder: inout D) throws { + while let fieldNumber = try decoder.nextFieldNumber() { + switch fieldNumber { + case 1: try decoder.decodeSingularEnumField(value: &self.landedState) + default: break + } + } + } + + func traverse(visitor: inout V) throws { + if self.landedState != .unknown { + try visitor.visitSingularEnumField(value: self.landedState, fieldNumber: 1) + } + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Telemetry_LandedStateResponse, rhs: Mavsdk_Rpc_Telemetry_LandedStateResponse) -> Bool { + if lhs.landedState != rhs.landedState {return false} + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + extension Mavsdk_Rpc_Telemetry_SubscribeArmedRequest: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { static let protoMessageName: String = _protobuf_package + ".SubscribeArmedRequest" static let _protobuf_nameMap = SwiftProtobuf._NameMap() @@ -1225,6 +1849,86 @@ extension Mavsdk_Rpc_Telemetry_AttitudeEulerResponse: SwiftProtobuf.Message, Swi } } +extension Mavsdk_Rpc_Telemetry_SubscribeAttitudeAngularVelocityBodyRequest: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".SubscribeAttitudeAngularVelocityBodyRequest" + static let _protobuf_nameMap = SwiftProtobuf._NameMap() + + mutating func decodeMessage(decoder: inout D) throws { + while let _ = try decoder.nextFieldNumber() { + } + } + + func traverse(visitor: inout V) throws { + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Telemetry_SubscribeAttitudeAngularVelocityBodyRequest, rhs: Mavsdk_Rpc_Telemetry_SubscribeAttitudeAngularVelocityBodyRequest) -> Bool { + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + +extension Mavsdk_Rpc_Telemetry_AttitudeAngularVelocityBodyResponse: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".AttitudeAngularVelocityBodyResponse" + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 1: .standard(proto: "attitude_angular_velocity_body"), + ] + + fileprivate class _StorageClass { + var _attitudeAngularVelocityBody: Mavsdk_Rpc_Telemetry_AngularVelocityBody? = nil + + static let defaultInstance = _StorageClass() + + private init() {} + + init(copying source: _StorageClass) { + _attitudeAngularVelocityBody = source._attitudeAngularVelocityBody + } + } + + fileprivate mutating func _uniqueStorage() -> _StorageClass { + if !isKnownUniquelyReferenced(&_storage) { + _storage = _StorageClass(copying: _storage) + } + return _storage + } + + mutating func decodeMessage(decoder: inout D) throws { + _ = _uniqueStorage() + try withExtendedLifetime(_storage) { (_storage: _StorageClass) in + while let fieldNumber = try decoder.nextFieldNumber() { + switch fieldNumber { + case 1: try decoder.decodeSingularMessageField(value: &_storage._attitudeAngularVelocityBody) + default: break + } + } + } + } + + func traverse(visitor: inout V) throws { + try withExtendedLifetime(_storage) { (_storage: _StorageClass) in + if let v = _storage._attitudeAngularVelocityBody { + try visitor.visitSingularMessageField(value: v, fieldNumber: 1) + } + } + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Telemetry_AttitudeAngularVelocityBodyResponse, rhs: Mavsdk_Rpc_Telemetry_AttitudeAngularVelocityBodyResponse) -> Bool { + if lhs._storage !== rhs._storage { + let storagesAreEqual: Bool = withExtendedLifetime((lhs._storage, rhs._storage)) { (_args: (_StorageClass, _StorageClass)) in + let _storage = _args.0 + let rhs_storage = _args.1 + if _storage._attitudeAngularVelocityBody != rhs_storage._attitudeAngularVelocityBody {return false} + return true + } + if !storagesAreEqual {return false} + } + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + extension Mavsdk_Rpc_Telemetry_SubscribeCameraAttitudeQuaternionRequest: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { static let protoMessageName: String = _protobuf_package + ".SubscribeCameraAttitudeQuaternionRequest" static let _protobuf_nameMap = SwiftProtobuf._NameMap() @@ -1660,21 +2364,261 @@ extension Mavsdk_Rpc_Telemetry_FlightModeResponse: SwiftProtobuf.Message, SwiftP } func traverse(visitor: inout V) throws { - if self.flightMode != .unknown { - try visitor.visitSingularEnumField(value: self.flightMode, fieldNumber: 1) + if self.flightMode != .unknown { + try visitor.visitSingularEnumField(value: self.flightMode, fieldNumber: 1) + } + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Telemetry_FlightModeResponse, rhs: Mavsdk_Rpc_Telemetry_FlightModeResponse) -> Bool { + if lhs.flightMode != rhs.flightMode {return false} + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + +extension Mavsdk_Rpc_Telemetry_SubscribeHealthRequest: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".SubscribeHealthRequest" + static let _protobuf_nameMap = SwiftProtobuf._NameMap() + + mutating func decodeMessage(decoder: inout D) throws { + while let _ = try decoder.nextFieldNumber() { + } + } + + func traverse(visitor: inout V) throws { + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Telemetry_SubscribeHealthRequest, rhs: Mavsdk_Rpc_Telemetry_SubscribeHealthRequest) -> Bool { + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + +extension Mavsdk_Rpc_Telemetry_HealthResponse: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".HealthResponse" + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 1: .same(proto: "health"), + ] + + fileprivate class _StorageClass { + var _health: Mavsdk_Rpc_Telemetry_Health? = nil + + static let defaultInstance = _StorageClass() + + private init() {} + + init(copying source: _StorageClass) { + _health = source._health + } + } + + fileprivate mutating func _uniqueStorage() -> _StorageClass { + if !isKnownUniquelyReferenced(&_storage) { + _storage = _StorageClass(copying: _storage) + } + return _storage + } + + mutating func decodeMessage(decoder: inout D) throws { + _ = _uniqueStorage() + try withExtendedLifetime(_storage) { (_storage: _StorageClass) in + while let fieldNumber = try decoder.nextFieldNumber() { + switch fieldNumber { + case 1: try decoder.decodeSingularMessageField(value: &_storage._health) + default: break + } + } + } + } + + func traverse(visitor: inout V) throws { + try withExtendedLifetime(_storage) { (_storage: _StorageClass) in + if let v = _storage._health { + try visitor.visitSingularMessageField(value: v, fieldNumber: 1) + } + } + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Telemetry_HealthResponse, rhs: Mavsdk_Rpc_Telemetry_HealthResponse) -> Bool { + if lhs._storage !== rhs._storage { + let storagesAreEqual: Bool = withExtendedLifetime((lhs._storage, rhs._storage)) { (_args: (_StorageClass, _StorageClass)) in + let _storage = _args.0 + let rhs_storage = _args.1 + if _storage._health != rhs_storage._health {return false} + return true + } + if !storagesAreEqual {return false} + } + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + +extension Mavsdk_Rpc_Telemetry_SubscribeRcStatusRequest: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".SubscribeRcStatusRequest" + static let _protobuf_nameMap = SwiftProtobuf._NameMap() + + mutating func decodeMessage(decoder: inout D) throws { + while let _ = try decoder.nextFieldNumber() { + } + } + + func traverse(visitor: inout V) throws { + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Telemetry_SubscribeRcStatusRequest, rhs: Mavsdk_Rpc_Telemetry_SubscribeRcStatusRequest) -> Bool { + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + +extension Mavsdk_Rpc_Telemetry_RcStatusResponse: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".RcStatusResponse" + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 1: .standard(proto: "rc_status"), + ] + + fileprivate class _StorageClass { + var _rcStatus: Mavsdk_Rpc_Telemetry_RcStatus? = nil + + static let defaultInstance = _StorageClass() + + private init() {} + + init(copying source: _StorageClass) { + _rcStatus = source._rcStatus + } + } + + fileprivate mutating func _uniqueStorage() -> _StorageClass { + if !isKnownUniquelyReferenced(&_storage) { + _storage = _StorageClass(copying: _storage) + } + return _storage + } + + mutating func decodeMessage(decoder: inout D) throws { + _ = _uniqueStorage() + try withExtendedLifetime(_storage) { (_storage: _StorageClass) in + while let fieldNumber = try decoder.nextFieldNumber() { + switch fieldNumber { + case 1: try decoder.decodeSingularMessageField(value: &_storage._rcStatus) + default: break + } + } + } + } + + func traverse(visitor: inout V) throws { + try withExtendedLifetime(_storage) { (_storage: _StorageClass) in + if let v = _storage._rcStatus { + try visitor.visitSingularMessageField(value: v, fieldNumber: 1) + } + } + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Telemetry_RcStatusResponse, rhs: Mavsdk_Rpc_Telemetry_RcStatusResponse) -> Bool { + if lhs._storage !== rhs._storage { + let storagesAreEqual: Bool = withExtendedLifetime((lhs._storage, rhs._storage)) { (_args: (_StorageClass, _StorageClass)) in + let _storage = _args.0 + let rhs_storage = _args.1 + if _storage._rcStatus != rhs_storage._rcStatus {return false} + return true + } + if !storagesAreEqual {return false} + } + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + +extension Mavsdk_Rpc_Telemetry_SubscribeStatusTextRequest: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".SubscribeStatusTextRequest" + static let _protobuf_nameMap = SwiftProtobuf._NameMap() + + mutating func decodeMessage(decoder: inout D) throws { + while let _ = try decoder.nextFieldNumber() { + } + } + + func traverse(visitor: inout V) throws { + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Telemetry_SubscribeStatusTextRequest, rhs: Mavsdk_Rpc_Telemetry_SubscribeStatusTextRequest) -> Bool { + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + +extension Mavsdk_Rpc_Telemetry_StatusTextResponse: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".StatusTextResponse" + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 1: .standard(proto: "status_text"), + ] + + fileprivate class _StorageClass { + var _statusText: Mavsdk_Rpc_Telemetry_StatusText? = nil + + static let defaultInstance = _StorageClass() + + private init() {} + + init(copying source: _StorageClass) { + _statusText = source._statusText + } + } + + fileprivate mutating func _uniqueStorage() -> _StorageClass { + if !isKnownUniquelyReferenced(&_storage) { + _storage = _StorageClass(copying: _storage) + } + return _storage + } + + mutating func decodeMessage(decoder: inout D) throws { + _ = _uniqueStorage() + try withExtendedLifetime(_storage) { (_storage: _StorageClass) in + while let fieldNumber = try decoder.nextFieldNumber() { + switch fieldNumber { + case 1: try decoder.decodeSingularMessageField(value: &_storage._statusText) + default: break + } + } + } + } + + func traverse(visitor: inout V) throws { + try withExtendedLifetime(_storage) { (_storage: _StorageClass) in + if let v = _storage._statusText { + try visitor.visitSingularMessageField(value: v, fieldNumber: 1) + } } try unknownFields.traverse(visitor: &visitor) } - static func ==(lhs: Mavsdk_Rpc_Telemetry_FlightModeResponse, rhs: Mavsdk_Rpc_Telemetry_FlightModeResponse) -> Bool { - if lhs.flightMode != rhs.flightMode {return false} + static func ==(lhs: Mavsdk_Rpc_Telemetry_StatusTextResponse, rhs: Mavsdk_Rpc_Telemetry_StatusTextResponse) -> Bool { + if lhs._storage !== rhs._storage { + let storagesAreEqual: Bool = withExtendedLifetime((lhs._storage, rhs._storage)) { (_args: (_StorageClass, _StorageClass)) in + let _storage = _args.0 + let rhs_storage = _args.1 + if _storage._statusText != rhs_storage._statusText {return false} + return true + } + if !storagesAreEqual {return false} + } if lhs.unknownFields != rhs.unknownFields {return false} return true } } -extension Mavsdk_Rpc_Telemetry_SubscribeHealthRequest: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { - static let protoMessageName: String = _protobuf_package + ".SubscribeHealthRequest" +extension Mavsdk_Rpc_Telemetry_SubscribeActuatorControlTargetRequest: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".SubscribeActuatorControlTargetRequest" static let _protobuf_nameMap = SwiftProtobuf._NameMap() mutating func decodeMessage(decoder: inout D) throws { @@ -1686,27 +2630,27 @@ extension Mavsdk_Rpc_Telemetry_SubscribeHealthRequest: SwiftProtobuf.Message, Sw try unknownFields.traverse(visitor: &visitor) } - static func ==(lhs: Mavsdk_Rpc_Telemetry_SubscribeHealthRequest, rhs: Mavsdk_Rpc_Telemetry_SubscribeHealthRequest) -> Bool { + static func ==(lhs: Mavsdk_Rpc_Telemetry_SubscribeActuatorControlTargetRequest, rhs: Mavsdk_Rpc_Telemetry_SubscribeActuatorControlTargetRequest) -> Bool { if lhs.unknownFields != rhs.unknownFields {return false} return true } } -extension Mavsdk_Rpc_Telemetry_HealthResponse: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { - static let protoMessageName: String = _protobuf_package + ".HealthResponse" +extension Mavsdk_Rpc_Telemetry_ActuatorControlTargetResponse: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".ActuatorControlTargetResponse" static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ - 1: .same(proto: "health"), + 1: .standard(proto: "actuator_control_target"), ] fileprivate class _StorageClass { - var _health: Mavsdk_Rpc_Telemetry_Health? = nil + var _actuatorControlTarget: Mavsdk_Rpc_Telemetry_ActuatorControlTarget? = nil static let defaultInstance = _StorageClass() private init() {} init(copying source: _StorageClass) { - _health = source._health + _actuatorControlTarget = source._actuatorControlTarget } } @@ -1722,7 +2666,7 @@ extension Mavsdk_Rpc_Telemetry_HealthResponse: SwiftProtobuf.Message, SwiftProto try withExtendedLifetime(_storage) { (_storage: _StorageClass) in while let fieldNumber = try decoder.nextFieldNumber() { switch fieldNumber { - case 1: try decoder.decodeSingularMessageField(value: &_storage._health) + case 1: try decoder.decodeSingularMessageField(value: &_storage._actuatorControlTarget) default: break } } @@ -1731,19 +2675,19 @@ extension Mavsdk_Rpc_Telemetry_HealthResponse: SwiftProtobuf.Message, SwiftProto func traverse(visitor: inout V) throws { try withExtendedLifetime(_storage) { (_storage: _StorageClass) in - if let v = _storage._health { + if let v = _storage._actuatorControlTarget { try visitor.visitSingularMessageField(value: v, fieldNumber: 1) } } try unknownFields.traverse(visitor: &visitor) } - static func ==(lhs: Mavsdk_Rpc_Telemetry_HealthResponse, rhs: Mavsdk_Rpc_Telemetry_HealthResponse) -> Bool { + static func ==(lhs: Mavsdk_Rpc_Telemetry_ActuatorControlTargetResponse, rhs: Mavsdk_Rpc_Telemetry_ActuatorControlTargetResponse) -> Bool { if lhs._storage !== rhs._storage { let storagesAreEqual: Bool = withExtendedLifetime((lhs._storage, rhs._storage)) { (_args: (_StorageClass, _StorageClass)) in let _storage = _args.0 let rhs_storage = _args.1 - if _storage._health != rhs_storage._health {return false} + if _storage._actuatorControlTarget != rhs_storage._actuatorControlTarget {return false} return true } if !storagesAreEqual {return false} @@ -1753,8 +2697,8 @@ extension Mavsdk_Rpc_Telemetry_HealthResponse: SwiftProtobuf.Message, SwiftProto } } -extension Mavsdk_Rpc_Telemetry_SubscribeRcStatusRequest: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { - static let protoMessageName: String = _protobuf_package + ".SubscribeRcStatusRequest" +extension Mavsdk_Rpc_Telemetry_SubscribeActuatorOutputStatusRequest: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".SubscribeActuatorOutputStatusRequest" static let _protobuf_nameMap = SwiftProtobuf._NameMap() mutating func decodeMessage(decoder: inout D) throws { @@ -1766,27 +2710,27 @@ extension Mavsdk_Rpc_Telemetry_SubscribeRcStatusRequest: SwiftProtobuf.Message, try unknownFields.traverse(visitor: &visitor) } - static func ==(lhs: Mavsdk_Rpc_Telemetry_SubscribeRcStatusRequest, rhs: Mavsdk_Rpc_Telemetry_SubscribeRcStatusRequest) -> Bool { + static func ==(lhs: Mavsdk_Rpc_Telemetry_SubscribeActuatorOutputStatusRequest, rhs: Mavsdk_Rpc_Telemetry_SubscribeActuatorOutputStatusRequest) -> Bool { if lhs.unknownFields != rhs.unknownFields {return false} return true } } -extension Mavsdk_Rpc_Telemetry_RcStatusResponse: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { - static let protoMessageName: String = _protobuf_package + ".RcStatusResponse" +extension Mavsdk_Rpc_Telemetry_ActuatorOutputStatusResponse: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".ActuatorOutputStatusResponse" static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ - 1: .standard(proto: "rc_status"), + 1: .standard(proto: "actuator_output_status"), ] fileprivate class _StorageClass { - var _rcStatus: Mavsdk_Rpc_Telemetry_RcStatus? = nil + var _actuatorOutputStatus: Mavsdk_Rpc_Telemetry_ActuatorOutputStatus? = nil static let defaultInstance = _StorageClass() private init() {} init(copying source: _StorageClass) { - _rcStatus = source._rcStatus + _actuatorOutputStatus = source._actuatorOutputStatus } } @@ -1802,7 +2746,7 @@ extension Mavsdk_Rpc_Telemetry_RcStatusResponse: SwiftProtobuf.Message, SwiftPro try withExtendedLifetime(_storage) { (_storage: _StorageClass) in while let fieldNumber = try decoder.nextFieldNumber() { switch fieldNumber { - case 1: try decoder.decodeSingularMessageField(value: &_storage._rcStatus) + case 1: try decoder.decodeSingularMessageField(value: &_storage._actuatorOutputStatus) default: break } } @@ -1811,19 +2755,19 @@ extension Mavsdk_Rpc_Telemetry_RcStatusResponse: SwiftProtobuf.Message, SwiftPro func traverse(visitor: inout V) throws { try withExtendedLifetime(_storage) { (_storage: _StorageClass) in - if let v = _storage._rcStatus { + if let v = _storage._actuatorOutputStatus { try visitor.visitSingularMessageField(value: v, fieldNumber: 1) } } try unknownFields.traverse(visitor: &visitor) } - static func ==(lhs: Mavsdk_Rpc_Telemetry_RcStatusResponse, rhs: Mavsdk_Rpc_Telemetry_RcStatusResponse) -> Bool { + static func ==(lhs: Mavsdk_Rpc_Telemetry_ActuatorOutputStatusResponse, rhs: Mavsdk_Rpc_Telemetry_ActuatorOutputStatusResponse) -> Bool { if lhs._storage !== rhs._storage { let storagesAreEqual: Bool = withExtendedLifetime((lhs._storage, rhs._storage)) { (_args: (_StorageClass, _StorageClass)) in let _storage = _args.0 let rhs_storage = _args.1 - if _storage._rcStatus != rhs_storage._rcStatus {return false} + if _storage._actuatorOutputStatus != rhs_storage._actuatorOutputStatus {return false} return true } if !storagesAreEqual {return false} @@ -1833,8 +2777,8 @@ extension Mavsdk_Rpc_Telemetry_RcStatusResponse: SwiftProtobuf.Message, SwiftPro } } -extension Mavsdk_Rpc_Telemetry_SubscribeStatusTextRequest: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { - static let protoMessageName: String = _protobuf_package + ".SubscribeStatusTextRequest" +extension Mavsdk_Rpc_Telemetry_SubscribeOdometryRequest: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".SubscribeOdometryRequest" static let _protobuf_nameMap = SwiftProtobuf._NameMap() mutating func decodeMessage(decoder: inout D) throws { @@ -1846,27 +2790,27 @@ extension Mavsdk_Rpc_Telemetry_SubscribeStatusTextRequest: SwiftProtobuf.Message try unknownFields.traverse(visitor: &visitor) } - static func ==(lhs: Mavsdk_Rpc_Telemetry_SubscribeStatusTextRequest, rhs: Mavsdk_Rpc_Telemetry_SubscribeStatusTextRequest) -> Bool { + static func ==(lhs: Mavsdk_Rpc_Telemetry_SubscribeOdometryRequest, rhs: Mavsdk_Rpc_Telemetry_SubscribeOdometryRequest) -> Bool { if lhs.unknownFields != rhs.unknownFields {return false} return true } } -extension Mavsdk_Rpc_Telemetry_StatusTextResponse: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { - static let protoMessageName: String = _protobuf_package + ".StatusTextResponse" +extension Mavsdk_Rpc_Telemetry_OdometryResponse: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".OdometryResponse" static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ - 1: .standard(proto: "status_text"), + 1: .same(proto: "odometry"), ] fileprivate class _StorageClass { - var _statusText: Mavsdk_Rpc_Telemetry_StatusText? = nil + var _odometry: Mavsdk_Rpc_Telemetry_Odometry? = nil static let defaultInstance = _StorageClass() private init() {} init(copying source: _StorageClass) { - _statusText = source._statusText + _odometry = source._odometry } } @@ -1882,7 +2826,7 @@ extension Mavsdk_Rpc_Telemetry_StatusTextResponse: SwiftProtobuf.Message, SwiftP try withExtendedLifetime(_storage) { (_storage: _StorageClass) in while let fieldNumber = try decoder.nextFieldNumber() { switch fieldNumber { - case 1: try decoder.decodeSingularMessageField(value: &_storage._statusText) + case 1: try decoder.decodeSingularMessageField(value: &_storage._odometry) default: break } } @@ -1891,19 +2835,19 @@ extension Mavsdk_Rpc_Telemetry_StatusTextResponse: SwiftProtobuf.Message, SwiftP func traverse(visitor: inout V) throws { try withExtendedLifetime(_storage) { (_storage: _StorageClass) in - if let v = _storage._statusText { + if let v = _storage._odometry { try visitor.visitSingularMessageField(value: v, fieldNumber: 1) } } try unknownFields.traverse(visitor: &visitor) } - static func ==(lhs: Mavsdk_Rpc_Telemetry_StatusTextResponse, rhs: Mavsdk_Rpc_Telemetry_StatusTextResponse) -> Bool { + static func ==(lhs: Mavsdk_Rpc_Telemetry_OdometryResponse, rhs: Mavsdk_Rpc_Telemetry_OdometryResponse) -> Bool { if lhs._storage !== rhs._storage { let storagesAreEqual: Bool = withExtendedLifetime((lhs._storage, rhs._storage)) { (_args: (_StorageClass, _StorageClass)) in let _storage = _args.0 let rhs_storage = _args.1 - if _storage._statusText != rhs_storage._statusText {return false} + if _storage._odometry != rhs_storage._odometry {return false} return true } if !storagesAreEqual {return false} @@ -2048,6 +2992,47 @@ extension Mavsdk_Rpc_Telemetry_EulerAngle: SwiftProtobuf.Message, SwiftProtobuf. } } +extension Mavsdk_Rpc_Telemetry_AngularVelocityBody: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".AngularVelocityBody" + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 1: .standard(proto: "roll_rad_s"), + 2: .standard(proto: "pitch_rad_s"), + 3: .standard(proto: "yaw_rad_s"), + ] + + mutating func decodeMessage(decoder: inout D) throws { + while let fieldNumber = try decoder.nextFieldNumber() { + switch fieldNumber { + case 1: try decoder.decodeSingularFloatField(value: &self.rollRadS) + case 2: try decoder.decodeSingularFloatField(value: &self.pitchRadS) + case 3: try decoder.decodeSingularFloatField(value: &self.yawRadS) + default: break + } + } + } + + func traverse(visitor: inout V) throws { + if self.rollRadS != 0 { + try visitor.visitSingularFloatField(value: self.rollRadS, fieldNumber: 1) + } + if self.pitchRadS != 0 { + try visitor.visitSingularFloatField(value: self.pitchRadS, fieldNumber: 2) + } + if self.yawRadS != 0 { + try visitor.visitSingularFloatField(value: self.yawRadS, fieldNumber: 3) + } + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Telemetry_AngularVelocityBody, rhs: Mavsdk_Rpc_Telemetry_AngularVelocityBody) -> Bool { + if lhs.rollRadS != rhs.rollRadS {return false} + if lhs.pitchRadS != rhs.pitchRadS {return false} + if lhs.yawRadS != rhs.yawRadS {return false} + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + extension Mavsdk_Rpc_Telemetry_SpeedNed: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { static let protoMessageName: String = _protobuf_package + ".SpeedNed" static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ @@ -2307,3 +3292,318 @@ extension Mavsdk_Rpc_Telemetry_StatusText.StatusType: SwiftProtobuf._ProtoNamePr 2: .same(proto: "CRITICAL"), ] } + +extension Mavsdk_Rpc_Telemetry_ActuatorControlTarget: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".ActuatorControlTarget" + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 1: .same(proto: "group"), + 2: .same(proto: "controls"), + ] + + mutating func decodeMessage(decoder: inout D) throws { + while let fieldNumber = try decoder.nextFieldNumber() { + switch fieldNumber { + case 1: try decoder.decodeSingularInt32Field(value: &self.group) + case 2: try decoder.decodeRepeatedFloatField(value: &self.controls) + default: break + } + } + } + + func traverse(visitor: inout V) throws { + if self.group != 0 { + try visitor.visitSingularInt32Field(value: self.group, fieldNumber: 1) + } + if !self.controls.isEmpty { + try visitor.visitPackedFloatField(value: self.controls, fieldNumber: 2) + } + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Telemetry_ActuatorControlTarget, rhs: Mavsdk_Rpc_Telemetry_ActuatorControlTarget) -> Bool { + if lhs.group != rhs.group {return false} + if lhs.controls != rhs.controls {return false} + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + +extension Mavsdk_Rpc_Telemetry_ActuatorOutputStatus: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".ActuatorOutputStatus" + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 1: .same(proto: "active"), + 2: .same(proto: "actuator"), + ] + + mutating func decodeMessage(decoder: inout D) throws { + while let fieldNumber = try decoder.nextFieldNumber() { + switch fieldNumber { + case 1: try decoder.decodeSingularUInt32Field(value: &self.active) + case 2: try decoder.decodeRepeatedFloatField(value: &self.actuator) + default: break + } + } + } + + func traverse(visitor: inout V) throws { + if self.active != 0 { + try visitor.visitSingularUInt32Field(value: self.active, fieldNumber: 1) + } + if !self.actuator.isEmpty { + try visitor.visitPackedFloatField(value: self.actuator, fieldNumber: 2) + } + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Telemetry_ActuatorOutputStatus, rhs: Mavsdk_Rpc_Telemetry_ActuatorOutputStatus) -> Bool { + if lhs.active != rhs.active {return false} + if lhs.actuator != rhs.actuator {return false} + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + +extension Mavsdk_Rpc_Telemetry_Odometry: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".Odometry" + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 1: .standard(proto: "time_usec"), + 2: .standard(proto: "frame_id"), + 3: .standard(proto: "child_frame_id"), + 4: .standard(proto: "position_body"), + 5: .same(proto: "q"), + 6: .standard(proto: "speed_body"), + 7: .standard(proto: "angular_velocity_body"), + 8: .standard(proto: "pose_covariance"), + 9: .standard(proto: "velocity_covariance"), + ] + + fileprivate class _StorageClass { + var _timeUsec: UInt64 = 0 + var _frameID: Mavsdk_Rpc_Telemetry_Odometry.MavFrame = .undef + var _childFrameID: Mavsdk_Rpc_Telemetry_Odometry.MavFrame = .undef + var _positionBody: Mavsdk_Rpc_Telemetry_PositionBody? = nil + var _q: Mavsdk_Rpc_Telemetry_Quaternion? = nil + var _speedBody: Mavsdk_Rpc_Telemetry_SpeedBody? = nil + var _angularVelocityBody: Mavsdk_Rpc_Telemetry_AngularVelocityBody? = nil + var _poseCovariance: Mavsdk_Rpc_Telemetry_Covariance? = nil + var _velocityCovariance: Mavsdk_Rpc_Telemetry_Covariance? = nil + + static let defaultInstance = _StorageClass() + + private init() {} + + init(copying source: _StorageClass) { + _timeUsec = source._timeUsec + _frameID = source._frameID + _childFrameID = source._childFrameID + _positionBody = source._positionBody + _q = source._q + _speedBody = source._speedBody + _angularVelocityBody = source._angularVelocityBody + _poseCovariance = source._poseCovariance + _velocityCovariance = source._velocityCovariance + } + } + + fileprivate mutating func _uniqueStorage() -> _StorageClass { + if !isKnownUniquelyReferenced(&_storage) { + _storage = _StorageClass(copying: _storage) + } + return _storage + } + + mutating func decodeMessage(decoder: inout D) throws { + _ = _uniqueStorage() + try withExtendedLifetime(_storage) { (_storage: _StorageClass) in + while let fieldNumber = try decoder.nextFieldNumber() { + switch fieldNumber { + case 1: try decoder.decodeSingularUInt64Field(value: &_storage._timeUsec) + case 2: try decoder.decodeSingularEnumField(value: &_storage._frameID) + case 3: try decoder.decodeSingularEnumField(value: &_storage._childFrameID) + case 4: try decoder.decodeSingularMessageField(value: &_storage._positionBody) + case 5: try decoder.decodeSingularMessageField(value: &_storage._q) + case 6: try decoder.decodeSingularMessageField(value: &_storage._speedBody) + case 7: try decoder.decodeSingularMessageField(value: &_storage._angularVelocityBody) + case 8: try decoder.decodeSingularMessageField(value: &_storage._poseCovariance) + case 9: try decoder.decodeSingularMessageField(value: &_storage._velocityCovariance) + default: break + } + } + } + } + + func traverse(visitor: inout V) throws { + try withExtendedLifetime(_storage) { (_storage: _StorageClass) in + if _storage._timeUsec != 0 { + try visitor.visitSingularUInt64Field(value: _storage._timeUsec, fieldNumber: 1) + } + if _storage._frameID != .undef { + try visitor.visitSingularEnumField(value: _storage._frameID, fieldNumber: 2) + } + if _storage._childFrameID != .undef { + try visitor.visitSingularEnumField(value: _storage._childFrameID, fieldNumber: 3) + } + if let v = _storage._positionBody { + try visitor.visitSingularMessageField(value: v, fieldNumber: 4) + } + if let v = _storage._q { + try visitor.visitSingularMessageField(value: v, fieldNumber: 5) + } + if let v = _storage._speedBody { + try visitor.visitSingularMessageField(value: v, fieldNumber: 6) + } + if let v = _storage._angularVelocityBody { + try visitor.visitSingularMessageField(value: v, fieldNumber: 7) + } + if let v = _storage._poseCovariance { + try visitor.visitSingularMessageField(value: v, fieldNumber: 8) + } + if let v = _storage._velocityCovariance { + try visitor.visitSingularMessageField(value: v, fieldNumber: 9) + } + } + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Telemetry_Odometry, rhs: Mavsdk_Rpc_Telemetry_Odometry) -> Bool { + if lhs._storage !== rhs._storage { + let storagesAreEqual: Bool = withExtendedLifetime((lhs._storage, rhs._storage)) { (_args: (_StorageClass, _StorageClass)) in + let _storage = _args.0 + let rhs_storage = _args.1 + if _storage._timeUsec != rhs_storage._timeUsec {return false} + if _storage._frameID != rhs_storage._frameID {return false} + if _storage._childFrameID != rhs_storage._childFrameID {return false} + if _storage._positionBody != rhs_storage._positionBody {return false} + if _storage._q != rhs_storage._q {return false} + if _storage._speedBody != rhs_storage._speedBody {return false} + if _storage._angularVelocityBody != rhs_storage._angularVelocityBody {return false} + if _storage._poseCovariance != rhs_storage._poseCovariance {return false} + if _storage._velocityCovariance != rhs_storage._velocityCovariance {return false} + return true + } + if !storagesAreEqual {return false} + } + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + +extension Mavsdk_Rpc_Telemetry_Odometry.MavFrame: SwiftProtobuf._ProtoNameProviding { + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 0: .same(proto: "UNDEF"), + 8: .same(proto: "BODY_NED"), + 16: .same(proto: "VISION_NED"), + 18: .same(proto: "ESTIM_NED"), + ] +} + +extension Mavsdk_Rpc_Telemetry_Covariance: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".Covariance" + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 1: .standard(proto: "covariance_matrix"), + ] + + mutating func decodeMessage(decoder: inout D) throws { + while let fieldNumber = try decoder.nextFieldNumber() { + switch fieldNumber { + case 1: try decoder.decodeRepeatedFloatField(value: &self.covarianceMatrix) + default: break + } + } + } + + func traverse(visitor: inout V) throws { + if !self.covarianceMatrix.isEmpty { + try visitor.visitPackedFloatField(value: self.covarianceMatrix, fieldNumber: 1) + } + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Telemetry_Covariance, rhs: Mavsdk_Rpc_Telemetry_Covariance) -> Bool { + if lhs.covarianceMatrix != rhs.covarianceMatrix {return false} + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + +extension Mavsdk_Rpc_Telemetry_SpeedBody: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".SpeedBody" + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 1: .standard(proto: "velocity_x_m_s"), + 2: .standard(proto: "velocity_y_m_s"), + 3: .standard(proto: "velocity_z_m_s"), + ] + + mutating func decodeMessage(decoder: inout D) throws { + while let fieldNumber = try decoder.nextFieldNumber() { + switch fieldNumber { + case 1: try decoder.decodeSingularFloatField(value: &self.velocityXMS) + case 2: try decoder.decodeSingularFloatField(value: &self.velocityYMS) + case 3: try decoder.decodeSingularFloatField(value: &self.velocityZMS) + default: break + } + } + } + + func traverse(visitor: inout V) throws { + if self.velocityXMS != 0 { + try visitor.visitSingularFloatField(value: self.velocityXMS, fieldNumber: 1) + } + if self.velocityYMS != 0 { + try visitor.visitSingularFloatField(value: self.velocityYMS, fieldNumber: 2) + } + if self.velocityZMS != 0 { + try visitor.visitSingularFloatField(value: self.velocityZMS, fieldNumber: 3) + } + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Telemetry_SpeedBody, rhs: Mavsdk_Rpc_Telemetry_SpeedBody) -> Bool { + if lhs.velocityXMS != rhs.velocityXMS {return false} + if lhs.velocityYMS != rhs.velocityYMS {return false} + if lhs.velocityZMS != rhs.velocityZMS {return false} + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + +extension Mavsdk_Rpc_Telemetry_PositionBody: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".PositionBody" + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 1: .standard(proto: "x_m"), + 2: .standard(proto: "y_m"), + 3: .standard(proto: "z_m"), + ] + + mutating func decodeMessage(decoder: inout D) throws { + while let fieldNumber = try decoder.nextFieldNumber() { + switch fieldNumber { + case 1: try decoder.decodeSingularFloatField(value: &self.xM) + case 2: try decoder.decodeSingularFloatField(value: &self.yM) + case 3: try decoder.decodeSingularFloatField(value: &self.zM) + default: break + } + } + } + + func traverse(visitor: inout V) throws { + if self.xM != 0 { + try visitor.visitSingularFloatField(value: self.xM, fieldNumber: 1) + } + if self.yM != 0 { + try visitor.visitSingularFloatField(value: self.yM, fieldNumber: 2) + } + if self.zM != 0 { + try visitor.visitSingularFloatField(value: self.zM, fieldNumber: 3) + } + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Telemetry_PositionBody, rhs: Mavsdk_Rpc_Telemetry_PositionBody) -> Bool { + if lhs.xM != rhs.xM {return false} + if lhs.yM != rhs.yM {return false} + if lhs.zM != rhs.zM {return false} + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} diff --git a/proto b/proto index 766f93e..9ed9854 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 766f93e7f7508c924632181faf5fbe5a6a57d14b +Subproject commit 9ed985463efd30c3ce87198b873edb8efe5e08cd diff --git a/templates/enum.j2 b/templates/enum.j2 index 1d6052b..ac4c81e 100644 --- a/templates/enum.j2 +++ b/templates/enum.j2 @@ -9,7 +9,7 @@ public enum {{ name.upper_camel_case }}: Equatable { switch self { {%- for value in values %} case .{{ value.name.lower_camel_case }}: - return .{{ value.name.lower_camel_case }} + return .{% if value.name.uppercase.startswith(name.uppercase) %}{% set value_without_prefix = value.name.lower_camel_case[name.lower_camel_case|length:] %}{{ value_without_prefix[0].lower() + value_without_prefix[1:] }}{% else %}{{ value.name.lower_camel_case }}{% endif %} {%- endfor %} case .UNRECOGNIZED(let i): return .UNRECOGNIZED(i) @@ -19,7 +19,7 @@ public enum {{ name.upper_camel_case }}: Equatable { internal static func translateFromRpc(_ rpc{{ name.upper_camel_case }}: {{ package.upper_camel_case.replace('_', '').replace('.', '_') }}{% if parent_struct is not none %}_{{ parent_struct.upper_camel_case }}.{% else %}_{% endif %}{{ name.upper_camel_case }}) -> {{ name.upper_camel_case }} { switch rpc{{ name.upper_camel_case }} { {%- for value in values %} - case .{{ value.name.lower_camel_case }}: + case .{% if value.name.uppercase.startswith(name.uppercase) %}{% set value_without_prefix = value.name.lower_camel_case[name.lower_camel_case|length:] %}{{ value_without_prefix[0].lower() + value_without_prefix[1:] }}{% else %}{{ value.name.lower_camel_case }}{% endif %}: return .{{ value.name.lower_camel_case }} {%- endfor %} case .UNRECOGNIZED(let i): diff --git a/tools/generate_from_protos.bash b/tools/generate_from_protos.bash index d839bf8..b6ea620 100755 --- a/tools/generate_from_protos.bash +++ b/tools/generate_from_protos.bash @@ -9,7 +9,7 @@ PB_PLUGINS_DIR=${PB_PLUGINS_DIR:-"${SCRIPT_DIR}/../proto/pb_plugins"} PROTO_DIR=${PROTO_DIR:-"${SCRIPT_DIR}/../proto/protos"} OUTPUT_DIR=${OUTPUT_DIR:-"${SCRIPT_DIR}/../Sources/MAVSDK-Swift/Generated"} -PLUGIN_LIST="action calibration gimbal camera core info mission offboard param telemetry" +PLUGIN_LIST="action calibration camera core gimbal info mission offboard param telemetry" if [ ! -d ${PROTO_DIR} ]; then echo "Script is not in the right location! It will look for the proto files in '${PROTO_DIR}', which doesn't exist!"