From 43a01732afe76bf45cbe6bb53a2af9f091eb244c Mon Sep 17 00:00:00 2001 From: Jonas Vautherin Date: Wed, 27 Sep 2023 18:37:01 +0200 Subject: [PATCH] Update mavsdk-server to 1.4.17 --- Package.swift | 4 +- Sources/Mavsdk/Drone.swift | 6 + Sources/Mavsdk/Generated/Param.swift | 158 ++++++++- Sources/Mavsdk/Generated/Rtk.swift | 235 +++++++++++++ Sources/Mavsdk/Generated/action.pb.swift | 4 +- .../Mavsdk/Generated/action_server.pb.swift | 4 +- Sources/Mavsdk/Generated/calibration.pb.swift | 2 +- Sources/Mavsdk/Generated/camera.pb.swift | 14 +- .../Generated/component_information.pb.swift | 2 +- .../component_information_server.pb.swift | 2 +- Sources/Mavsdk/Generated/failure.pb.swift | 6 +- Sources/Mavsdk/Generated/follow_me.pb.swift | 4 +- Sources/Mavsdk/Generated/ftp.pb.swift | 2 +- Sources/Mavsdk/Generated/geofence.pb.swift | 4 +- Sources/Mavsdk/Generated/gimbal.pb.swift | 6 +- Sources/Mavsdk/Generated/info.pb.swift | 2 +- Sources/Mavsdk/Generated/log_files.pb.swift | 2 +- .../Mavsdk/Generated/manual_control.pb.swift | 2 +- Sources/Mavsdk/Generated/mission.pb.swift | 4 +- Sources/Mavsdk/Generated/mission_raw.pb.swift | 2 +- .../Generated/mission_raw_server.pb.swift | 2 +- Sources/Mavsdk/Generated/mocap.pb.swift | 4 +- Sources/Mavsdk/Generated/offboard.pb.swift | 4 +- Sources/Mavsdk/Generated/param.grpc.swift | 96 ++++++ Sources/Mavsdk/Generated/param.pb.swift | 303 ++++++++++++++++- Sources/Mavsdk/Generated/rtk.grpc.swift | 133 ++++++++ Sources/Mavsdk/Generated/rtk.pb.swift | 321 ++++++++++++++++++ .../Mavsdk/Generated/server_utility.pb.swift | 4 +- Sources/Mavsdk/Generated/shell.pb.swift | 2 +- Sources/Mavsdk/Generated/telemetry.pb.swift | 14 +- .../Generated/telemetry_server.pb.swift | 12 +- Sources/Mavsdk/Generated/transponder.pb.swift | 4 +- Sources/Mavsdk/Generated/tune.pb.swift | 4 +- Sources/Mavsdk/proto | 2 +- 34 files changed, 1306 insertions(+), 64 deletions(-) create mode 100644 Sources/Mavsdk/Generated/Rtk.swift create mode 100644 Sources/Mavsdk/Generated/rtk.grpc.swift create mode 100644 Sources/Mavsdk/Generated/rtk.pb.swift diff --git a/Package.swift b/Package.swift index e254868..cba8ba1 100644 --- a/Package.swift +++ b/Package.swift @@ -47,8 +47,8 @@ let package = Package( ] ), .binaryTarget(name: "mavsdk_server", - url: "https://github.com/mavlink/MAVSDK/releases/download/v1.4.4/mavsdk_server.xcframework.zip", - checksum: "a8c116952919a415a4d8bf166831f0ba4e87c26f4ba33f07aacec9073bc45be6"), + url: "https://github.com/mavlink/MAVSDK/releases/download/v1.4.17/mavsdk_server.xcframework.zip", + checksum: "e5b1f13add15892aba1315412d9aa9a9eb4eb565512e87325819d7f23dde8aec"), .testTarget(name: "MavsdkTests", dependencies: [ "Mavsdk", diff --git a/Sources/Mavsdk/Drone.swift b/Sources/Mavsdk/Drone.swift index 1117e6a..238b0d6 100644 --- a/Sources/Mavsdk/Drone.swift +++ b/Sources/Mavsdk/Drone.swift @@ -10,6 +10,7 @@ public class Drone { public var calibration: Calibration! public var camera: Camera! public var core: Core! + public var failure: Failure! public var followMe: FollowMe! public var ftp: Ftp! public var geofence: Geofence! @@ -22,8 +23,10 @@ public class Drone { public var mocap: Mocap! public var offboard: Offboard! public var param: Param! + public var rtk: Rtk! public var shell: Shell! public var telemetry: Telemetry! + public var transponder: Transponder! public var tune: Tune! public init(scheduler: SchedulerType = ConcurrentDispatchQueueScheduler(qos: .background)) { @@ -76,6 +79,7 @@ public class Drone { self.calibration = Calibration(address: address, port: port, scheduler: scheduler) self.camera = Camera(address: address, port: port, scheduler: scheduler) self.core = Core(address: address, port: port, scheduler: scheduler) + self.failure = Failure(address: address, port: port, scheduler: scheduler) self.followMe = FollowMe(address: address, port: port, scheduler: scheduler) self.ftp = Ftp(address: address, port: port, scheduler: scheduler) self.geofence = Geofence(address: address, port: port, scheduler: scheduler) @@ -88,8 +92,10 @@ public class Drone { self.mocap = Mocap(address: address, port: port, scheduler: scheduler) self.offboard = Offboard(address: address, port: port, scheduler: scheduler) self.param = Param(address: address, port: port, scheduler: scheduler) + self.rtk = Rtk(address: address, port: port, scheduler: scheduler) self.shell = Shell(address: address, port: port, scheduler: scheduler) self.telemetry = Telemetry(address: address, port: port, scheduler: scheduler) + self.transponder = Transponder(address: address, port: port, scheduler: scheduler) self.tune = Tune(address: address, port: port, scheduler: scheduler) } diff --git a/Sources/Mavsdk/Generated/Param.swift b/Sources/Mavsdk/Generated/Param.swift index 149fc71..48c3b6c 100644 --- a/Sources/Mavsdk/Generated/Param.swift +++ b/Sources/Mavsdk/Generated/Param.swift @@ -158,11 +158,64 @@ public class Param { } /** - Type collecting all integer and float parameters. + Type for custom parameters + */ + public struct CustomParam: Equatable { + public let name: String + public let value: String + + + + /** + Initializes a new `CustomParam`. + + + - Parameters: + + - name: Name of the parameter + + - value: Value of the parameter (max len 128 bytes) + + + */ + public init(name: String, value: String) { + self.name = name + self.value = value + } + + internal var rpcCustomParam: Mavsdk_Rpc_Param_CustomParam { + var rpcCustomParam = Mavsdk_Rpc_Param_CustomParam() + + + rpcCustomParam.name = name + + + + + rpcCustomParam.value = value + + + + return rpcCustomParam + } + + internal static func translateFromRpc(_ rpcCustomParam: Mavsdk_Rpc_Param_CustomParam) -> CustomParam { + return CustomParam(name: rpcCustomParam.name, value: rpcCustomParam.value) + } + + public static func == (lhs: CustomParam, rhs: CustomParam) -> Bool { + return lhs.name == rhs.name + && lhs.value == rhs.value + } + } + + /** + Type collecting all integer, float, and custom parameters. */ public struct AllParams: Equatable { public let intParams: [IntParam] public let floatParams: [FloatParam] + public let customParams: [CustomParam] @@ -176,11 +229,14 @@ public class Param { - floatParams: Collection of all parameter names and values of type float + - customParams: Collection of all parameter names and values of type custom + */ - public init(intParams: [IntParam], floatParams: [FloatParam]) { + public init(intParams: [IntParam], floatParams: [FloatParam], customParams: [CustomParam]) { self.intParams = intParams self.floatParams = floatParams + self.customParams = customParams } internal var rpcAllParams: Mavsdk_Rpc_Param_AllParams { @@ -195,17 +251,23 @@ public class Param { rpcAllParams.floatParams = floatParams.map{ $0.rpcFloatParam } + + + rpcAllParams.customParams = customParams.map{ $0.rpcCustomParam } + + return rpcAllParams } internal static func translateFromRpc(_ rpcAllParams: Mavsdk_Rpc_Param_AllParams) -> AllParams { - return AllParams(intParams: rpcAllParams.intParams.map{ IntParam.translateFromRpc($0) }, floatParams: rpcAllParams.floatParams.map{ FloatParam.translateFromRpc($0) }) + return AllParams(intParams: rpcAllParams.intParams.map{ IntParam.translateFromRpc($0) }, floatParams: rpcAllParams.floatParams.map{ FloatParam.translateFromRpc($0) }, customParams: rpcAllParams.customParams.map{ CustomParam.translateFromRpc($0) }) } public static func == (lhs: AllParams, rhs: AllParams) -> Bool { return lhs.intParams == rhs.intParams && lhs.floatParams == rhs.floatParams + && lhs.customParams == rhs.customParams } } @@ -237,6 +299,8 @@ public class Param { case paramNameTooLong /// No system connected. case noSystem + /// Param value too long (> 128). + case paramValueTooLong case UNRECOGNIZED(Int) internal var rpcResult: Mavsdk_Rpc_Param_ParamResult.Result { @@ -255,6 +319,8 @@ public class Param { return .paramNameTooLong case .noSystem: return .noSystem + case .paramValueTooLong: + return .paramValueTooLong case .UNRECOGNIZED(let i): return .UNRECOGNIZED(i) } @@ -276,6 +342,8 @@ public class Param { return .paramNameTooLong case .noSystem: return .noSystem + case .paramValueTooLong: + return .paramValueTooLong case .UNRECOGNIZED(let i): return .UNRECOGNIZED(i) } @@ -495,6 +563,90 @@ public class Param { } } + /** + Get a custom parameter. + + If the type is wrong, the result will be `WRONG_TYPE`. + + - Parameter name: Name of the parameter + + */ + public func getParamCustom(name: String) -> Single { + return Single.create { single in + var request = Mavsdk_Rpc_Param_GetParamCustomRequest() + + + + request.name = name + + + + do { + let response = self.service.getParamCustom(request) + + + let result = try response.response.wait().paramResult + if (result.result != Mavsdk_Rpc_Param_ParamResult.Result.success) { + single(.failure(ParamError(code: ParamResult.Result.translateFromRpc(result.result), description: result.resultStr))) + + return Disposables.create() + } + + + let value = try response.response.wait().value + + single(.success(value)) + } catch { + single(.failure(error)) + } + + return Disposables.create() + } + } + + /** + Set a custom parameter. + + If the type is wrong, the result will be `WRONG_TYPE`. + + - Parameters: + - name: Name of the parameter to set + - value: Value the parameter should be set to + + */ + public func setParamCustom(name: String, value: String) -> Completable { + return Completable.create { completable in + var request = Mavsdk_Rpc_Param_SetParamCustomRequest() + + + + request.name = name + + + + request.value = value + + + + do { + + let response = self.service.setParamCustom(request) + + let result = try response.response.wait().paramResult + if (result.result == Mavsdk_Rpc_Param_ParamResult.Result.success) { + completable(.completed) + } else { + completable(.error(ParamError(code: ParamResult.Result.translateFromRpc(result.result), description: result.resultStr))) + } + + } catch { + completable(.error(error)) + } + + return Disposables.create() + } + } + /** Get all parameters. diff --git a/Sources/Mavsdk/Generated/Rtk.swift b/Sources/Mavsdk/Generated/Rtk.swift new file mode 100644 index 0000000..09392e7 --- /dev/null +++ b/Sources/Mavsdk/Generated/Rtk.swift @@ -0,0 +1,235 @@ +import Foundation +import RxSwift +import GRPC +import NIO + +/** + Service to send RTK corrections to the vehicle. + */ +public class Rtk { + private let service: Mavsdk_Rpc_Rtk_RtkServiceClient + private let scheduler: SchedulerType + private let clientEventLoopGroup: EventLoopGroup + + /** + Initializes a new `Rtk` plugin. + + Normally never created manually, but used from the `Drone` helper class instead. + + - Parameters: + - address: The address of the `MavsdkServer` instance to connect to + - port: The port of the `MavsdkServer` instance to connect to + - scheduler: The scheduler to be used by `Observable`s + */ + public convenience init(address: String = "localhost", + port: Int32 = 50051, + scheduler: SchedulerType = ConcurrentDispatchQueueScheduler(qos: .background)) { + let eventLoopGroup = MultiThreadedEventLoopGroup(numberOfThreads: 2) + let channel = ClientConnection.insecure(group: eventLoopGroup).connect(host: address, port: Int(port)) + let service = Mavsdk_Rpc_Rtk_RtkServiceClient(channel: channel) + + self.init(service: service, scheduler: scheduler, eventLoopGroup: eventLoopGroup) + } + + init(service: Mavsdk_Rpc_Rtk_RtkServiceClient, scheduler: SchedulerType, eventLoopGroup: EventLoopGroup) { + self.service = service + self.scheduler = scheduler + self.clientEventLoopGroup = eventLoopGroup + } + + public struct RuntimeRtkError: Error { + public let description: String + + init(_ description: String) { + self.description = description + } + } + + + public struct RtkError: Error { + public let code: Rtk.RtkResult.Result + public let description: String + } + + + + /** + RTCM data type + */ + public struct RtcmData: Equatable { + public let data: String + + + + /** + Initializes a new `RtcmData`. + + + - Parameter data: The data encoded as a string + + */ + public init(data: String) { + self.data = data + } + + internal var rpcRtcmData: Mavsdk_Rpc_Rtk_RtcmData { + var rpcRtcmData = Mavsdk_Rpc_Rtk_RtcmData() + + + rpcRtcmData.data = data + + + + return rpcRtcmData + } + + internal static func translateFromRpc(_ rpcRtcmData: Mavsdk_Rpc_Rtk_RtcmData) -> RtcmData { + return RtcmData(data: rpcRtcmData.data) + } + + public static func == (lhs: RtcmData, rhs: RtcmData) -> Bool { + return lhs.data == rhs.data + } + } + + /** + + */ + public struct RtkResult: Equatable { + public let result: Result + public let resultStr: String + + + + + /** + Possible results returned for rtk requests. + */ + public enum Result: Equatable { + /// Unknown result. + case unknown + /// Request succeeded. + case success + /// Passed data is too long. + case tooLong + /// No system connected. + case noSystem + /// Connection error. + case connectionError + case UNRECOGNIZED(Int) + + internal var rpcResult: Mavsdk_Rpc_Rtk_RtkResult.Result { + switch self { + case .unknown: + return .unknown + case .success: + return .success + case .tooLong: + return .tooLong + case .noSystem: + return .noSystem + case .connectionError: + return .connectionError + case .UNRECOGNIZED(let i): + return .UNRECOGNIZED(i) + } + } + + internal static func translateFromRpc(_ rpcResult: Mavsdk_Rpc_Rtk_RtkResult.Result) -> Result { + switch rpcResult { + case .unknown: + return .unknown + case .success: + return .success + case .tooLong: + return .tooLong + case .noSystem: + return .noSystem + case .connectionError: + return .connectionError + case .UNRECOGNIZED(let i): + return .UNRECOGNIZED(i) + } + } + } + + + /** + Initializes a new `RtkResult`. + + + - Parameters: + + - result: Result enum value + + - resultStr: Human-readable English string describing the result + + + */ + public init(result: Result, resultStr: String) { + self.result = result + self.resultStr = resultStr + } + + internal var rpcRtkResult: Mavsdk_Rpc_Rtk_RtkResult { + var rpcRtkResult = Mavsdk_Rpc_Rtk_RtkResult() + + + rpcRtkResult.result = result.rpcResult + + + + + rpcRtkResult.resultStr = resultStr + + + + return rpcRtkResult + } + + internal static func translateFromRpc(_ rpcRtkResult: Mavsdk_Rpc_Rtk_RtkResult) -> RtkResult { + return RtkResult(result: Result.translateFromRpc(rpcRtkResult.result), resultStr: rpcRtkResult.resultStr) + } + + public static func == (lhs: RtkResult, rhs: RtkResult) -> Bool { + return lhs.result == rhs.result + && lhs.resultStr == rhs.resultStr + } + } + + + /** + Send RTCM data. + + - Parameter rtcmData: The data + + */ + public func sendRtcmData(rtcmData: RtcmData) -> Completable { + return Completable.create { completable in + var request = Mavsdk_Rpc_Rtk_SendRtcmDataRequest() + + + + request.rtcmData = rtcmData.rpcRtcmData + + + + do { + + let response = self.service.sendRtcmData(request) + + let result = try response.response.wait().rtkResult + if (result.result == Mavsdk_Rpc_Rtk_RtkResult.Result.success) { + completable(.completed) + } else { + completable(.error(RtkError(code: RtkResult.Result.translateFromRpc(result.result), description: result.resultStr))) + } + + } catch { + completable(.error(error)) + } + + return Disposables.create() + } + } +} \ No newline at end of file diff --git a/Sources/Mavsdk/Generated/action.pb.swift b/Sources/Mavsdk/Generated/action.pb.swift index 1fd6cb2..0ee789d 100644 --- a/Sources/Mavsdk/Generated/action.pb.swift +++ b/Sources/Mavsdk/Generated/action.pb.swift @@ -72,7 +72,7 @@ enum Mavsdk_Rpc_Action_OrbitYawBehavior: SwiftProtobuf.Enum { extension Mavsdk_Rpc_Action_OrbitYawBehavior: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Action_OrbitYawBehavior] = [ + static let allCases: [Mavsdk_Rpc_Action_OrbitYawBehavior] = [ .holdFrontToCircleCenter, .holdInitialHeading, .uncontrolled, @@ -931,7 +931,7 @@ struct Mavsdk_Rpc_Action_ActionResult { extension Mavsdk_Rpc_Action_ActionResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Action_ActionResult.Result] = [ + static let allCases: [Mavsdk_Rpc_Action_ActionResult.Result] = [ .unknown, .success, .noSystem, diff --git a/Sources/Mavsdk/Generated/action_server.pb.swift b/Sources/Mavsdk/Generated/action_server.pb.swift index e8a7c7f..eb29b19 100644 --- a/Sources/Mavsdk/Generated/action_server.pb.swift +++ b/Sources/Mavsdk/Generated/action_server.pb.swift @@ -121,7 +121,7 @@ enum Mavsdk_Rpc_ActionServer_FlightMode: SwiftProtobuf.Enum { extension Mavsdk_Rpc_ActionServer_FlightMode: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_ActionServer_FlightMode] = [ + static let allCases: [Mavsdk_Rpc_ActionServer_FlightMode] = [ .unknown, .ready, .takeoff, @@ -708,7 +708,7 @@ struct Mavsdk_Rpc_ActionServer_ActionServerResult { extension Mavsdk_Rpc_ActionServer_ActionServerResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_ActionServer_ActionServerResult.Result] = [ + static let allCases: [Mavsdk_Rpc_ActionServer_ActionServerResult.Result] = [ .unknown, .success, .noSystem, diff --git a/Sources/Mavsdk/Generated/calibration.pb.swift b/Sources/Mavsdk/Generated/calibration.pb.swift index 10099f1..93918ad 100644 --- a/Sources/Mavsdk/Generated/calibration.pb.swift +++ b/Sources/Mavsdk/Generated/calibration.pb.swift @@ -365,7 +365,7 @@ struct Mavsdk_Rpc_Calibration_CalibrationResult { extension Mavsdk_Rpc_Calibration_CalibrationResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Calibration_CalibrationResult.Result] = [ + static let allCases: [Mavsdk_Rpc_Calibration_CalibrationResult.Result] = [ .unknown, .success, .next, diff --git a/Sources/Mavsdk/Generated/camera.pb.swift b/Sources/Mavsdk/Generated/camera.pb.swift index d3ce708..a45ae98 100644 --- a/Sources/Mavsdk/Generated/camera.pb.swift +++ b/Sources/Mavsdk/Generated/camera.pb.swift @@ -62,7 +62,7 @@ enum Mavsdk_Rpc_Camera_Mode: SwiftProtobuf.Enum { extension Mavsdk_Rpc_Camera_Mode: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Camera_Mode] = [ + static let allCases: [Mavsdk_Rpc_Camera_Mode] = [ .unknown, .photo, .video, @@ -108,7 +108,7 @@ enum Mavsdk_Rpc_Camera_PhotosRange: SwiftProtobuf.Enum { extension Mavsdk_Rpc_Camera_PhotosRange: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Camera_PhotosRange] = [ + static let allCases: [Mavsdk_Rpc_Camera_PhotosRange] = [ .all, .sinceConnection, ] @@ -886,7 +886,7 @@ struct Mavsdk_Rpc_Camera_CameraResult { extension Mavsdk_Rpc_Camera_CameraResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Camera_CameraResult.Result] = [ + static let allCases: [Mavsdk_Rpc_Camera_CameraResult.Result] = [ .unknown, .success, .inProgress, @@ -1174,7 +1174,7 @@ struct Mavsdk_Rpc_Camera_VideoStreamInfo { extension Mavsdk_Rpc_Camera_VideoStreamInfo.VideoStreamStatus: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Camera_VideoStreamInfo.VideoStreamStatus] = [ + static let allCases: [Mavsdk_Rpc_Camera_VideoStreamInfo.VideoStreamStatus] = [ .notRunning, .inProgress, ] @@ -1182,7 +1182,7 @@ extension Mavsdk_Rpc_Camera_VideoStreamInfo.VideoStreamStatus: CaseIterable { extension Mavsdk_Rpc_Camera_VideoStreamInfo.VideoStreamSpectrum: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Camera_VideoStreamInfo.VideoStreamSpectrum] = [ + static let allCases: [Mavsdk_Rpc_Camera_VideoStreamInfo.VideoStreamSpectrum] = [ .unknown, .visibleLight, .infrared, @@ -1332,7 +1332,7 @@ struct Mavsdk_Rpc_Camera_Status { extension Mavsdk_Rpc_Camera_Status.StorageStatus: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Camera_Status.StorageStatus] = [ + static let allCases: [Mavsdk_Rpc_Camera_Status.StorageStatus] = [ .notAvailable, .unformatted, .formatted, @@ -1342,7 +1342,7 @@ extension Mavsdk_Rpc_Camera_Status.StorageStatus: CaseIterable { extension Mavsdk_Rpc_Camera_Status.StorageType: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Camera_Status.StorageType] = [ + static let allCases: [Mavsdk_Rpc_Camera_Status.StorageType] = [ .unknown, .usbStick, .sd, diff --git a/Sources/Mavsdk/Generated/component_information.pb.swift b/Sources/Mavsdk/Generated/component_information.pb.swift index 538ced5..14a5c31 100644 --- a/Sources/Mavsdk/Generated/component_information.pb.swift +++ b/Sources/Mavsdk/Generated/component_information.pb.swift @@ -200,7 +200,7 @@ struct Mavsdk_Rpc_ComponentInformation_ComponentInformationResult { extension Mavsdk_Rpc_ComponentInformation_ComponentInformationResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_ComponentInformation_ComponentInformationResult.Result] = [ + static let allCases: [Mavsdk_Rpc_ComponentInformation_ComponentInformationResult.Result] = [ .unknown, .success, .noSystem, diff --git a/Sources/Mavsdk/Generated/component_information_server.pb.swift b/Sources/Mavsdk/Generated/component_information_server.pb.swift index 95fbcde..f8b33f6 100644 --- a/Sources/Mavsdk/Generated/component_information_server.pb.swift +++ b/Sources/Mavsdk/Generated/component_information_server.pb.swift @@ -229,7 +229,7 @@ struct Mavsdk_Rpc_ComponentInformationServer_ComponentInformationServerResult { extension Mavsdk_Rpc_ComponentInformationServer_ComponentInformationServerResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_ComponentInformationServer_ComponentInformationServerResult.Result] = [ + static let allCases: [Mavsdk_Rpc_ComponentInformationServer_ComponentInformationServerResult.Result] = [ .unknown, .success, .duplicateParam, diff --git a/Sources/Mavsdk/Generated/failure.pb.swift b/Sources/Mavsdk/Generated/failure.pb.swift index abc98b2..b90c1f7 100644 --- a/Sources/Mavsdk/Generated/failure.pb.swift +++ b/Sources/Mavsdk/Generated/failure.pb.swift @@ -122,7 +122,7 @@ enum Mavsdk_Rpc_Failure_FailureUnit: SwiftProtobuf.Enum { extension Mavsdk_Rpc_Failure_FailureUnit: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Failure_FailureUnit] = [ + static let allCases: [Mavsdk_Rpc_Failure_FailureUnit] = [ .sensorGyro, .sensorAccel, .sensorMag, @@ -210,7 +210,7 @@ enum Mavsdk_Rpc_Failure_FailureType: SwiftProtobuf.Enum { extension Mavsdk_Rpc_Failure_FailureType: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Failure_FailureType] = [ + static let allCases: [Mavsdk_Rpc_Failure_FailureType] = [ .ok, .off, .stuck, @@ -347,7 +347,7 @@ struct Mavsdk_Rpc_Failure_FailureResult { extension Mavsdk_Rpc_Failure_FailureResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Failure_FailureResult.Result] = [ + static let allCases: [Mavsdk_Rpc_Failure_FailureResult.Result] = [ .unknown, .success, .noSystem, diff --git a/Sources/Mavsdk/Generated/follow_me.pb.swift b/Sources/Mavsdk/Generated/follow_me.pb.swift index ece97fd..bf67a69 100644 --- a/Sources/Mavsdk/Generated/follow_me.pb.swift +++ b/Sources/Mavsdk/Generated/follow_me.pb.swift @@ -95,7 +95,7 @@ struct Mavsdk_Rpc_FollowMe_Config { extension Mavsdk_Rpc_FollowMe_Config.FollowDirection: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_FollowMe_Config.FollowDirection] = [ + static let allCases: [Mavsdk_Rpc_FollowMe_Config.FollowDirection] = [ .none, .behind, .front, @@ -458,7 +458,7 @@ struct Mavsdk_Rpc_FollowMe_FollowMeResult { extension Mavsdk_Rpc_FollowMe_FollowMeResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_FollowMe_FollowMeResult.Result] = [ + static let allCases: [Mavsdk_Rpc_FollowMe_FollowMeResult.Result] = [ .unknown, .success, .noSystem, diff --git a/Sources/Mavsdk/Generated/ftp.pb.swift b/Sources/Mavsdk/Generated/ftp.pb.swift index 3301651..d5e2c29 100644 --- a/Sources/Mavsdk/Generated/ftp.pb.swift +++ b/Sources/Mavsdk/Generated/ftp.pb.swift @@ -580,7 +580,7 @@ struct Mavsdk_Rpc_Ftp_FtpResult { extension Mavsdk_Rpc_Ftp_FtpResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Ftp_FtpResult.Result] = [ + static let allCases: [Mavsdk_Rpc_Ftp_FtpResult.Result] = [ .unknown, .success, .next, diff --git a/Sources/Mavsdk/Generated/geofence.pb.swift b/Sources/Mavsdk/Generated/geofence.pb.swift index 7366ac9..6ee1788 100644 --- a/Sources/Mavsdk/Generated/geofence.pb.swift +++ b/Sources/Mavsdk/Generated/geofence.pb.swift @@ -91,7 +91,7 @@ struct Mavsdk_Rpc_Geofence_Polygon { extension Mavsdk_Rpc_Geofence_Polygon.FenceType: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Geofence_Polygon.FenceType] = [ + static let allCases: [Mavsdk_Rpc_Geofence_Polygon.FenceType] = [ .inclusion, .exclusion, ] @@ -248,7 +248,7 @@ struct Mavsdk_Rpc_Geofence_GeofenceResult { extension Mavsdk_Rpc_Geofence_GeofenceResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Geofence_GeofenceResult.Result] = [ + static let allCases: [Mavsdk_Rpc_Geofence_GeofenceResult.Result] = [ .unknown, .success, .error, diff --git a/Sources/Mavsdk/Generated/gimbal.pb.swift b/Sources/Mavsdk/Generated/gimbal.pb.swift index 96e317e..c51df96 100644 --- a/Sources/Mavsdk/Generated/gimbal.pb.swift +++ b/Sources/Mavsdk/Generated/gimbal.pb.swift @@ -57,7 +57,7 @@ enum Mavsdk_Rpc_Gimbal_GimbalMode: SwiftProtobuf.Enum { extension Mavsdk_Rpc_Gimbal_GimbalMode: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Gimbal_GimbalMode] = [ + static let allCases: [Mavsdk_Rpc_Gimbal_GimbalMode] = [ .yawFollow, .yawLock, ] @@ -107,7 +107,7 @@ enum Mavsdk_Rpc_Gimbal_ControlMode: SwiftProtobuf.Enum { extension Mavsdk_Rpc_Gimbal_ControlMode: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Gimbal_ControlMode] = [ + static let allCases: [Mavsdk_Rpc_Gimbal_ControlMode] = [ .none, .primary, .secondary, @@ -461,7 +461,7 @@ 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] = [ + static let allCases: [Mavsdk_Rpc_Gimbal_GimbalResult.Result] = [ .unknown, .success, .error, diff --git a/Sources/Mavsdk/Generated/info.pb.swift b/Sources/Mavsdk/Generated/info.pb.swift index 76d4711..ccb0ffd 100644 --- a/Sources/Mavsdk/Generated/info.pb.swift +++ b/Sources/Mavsdk/Generated/info.pb.swift @@ -387,7 +387,7 @@ struct Mavsdk_Rpc_Info_InfoResult { extension Mavsdk_Rpc_Info_InfoResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Info_InfoResult.Result] = [ + static let allCases: [Mavsdk_Rpc_Info_InfoResult.Result] = [ .unknown, .success, .informationNotReceivedYet, diff --git a/Sources/Mavsdk/Generated/log_files.pb.swift b/Sources/Mavsdk/Generated/log_files.pb.swift index e7080f5..a3ca15a 100644 --- a/Sources/Mavsdk/Generated/log_files.pb.swift +++ b/Sources/Mavsdk/Generated/log_files.pb.swift @@ -286,7 +286,7 @@ struct Mavsdk_Rpc_LogFiles_LogFilesResult { extension Mavsdk_Rpc_LogFiles_LogFilesResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_LogFiles_LogFilesResult.Result] = [ + static let allCases: [Mavsdk_Rpc_LogFiles_LogFilesResult.Result] = [ .unknown, .success, .next, diff --git a/Sources/Mavsdk/Generated/manual_control.pb.swift b/Sources/Mavsdk/Generated/manual_control.pb.swift index be496d6..217622c 100644 --- a/Sources/Mavsdk/Generated/manual_control.pb.swift +++ b/Sources/Mavsdk/Generated/manual_control.pb.swift @@ -214,7 +214,7 @@ struct Mavsdk_Rpc_ManualControl_ManualControlResult { extension Mavsdk_Rpc_ManualControl_ManualControlResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_ManualControl_ManualControlResult.Result] = [ + static let allCases: [Mavsdk_Rpc_ManualControl_ManualControlResult.Result] = [ .unknown, .success, .noSystem, diff --git a/Sources/Mavsdk/Generated/mission.pb.swift b/Sources/Mavsdk/Generated/mission.pb.swift index e04dba7..6096c6d 100644 --- a/Sources/Mavsdk/Generated/mission.pb.swift +++ b/Sources/Mavsdk/Generated/mission.pb.swift @@ -647,7 +647,7 @@ struct Mavsdk_Rpc_Mission_MissionItem { extension Mavsdk_Rpc_Mission_MissionItem.CameraAction: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Mission_MissionItem.CameraAction] = [ + static let allCases: [Mavsdk_Rpc_Mission_MissionItem.CameraAction] = [ .none, .takePhoto, .startPhotoInterval, @@ -801,7 +801,7 @@ struct Mavsdk_Rpc_Mission_MissionResult { extension Mavsdk_Rpc_Mission_MissionResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Mission_MissionResult.Result] = [ + static let allCases: [Mavsdk_Rpc_Mission_MissionResult.Result] = [ .unknown, .success, .error, diff --git a/Sources/Mavsdk/Generated/mission_raw.pb.swift b/Sources/Mavsdk/Generated/mission_raw.pb.swift index 6a0f97a..89cc2be 100644 --- a/Sources/Mavsdk/Generated/mission_raw.pb.swift +++ b/Sources/Mavsdk/Generated/mission_raw.pb.swift @@ -573,7 +573,7 @@ struct Mavsdk_Rpc_MissionRaw_MissionRawResult { extension Mavsdk_Rpc_MissionRaw_MissionRawResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_MissionRaw_MissionRawResult.Result] = [ + static let allCases: [Mavsdk_Rpc_MissionRaw_MissionRawResult.Result] = [ .unknown, .success, .error, diff --git a/Sources/Mavsdk/Generated/mission_raw_server.pb.swift b/Sources/Mavsdk/Generated/mission_raw_server.pb.swift index 28b8669..0f7e4fa 100644 --- a/Sources/Mavsdk/Generated/mission_raw_server.pb.swift +++ b/Sources/Mavsdk/Generated/mission_raw_server.pb.swift @@ -325,7 +325,7 @@ struct Mavsdk_Rpc_MissionRawServer_MissionRawServerResult { extension Mavsdk_Rpc_MissionRawServer_MissionRawServerResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_MissionRawServer_MissionRawServerResult.Result] = [ + static let allCases: [Mavsdk_Rpc_MissionRawServer_MissionRawServerResult.Result] = [ .unknown, .success, .error, diff --git a/Sources/Mavsdk/Generated/mocap.pb.swift b/Sources/Mavsdk/Generated/mocap.pb.swift index 2c88073..40ea886 100644 --- a/Sources/Mavsdk/Generated/mocap.pb.swift +++ b/Sources/Mavsdk/Generated/mocap.pb.swift @@ -495,7 +495,7 @@ struct Mavsdk_Rpc_Mocap_Odometry { extension Mavsdk_Rpc_Mocap_Odometry.MavFrame: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Mocap_Odometry.MavFrame] = [ + static let allCases: [Mavsdk_Rpc_Mocap_Odometry.MavFrame] = [ .mocapNed, .localFrd, ] @@ -577,7 +577,7 @@ struct Mavsdk_Rpc_Mocap_MocapResult { extension Mavsdk_Rpc_Mocap_MocapResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Mocap_MocapResult.Result] = [ + static let allCases: [Mavsdk_Rpc_Mocap_MocapResult.Result] = [ .unknown, .success, .noSystem, diff --git a/Sources/Mavsdk/Generated/offboard.pb.swift b/Sources/Mavsdk/Generated/offboard.pb.swift index 96c9855..aa5f01f 100644 --- a/Sources/Mavsdk/Generated/offboard.pb.swift +++ b/Sources/Mavsdk/Generated/offboard.pb.swift @@ -685,7 +685,7 @@ struct Mavsdk_Rpc_Offboard_PositionGlobalYaw { extension Mavsdk_Rpc_Offboard_PositionGlobalYaw.AltitudeType: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Offboard_PositionGlobalYaw.AltitudeType] = [ + static let allCases: [Mavsdk_Rpc_Offboard_PositionGlobalYaw.AltitudeType] = [ .relHome, .amsl, .agl, @@ -844,7 +844,7 @@ struct Mavsdk_Rpc_Offboard_OffboardResult { extension Mavsdk_Rpc_Offboard_OffboardResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Offboard_OffboardResult.Result] = [ + static let allCases: [Mavsdk_Rpc_Offboard_OffboardResult.Result] = [ .unknown, .success, .noSystem, diff --git a/Sources/Mavsdk/Generated/param.grpc.swift b/Sources/Mavsdk/Generated/param.grpc.swift index febe2a0..f8e2687 100644 --- a/Sources/Mavsdk/Generated/param.grpc.swift +++ b/Sources/Mavsdk/Generated/param.grpc.swift @@ -52,6 +52,16 @@ internal protocol Mavsdk_Rpc_Param_ParamServiceClientProtocol: GRPCClient { callOptions: CallOptions? ) -> UnaryCall + func getParamCustom( + _ request: Mavsdk_Rpc_Param_GetParamCustomRequest, + callOptions: CallOptions? + ) -> UnaryCall + + func setParamCustom( + _ request: Mavsdk_Rpc_Param_SetParamCustomRequest, + callOptions: CallOptions? + ) -> UnaryCall + func getAllParams( _ request: Mavsdk_Rpc_Param_GetAllParamsRequest, callOptions: CallOptions? @@ -147,6 +157,48 @@ extension Mavsdk_Rpc_Param_ParamServiceClientProtocol { ) } + /// + /// Get a custom parameter. + /// + /// If the type is wrong, the result will be `WRONG_TYPE`. + /// + /// - Parameters: + /// - request: Request to send to GetParamCustom. + /// - callOptions: Call options. + /// - Returns: A `UnaryCall` with futures for the metadata, status and response. + internal func getParamCustom( + _ request: Mavsdk_Rpc_Param_GetParamCustomRequest, + callOptions: CallOptions? = nil + ) -> UnaryCall { + return self.makeUnaryCall( + path: "/mavsdk.rpc.param.ParamService/GetParamCustom", + request: request, + callOptions: callOptions ?? self.defaultCallOptions, + interceptors: self.interceptors?.makeGetParamCustomInterceptors() ?? [] + ) + } + + /// + /// Set a custom parameter. + /// + /// If the type is wrong, the result will be `WRONG_TYPE`. + /// + /// - Parameters: + /// - request: Request to send to SetParamCustom. + /// - callOptions: Call options. + /// - Returns: A `UnaryCall` with futures for the metadata, status and response. + internal func setParamCustom( + _ request: Mavsdk_Rpc_Param_SetParamCustomRequest, + callOptions: CallOptions? = nil + ) -> UnaryCall { + return self.makeUnaryCall( + path: "/mavsdk.rpc.param.ParamService/SetParamCustom", + request: request, + callOptions: callOptions ?? self.defaultCallOptions, + interceptors: self.interceptors?.makeSetParamCustomInterceptors() ?? [] + ) + } + /// /// Get all parameters. /// @@ -181,6 +233,12 @@ internal protocol Mavsdk_Rpc_Param_ParamServiceClientInterceptorFactoryProtocol /// - Returns: Interceptors to use when invoking 'setParamFloat'. func makeSetParamFloatInterceptors() -> [ClientInterceptor] + /// - Returns: Interceptors to use when invoking 'getParamCustom'. + func makeGetParamCustomInterceptors() -> [ClientInterceptor] + + /// - Returns: Interceptors to use when invoking 'setParamCustom'. + func makeSetParamCustomInterceptors() -> [ClientInterceptor] + /// - Returns: Interceptors to use when invoking 'getAllParams'. func makeGetAllParamsInterceptors() -> [ClientInterceptor] } @@ -237,6 +295,18 @@ internal protocol Mavsdk_Rpc_Param_ParamServiceProvider: CallHandlerProvider { /// If the type is wrong, the result will be `WRONG_TYPE`. func setParamFloat(request: Mavsdk_Rpc_Param_SetParamFloatRequest, context: StatusOnlyCallContext) -> EventLoopFuture + /// + /// Get a custom parameter. + /// + /// If the type is wrong, the result will be `WRONG_TYPE`. + func getParamCustom(request: Mavsdk_Rpc_Param_GetParamCustomRequest, context: StatusOnlyCallContext) -> EventLoopFuture + + /// + /// Set a custom parameter. + /// + /// If the type is wrong, the result will be `WRONG_TYPE`. + func setParamCustom(request: Mavsdk_Rpc_Param_SetParamCustomRequest, context: StatusOnlyCallContext) -> EventLoopFuture + /// /// Get all parameters. func getAllParams(request: Mavsdk_Rpc_Param_GetAllParamsRequest, context: StatusOnlyCallContext) -> EventLoopFuture @@ -288,6 +358,24 @@ extension Mavsdk_Rpc_Param_ParamServiceProvider { userFunction: self.setParamFloat(request:context:) ) + case "GetParamCustom": + return UnaryServerHandler( + context: context, + requestDeserializer: ProtobufDeserializer(), + responseSerializer: ProtobufSerializer(), + interceptors: self.interceptors?.makeGetParamCustomInterceptors() ?? [], + userFunction: self.getParamCustom(request:context:) + ) + + case "SetParamCustom": + return UnaryServerHandler( + context: context, + requestDeserializer: ProtobufDeserializer(), + responseSerializer: ProtobufSerializer(), + interceptors: self.interceptors?.makeSetParamCustomInterceptors() ?? [], + userFunction: self.setParamCustom(request:context:) + ) + case "GetAllParams": return UnaryServerHandler( context: context, @@ -321,6 +409,14 @@ internal protocol Mavsdk_Rpc_Param_ParamServiceServerInterceptorFactoryProtocol /// Defaults to calling `self.makeInterceptors()`. func makeSetParamFloatInterceptors() -> [ServerInterceptor] + /// - Returns: Interceptors to use when handling 'getParamCustom'. + /// Defaults to calling `self.makeInterceptors()`. + func makeGetParamCustomInterceptors() -> [ServerInterceptor] + + /// - Returns: Interceptors to use when handling 'setParamCustom'. + /// Defaults to calling `self.makeInterceptors()`. + func makeSetParamCustomInterceptors() -> [ServerInterceptor] + /// - Returns: Interceptors to use when handling 'getAllParams'. /// Defaults to calling `self.makeInterceptors()`. func makeGetAllParamsInterceptors() -> [ServerInterceptor] diff --git a/Sources/Mavsdk/Generated/param.pb.swift b/Sources/Mavsdk/Generated/param.pb.swift index 8a4bc6c..f0ec166 100644 --- a/Sources/Mavsdk/Generated/param.pb.swift +++ b/Sources/Mavsdk/Generated/param.pb.swift @@ -168,6 +168,80 @@ struct Mavsdk_Rpc_Param_SetParamFloatResponse { fileprivate var _paramResult: Mavsdk_Rpc_Param_ParamResult? = nil } +struct Mavsdk_Rpc_Param_GetParamCustomRequest { + // 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 parameter + var name: String = String() + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} +} + +struct Mavsdk_Rpc_Param_GetParamCustomResponse { + // 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 paramResult: Mavsdk_Rpc_Param_ParamResult { + get {return _paramResult ?? Mavsdk_Rpc_Param_ParamResult()} + set {_paramResult = newValue} + } + /// Returns true if `paramResult` has been explicitly set. + var hasParamResult: Bool {return self._paramResult != nil} + /// Clears the value of `paramResult`. Subsequent reads from it will return its default value. + mutating func clearParamResult() {self._paramResult = nil} + + /// Value of the requested parameter + var value: String = String() + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} + + fileprivate var _paramResult: Mavsdk_Rpc_Param_ParamResult? = nil +} + +struct Mavsdk_Rpc_Param_SetParamCustomRequest { + // 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 parameter to set + var name: String = String() + + /// Value the parameter should be set to + var value: String = String() + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} +} + +struct Mavsdk_Rpc_Param_SetParamCustomResponse { + // 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 paramResult: Mavsdk_Rpc_Param_ParamResult { + get {return _paramResult ?? Mavsdk_Rpc_Param_ParamResult()} + set {_paramResult = newValue} + } + /// Returns true if `paramResult` has been explicitly set. + var hasParamResult: Bool {return self._paramResult != nil} + /// Clears the value of `paramResult`. Subsequent reads from it will return its default value. + mutating func clearParamResult() {self._paramResult = nil} + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} + + fileprivate var _paramResult: Mavsdk_Rpc_Param_ParamResult? = nil +} + struct Mavsdk_Rpc_Param_GetAllParamsRequest { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for @@ -237,7 +311,25 @@ struct Mavsdk_Rpc_Param_FloatParam { } /// -/// Type collecting all integer and float parameters. +/// Type for custom parameters +struct Mavsdk_Rpc_Param_CustomParam { + // 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 parameter + var name: String = String() + + /// Value of the parameter (max len 128 bytes) + var value: String = String() + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} +} + +/// +/// Type collecting all integer, float, and custom parameters. struct Mavsdk_Rpc_Param_AllParams { // SwiftProtobuf.Message conformance is added in an extension below. See the // `Message` and `Message+*Additions` files in the SwiftProtobuf library for @@ -249,6 +341,9 @@ struct Mavsdk_Rpc_Param_AllParams { /// Collection of all parameter names and values of type float var floatParams: [Mavsdk_Rpc_Param_FloatParam] = [] + /// Collection of all parameter names and values of type custom + var customParams: [Mavsdk_Rpc_Param_CustomParam] = [] + var unknownFields = SwiftProtobuf.UnknownStorage() init() {} @@ -292,6 +387,9 @@ struct Mavsdk_Rpc_Param_ParamResult { /// No system connected case noSystem // = 6 + + /// Param value too long (> 128) + case paramValueTooLong // = 7 case UNRECOGNIZED(Int) init() { @@ -307,6 +405,7 @@ struct Mavsdk_Rpc_Param_ParamResult { case 4: self = .wrongType case 5: self = .paramNameTooLong case 6: self = .noSystem + case 7: self = .paramValueTooLong default: self = .UNRECOGNIZED(rawValue) } } @@ -320,6 +419,7 @@ struct Mavsdk_Rpc_Param_ParamResult { case .wrongType: return 4 case .paramNameTooLong: return 5 case .noSystem: return 6 + case .paramValueTooLong: return 7 case .UNRECOGNIZED(let i): return i } } @@ -333,7 +433,7 @@ struct Mavsdk_Rpc_Param_ParamResult { extension Mavsdk_Rpc_Param_ParamResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Param_ParamResult.Result] = [ + static let allCases: [Mavsdk_Rpc_Param_ParamResult.Result] = [ .unknown, .success, .timeout, @@ -341,6 +441,7 @@ extension Mavsdk_Rpc_Param_ParamResult.Result: CaseIterable { .wrongType, .paramNameTooLong, .noSystem, + .paramValueTooLong, ] } @@ -355,10 +456,15 @@ extension Mavsdk_Rpc_Param_GetParamFloatRequest: @unchecked Sendable {} extension Mavsdk_Rpc_Param_GetParamFloatResponse: @unchecked Sendable {} extension Mavsdk_Rpc_Param_SetParamFloatRequest: @unchecked Sendable {} extension Mavsdk_Rpc_Param_SetParamFloatResponse: @unchecked Sendable {} +extension Mavsdk_Rpc_Param_GetParamCustomRequest: @unchecked Sendable {} +extension Mavsdk_Rpc_Param_GetParamCustomResponse: @unchecked Sendable {} +extension Mavsdk_Rpc_Param_SetParamCustomRequest: @unchecked Sendable {} +extension Mavsdk_Rpc_Param_SetParamCustomResponse: @unchecked Sendable {} extension Mavsdk_Rpc_Param_GetAllParamsRequest: @unchecked Sendable {} extension Mavsdk_Rpc_Param_GetAllParamsResponse: @unchecked Sendable {} extension Mavsdk_Rpc_Param_IntParam: @unchecked Sendable {} extension Mavsdk_Rpc_Param_FloatParam: @unchecked Sendable {} +extension Mavsdk_Rpc_Param_CustomParam: @unchecked Sendable {} extension Mavsdk_Rpc_Param_AllParams: @unchecked Sendable {} extension Mavsdk_Rpc_Param_ParamResult: @unchecked Sendable {} extension Mavsdk_Rpc_Param_ParamResult.Result: @unchecked Sendable {} @@ -664,6 +770,154 @@ extension Mavsdk_Rpc_Param_SetParamFloatResponse: SwiftProtobuf.Message, SwiftPr } } +extension Mavsdk_Rpc_Param_GetParamCustomRequest: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".GetParamCustomRequest" + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 1: .same(proto: "name"), + ] + + mutating func decodeMessage(decoder: inout D) throws { + while let fieldNumber = try decoder.nextFieldNumber() { + // The use of inline closures is to circumvent an issue where the compiler + // allocates stack space for every case branch when no optimizations are + // enabled. https://github.com/apple/swift-protobuf/issues/1034 + switch fieldNumber { + case 1: try { try decoder.decodeSingularStringField(value: &self.name) }() + default: break + } + } + } + + func traverse(visitor: inout V) throws { + if !self.name.isEmpty { + try visitor.visitSingularStringField(value: self.name, fieldNumber: 1) + } + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Param_GetParamCustomRequest, rhs: Mavsdk_Rpc_Param_GetParamCustomRequest) -> Bool { + if lhs.name != rhs.name {return false} + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + +extension Mavsdk_Rpc_Param_GetParamCustomResponse: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".GetParamCustomResponse" + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 1: .standard(proto: "param_result"), + 2: .same(proto: "value"), + ] + + mutating func decodeMessage(decoder: inout D) throws { + while let fieldNumber = try decoder.nextFieldNumber() { + // The use of inline closures is to circumvent an issue where the compiler + // allocates stack space for every case branch when no optimizations are + // enabled. https://github.com/apple/swift-protobuf/issues/1034 + switch fieldNumber { + case 1: try { try decoder.decodeSingularMessageField(value: &self._paramResult) }() + case 2: try { try decoder.decodeSingularStringField(value: &self.value) }() + default: break + } + } + } + + func traverse(visitor: inout V) throws { + // The use of inline closures is to circumvent an issue where the compiler + // allocates stack space for every if/case branch local when no optimizations + // are enabled. https://github.com/apple/swift-protobuf/issues/1034 and + // https://github.com/apple/swift-protobuf/issues/1182 + try { if let v = self._paramResult { + try visitor.visitSingularMessageField(value: v, fieldNumber: 1) + } }() + if !self.value.isEmpty { + try visitor.visitSingularStringField(value: self.value, fieldNumber: 2) + } + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Param_GetParamCustomResponse, rhs: Mavsdk_Rpc_Param_GetParamCustomResponse) -> Bool { + if lhs._paramResult != rhs._paramResult {return false} + if lhs.value != rhs.value {return false} + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + +extension Mavsdk_Rpc_Param_SetParamCustomRequest: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".SetParamCustomRequest" + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 1: .same(proto: "name"), + 2: .same(proto: "value"), + ] + + mutating func decodeMessage(decoder: inout D) throws { + while let fieldNumber = try decoder.nextFieldNumber() { + // The use of inline closures is to circumvent an issue where the compiler + // allocates stack space for every case branch when no optimizations are + // enabled. https://github.com/apple/swift-protobuf/issues/1034 + switch fieldNumber { + case 1: try { try decoder.decodeSingularStringField(value: &self.name) }() + case 2: try { try decoder.decodeSingularStringField(value: &self.value) }() + default: break + } + } + } + + func traverse(visitor: inout V) throws { + if !self.name.isEmpty { + try visitor.visitSingularStringField(value: self.name, fieldNumber: 1) + } + if !self.value.isEmpty { + try visitor.visitSingularStringField(value: self.value, fieldNumber: 2) + } + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Param_SetParamCustomRequest, rhs: Mavsdk_Rpc_Param_SetParamCustomRequest) -> Bool { + if lhs.name != rhs.name {return false} + if lhs.value != rhs.value {return false} + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + +extension Mavsdk_Rpc_Param_SetParamCustomResponse: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".SetParamCustomResponse" + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 1: .standard(proto: "param_result"), + ] + + mutating func decodeMessage(decoder: inout D) throws { + while let fieldNumber = try decoder.nextFieldNumber() { + // The use of inline closures is to circumvent an issue where the compiler + // allocates stack space for every case branch when no optimizations are + // enabled. https://github.com/apple/swift-protobuf/issues/1034 + switch fieldNumber { + case 1: try { try decoder.decodeSingularMessageField(value: &self._paramResult) }() + default: break + } + } + } + + func traverse(visitor: inout V) throws { + // The use of inline closures is to circumvent an issue where the compiler + // allocates stack space for every if/case branch local when no optimizations + // are enabled. https://github.com/apple/swift-protobuf/issues/1034 and + // https://github.com/apple/swift-protobuf/issues/1182 + try { if let v = self._paramResult { + try visitor.visitSingularMessageField(value: v, fieldNumber: 1) + } }() + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Param_SetParamCustomResponse, rhs: Mavsdk_Rpc_Param_SetParamCustomResponse) -> Bool { + if lhs._paramResult != rhs._paramResult {return false} + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + extension Mavsdk_Rpc_Param_GetAllParamsRequest: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { static let protoMessageName: String = _protobuf_package + ".GetAllParamsRequest" static let _protobuf_nameMap = SwiftProtobuf._NameMap() @@ -795,11 +1049,50 @@ extension Mavsdk_Rpc_Param_FloatParam: SwiftProtobuf.Message, SwiftProtobuf._Mes } } +extension Mavsdk_Rpc_Param_CustomParam: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".CustomParam" + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 1: .same(proto: "name"), + 2: .same(proto: "value"), + ] + + mutating func decodeMessage(decoder: inout D) throws { + while let fieldNumber = try decoder.nextFieldNumber() { + // The use of inline closures is to circumvent an issue where the compiler + // allocates stack space for every case branch when no optimizations are + // enabled. https://github.com/apple/swift-protobuf/issues/1034 + switch fieldNumber { + case 1: try { try decoder.decodeSingularStringField(value: &self.name) }() + case 2: try { try decoder.decodeSingularStringField(value: &self.value) }() + default: break + } + } + } + + func traverse(visitor: inout V) throws { + if !self.name.isEmpty { + try visitor.visitSingularStringField(value: self.name, fieldNumber: 1) + } + if !self.value.isEmpty { + try visitor.visitSingularStringField(value: self.value, fieldNumber: 2) + } + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Param_CustomParam, rhs: Mavsdk_Rpc_Param_CustomParam) -> Bool { + if lhs.name != rhs.name {return false} + if lhs.value != rhs.value {return false} + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + extension Mavsdk_Rpc_Param_AllParams: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { static let protoMessageName: String = _protobuf_package + ".AllParams" static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ 1: .standard(proto: "int_params"), 2: .standard(proto: "float_params"), + 3: .standard(proto: "custom_params"), ] mutating func decodeMessage(decoder: inout D) throws { @@ -810,6 +1103,7 @@ extension Mavsdk_Rpc_Param_AllParams: SwiftProtobuf.Message, SwiftProtobuf._Mess switch fieldNumber { case 1: try { try decoder.decodeRepeatedMessageField(value: &self.intParams) }() case 2: try { try decoder.decodeRepeatedMessageField(value: &self.floatParams) }() + case 3: try { try decoder.decodeRepeatedMessageField(value: &self.customParams) }() default: break } } @@ -822,12 +1116,16 @@ extension Mavsdk_Rpc_Param_AllParams: SwiftProtobuf.Message, SwiftProtobuf._Mess if !self.floatParams.isEmpty { try visitor.visitRepeatedMessageField(value: self.floatParams, fieldNumber: 2) } + if !self.customParams.isEmpty { + try visitor.visitRepeatedMessageField(value: self.customParams, fieldNumber: 3) + } try unknownFields.traverse(visitor: &visitor) } static func ==(lhs: Mavsdk_Rpc_Param_AllParams, rhs: Mavsdk_Rpc_Param_AllParams) -> Bool { if lhs.intParams != rhs.intParams {return false} if lhs.floatParams != rhs.floatParams {return false} + if lhs.customParams != rhs.customParams {return false} if lhs.unknownFields != rhs.unknownFields {return false} return true } @@ -880,5 +1178,6 @@ extension Mavsdk_Rpc_Param_ParamResult.Result: SwiftProtobuf._ProtoNameProviding 4: .same(proto: "RESULT_WRONG_TYPE"), 5: .same(proto: "RESULT_PARAM_NAME_TOO_LONG"), 6: .same(proto: "RESULT_NO_SYSTEM"), + 7: .same(proto: "RESULT_PARAM_VALUE_TOO_LONG"), ] } diff --git a/Sources/Mavsdk/Generated/rtk.grpc.swift b/Sources/Mavsdk/Generated/rtk.grpc.swift new file mode 100644 index 0000000..4f61f2a --- /dev/null +++ b/Sources/Mavsdk/Generated/rtk.grpc.swift @@ -0,0 +1,133 @@ +// +// DO NOT EDIT. +// +// Generated by the protocol buffer compiler. +// Source: rtk.proto +// + +// +// Copyright 2018, gRPC Authors All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +import GRPC +import NIO +import SwiftProtobuf + + +/// Service to send RTK corrections to the vehicle. +/// +/// Usage: instantiate `Mavsdk_Rpc_Rtk_RtkServiceClient`, then call methods of this protocol to make API calls. +internal protocol Mavsdk_Rpc_Rtk_RtkServiceClientProtocol: GRPCClient { + var serviceName: String { get } + var interceptors: Mavsdk_Rpc_Rtk_RtkServiceClientInterceptorFactoryProtocol? { get } + + func sendRtcmData( + _ request: Mavsdk_Rpc_Rtk_SendRtcmDataRequest, + callOptions: CallOptions? + ) -> UnaryCall +} + +extension Mavsdk_Rpc_Rtk_RtkServiceClientProtocol { + internal var serviceName: String { + return "mavsdk.rpc.rtk.RtkService" + } + + /// Send RTCM data. + /// + /// - Parameters: + /// - request: Request to send to SendRtcmData. + /// - callOptions: Call options. + /// - Returns: A `UnaryCall` with futures for the metadata, status and response. + internal func sendRtcmData( + _ request: Mavsdk_Rpc_Rtk_SendRtcmDataRequest, + callOptions: CallOptions? = nil + ) -> UnaryCall { + return self.makeUnaryCall( + path: "/mavsdk.rpc.rtk.RtkService/SendRtcmData", + request: request, + callOptions: callOptions ?? self.defaultCallOptions, + interceptors: self.interceptors?.makeSendRtcmDataInterceptors() ?? [] + ) + } +} + +internal protocol Mavsdk_Rpc_Rtk_RtkServiceClientInterceptorFactoryProtocol { + + /// - Returns: Interceptors to use when invoking 'sendRtcmData'. + func makeSendRtcmDataInterceptors() -> [ClientInterceptor] +} + +internal final class Mavsdk_Rpc_Rtk_RtkServiceClient: Mavsdk_Rpc_Rtk_RtkServiceClientProtocol { + internal let channel: GRPCChannel + internal var defaultCallOptions: CallOptions + internal var interceptors: Mavsdk_Rpc_Rtk_RtkServiceClientInterceptorFactoryProtocol? + + /// Creates a client for the mavsdk.rpc.rtk.RtkService service. + /// + /// - Parameters: + /// - channel: `GRPCChannel` to the service host. + /// - defaultCallOptions: Options to use for each service call if the user doesn't provide them. + /// - interceptors: A factory providing interceptors for each RPC. + internal init( + channel: GRPCChannel, + defaultCallOptions: CallOptions = CallOptions(), + interceptors: Mavsdk_Rpc_Rtk_RtkServiceClientInterceptorFactoryProtocol? = nil + ) { + self.channel = channel + self.defaultCallOptions = defaultCallOptions + self.interceptors = interceptors + } +} + +/// Service to send RTK corrections to the vehicle. +/// +/// To build a server, implement a class that conforms to this protocol. +internal protocol Mavsdk_Rpc_Rtk_RtkServiceProvider: CallHandlerProvider { + var interceptors: Mavsdk_Rpc_Rtk_RtkServiceServerInterceptorFactoryProtocol? { get } + + /// Send RTCM data. + func sendRtcmData(request: Mavsdk_Rpc_Rtk_SendRtcmDataRequest, context: StatusOnlyCallContext) -> EventLoopFuture +} + +extension Mavsdk_Rpc_Rtk_RtkServiceProvider { + internal var serviceName: Substring { return "mavsdk.rpc.rtk.RtkService" } + + /// Determines, calls and returns the appropriate request handler, depending on the request's method. + /// Returns nil for methods not handled by this service. + internal func handle( + method name: Substring, + context: CallHandlerContext + ) -> GRPCServerHandlerProtocol? { + switch name { + case "SendRtcmData": + return UnaryServerHandler( + context: context, + requestDeserializer: ProtobufDeserializer(), + responseSerializer: ProtobufSerializer(), + interceptors: self.interceptors?.makeSendRtcmDataInterceptors() ?? [], + userFunction: self.sendRtcmData(request:context:) + ) + + default: + return nil + } + } +} + +internal protocol Mavsdk_Rpc_Rtk_RtkServiceServerInterceptorFactoryProtocol { + + /// - Returns: Interceptors to use when handling 'sendRtcmData'. + /// Defaults to calling `self.makeInterceptors()`. + func makeSendRtcmDataInterceptors() -> [ServerInterceptor] +} diff --git a/Sources/Mavsdk/Generated/rtk.pb.swift b/Sources/Mavsdk/Generated/rtk.pb.swift new file mode 100644 index 0000000..e7cf1f9 --- /dev/null +++ b/Sources/Mavsdk/Generated/rtk.pb.swift @@ -0,0 +1,321 @@ +// DO NOT EDIT. +// swift-format-ignore-file +// +// Generated by the Swift generator plugin for the protocol buffer compiler. +// Source: rtk.proto +// +// For information on using the generated types, please see the documentation: +// https://github.com/apple/swift-protobuf/ + +import Foundation +import SwiftProtobuf + +// If the compiler emits an error on this type, it is because this file +// was generated by a version of the `protoc` Swift plug-in that is +// incompatible with the version of SwiftProtobuf to which you are linking. +// Please ensure that you are building against the same version of the API +// that was used to generate this file. +fileprivate struct _GeneratedWithProtocGenSwiftVersion: SwiftProtobuf.ProtobufAPIVersionCheck { + struct _2: SwiftProtobuf.ProtobufAPIVersion_2 {} + typealias Version = _2 +} + +/// RTCM data type +struct Mavsdk_Rpc_Rtk_RtcmData { + // 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 data encoded as a string + var data: String = String() + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} +} + +struct Mavsdk_Rpc_Rtk_SendRtcmDataRequest { + // 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 data + var rtcmData: Mavsdk_Rpc_Rtk_RtcmData { + get {return _rtcmData ?? Mavsdk_Rpc_Rtk_RtcmData()} + set {_rtcmData = newValue} + } + /// Returns true if `rtcmData` has been explicitly set. + var hasRtcmData: Bool {return self._rtcmData != nil} + /// Clears the value of `rtcmData`. Subsequent reads from it will return its default value. + mutating func clearRtcmData() {self._rtcmData = nil} + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} + + fileprivate var _rtcmData: Mavsdk_Rpc_Rtk_RtcmData? = nil +} + +struct Mavsdk_Rpc_Rtk_SendRtcmDataResponse { + // 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 rtkResult: Mavsdk_Rpc_Rtk_RtkResult { + get {return _rtkResult ?? Mavsdk_Rpc_Rtk_RtkResult()} + set {_rtkResult = newValue} + } + /// Returns true if `rtkResult` has been explicitly set. + var hasRtkResult: Bool {return self._rtkResult != nil} + /// Clears the value of `rtkResult`. Subsequent reads from it will return its default value. + mutating func clearRtkResult() {self._rtkResult = nil} + + var unknownFields = SwiftProtobuf.UnknownStorage() + + init() {} + + fileprivate var _rtkResult: Mavsdk_Rpc_Rtk_RtkResult? = nil +} + +struct Mavsdk_Rpc_Rtk_RtkResult { + // 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_Rtk_RtkResult.Result = .unknown + + /// Human-readable English string describing the result + var resultStr: String = String() + + var unknownFields = SwiftProtobuf.UnknownStorage() + + /// Possible results returned for rtk requests. + enum Result: SwiftProtobuf.Enum { + typealias RawValue = Int + + /// Unknown result + case unknown // = 0 + + /// Request succeeded + case success // = 1 + + /// Passed data is too long + case tooLong // = 2 + + /// No system connected + case noSystem // = 5 + + /// Connection error + case connectionError // = 6 + case UNRECOGNIZED(Int) + + init() { + self = .unknown + } + + init?(rawValue: Int) { + switch rawValue { + case 0: self = .unknown + case 1: self = .success + case 2: self = .tooLong + case 5: self = .noSystem + case 6: self = .connectionError + default: self = .UNRECOGNIZED(rawValue) + } + } + + var rawValue: Int { + switch self { + case .unknown: return 0 + case .success: return 1 + case .tooLong: return 2 + case .noSystem: return 5 + case .connectionError: return 6 + case .UNRECOGNIZED(let i): return i + } + } + + } + + init() {} +} + +#if swift(>=4.2) + +extension Mavsdk_Rpc_Rtk_RtkResult.Result: CaseIterable { + // The compiler won't synthesize support with the UNRECOGNIZED case. + static let allCases: [Mavsdk_Rpc_Rtk_RtkResult.Result] = [ + .unknown, + .success, + .tooLong, + .noSystem, + .connectionError, + ] +} + +#endif // swift(>=4.2) + +#if swift(>=5.5) && canImport(_Concurrency) +extension Mavsdk_Rpc_Rtk_RtcmData: @unchecked Sendable {} +extension Mavsdk_Rpc_Rtk_SendRtcmDataRequest: @unchecked Sendable {} +extension Mavsdk_Rpc_Rtk_SendRtcmDataResponse: @unchecked Sendable {} +extension Mavsdk_Rpc_Rtk_RtkResult: @unchecked Sendable {} +extension Mavsdk_Rpc_Rtk_RtkResult.Result: @unchecked Sendable {} +#endif // swift(>=5.5) && canImport(_Concurrency) + +// MARK: - Code below here is support for the SwiftProtobuf runtime. + +fileprivate let _protobuf_package = "mavsdk.rpc.rtk" + +extension Mavsdk_Rpc_Rtk_RtcmData: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".RtcmData" + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 1: .same(proto: "data"), + ] + + mutating func decodeMessage(decoder: inout D) throws { + while let fieldNumber = try decoder.nextFieldNumber() { + // The use of inline closures is to circumvent an issue where the compiler + // allocates stack space for every case branch when no optimizations are + // enabled. https://github.com/apple/swift-protobuf/issues/1034 + switch fieldNumber { + case 1: try { try decoder.decodeSingularStringField(value: &self.data) }() + default: break + } + } + } + + func traverse(visitor: inout V) throws { + if !self.data.isEmpty { + try visitor.visitSingularStringField(value: self.data, fieldNumber: 1) + } + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Rtk_RtcmData, rhs: Mavsdk_Rpc_Rtk_RtcmData) -> Bool { + if lhs.data != rhs.data {return false} + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + +extension Mavsdk_Rpc_Rtk_SendRtcmDataRequest: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".SendRtcmDataRequest" + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 1: .standard(proto: "rtcm_data"), + ] + + mutating func decodeMessage(decoder: inout D) throws { + while let fieldNumber = try decoder.nextFieldNumber() { + // The use of inline closures is to circumvent an issue where the compiler + // allocates stack space for every case branch when no optimizations are + // enabled. https://github.com/apple/swift-protobuf/issues/1034 + switch fieldNumber { + case 1: try { try decoder.decodeSingularMessageField(value: &self._rtcmData) }() + default: break + } + } + } + + func traverse(visitor: inout V) throws { + // The use of inline closures is to circumvent an issue where the compiler + // allocates stack space for every if/case branch local when no optimizations + // are enabled. https://github.com/apple/swift-protobuf/issues/1034 and + // https://github.com/apple/swift-protobuf/issues/1182 + try { if let v = self._rtcmData { + try visitor.visitSingularMessageField(value: v, fieldNumber: 1) + } }() + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Rtk_SendRtcmDataRequest, rhs: Mavsdk_Rpc_Rtk_SendRtcmDataRequest) -> Bool { + if lhs._rtcmData != rhs._rtcmData {return false} + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + +extension Mavsdk_Rpc_Rtk_SendRtcmDataResponse: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".SendRtcmDataResponse" + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 1: .standard(proto: "rtk_result"), + ] + + mutating func decodeMessage(decoder: inout D) throws { + while let fieldNumber = try decoder.nextFieldNumber() { + // The use of inline closures is to circumvent an issue where the compiler + // allocates stack space for every case branch when no optimizations are + // enabled. https://github.com/apple/swift-protobuf/issues/1034 + switch fieldNumber { + case 1: try { try decoder.decodeSingularMessageField(value: &self._rtkResult) }() + default: break + } + } + } + + func traverse(visitor: inout V) throws { + // The use of inline closures is to circumvent an issue where the compiler + // allocates stack space for every if/case branch local when no optimizations + // are enabled. https://github.com/apple/swift-protobuf/issues/1034 and + // https://github.com/apple/swift-protobuf/issues/1182 + try { if let v = self._rtkResult { + try visitor.visitSingularMessageField(value: v, fieldNumber: 1) + } }() + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Rtk_SendRtcmDataResponse, rhs: Mavsdk_Rpc_Rtk_SendRtcmDataResponse) -> Bool { + if lhs._rtkResult != rhs._rtkResult {return false} + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + +extension Mavsdk_Rpc_Rtk_RtkResult: SwiftProtobuf.Message, SwiftProtobuf._MessageImplementationBase, SwiftProtobuf._ProtoNameProviding { + static let protoMessageName: String = _protobuf_package + ".RtkResult" + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 1: .same(proto: "result"), + 2: .standard(proto: "result_str"), + ] + + mutating func decodeMessage(decoder: inout D) throws { + while let fieldNumber = try decoder.nextFieldNumber() { + // The use of inline closures is to circumvent an issue where the compiler + // allocates stack space for every case branch when no optimizations are + // enabled. https://github.com/apple/swift-protobuf/issues/1034 + switch fieldNumber { + case 1: try { try decoder.decodeSingularEnumField(value: &self.result) }() + case 2: try { try decoder.decodeSingularStringField(value: &self.resultStr) }() + default: break + } + } + } + + func traverse(visitor: inout V) throws { + if self.result != .unknown { + try visitor.visitSingularEnumField(value: self.result, fieldNumber: 1) + } + if !self.resultStr.isEmpty { + try visitor.visitSingularStringField(value: self.resultStr, fieldNumber: 2) + } + try unknownFields.traverse(visitor: &visitor) + } + + static func ==(lhs: Mavsdk_Rpc_Rtk_RtkResult, rhs: Mavsdk_Rpc_Rtk_RtkResult) -> Bool { + if lhs.result != rhs.result {return false} + if lhs.resultStr != rhs.resultStr {return false} + if lhs.unknownFields != rhs.unknownFields {return false} + return true + } +} + +extension Mavsdk_Rpc_Rtk_RtkResult.Result: SwiftProtobuf._ProtoNameProviding { + static let _protobuf_nameMap: SwiftProtobuf._NameMap = [ + 0: .same(proto: "RESULT_UNKNOWN"), + 1: .same(proto: "RESULT_SUCCESS"), + 2: .same(proto: "RESULT_TOO_LONG"), + 5: .same(proto: "RESULT_NO_SYSTEM"), + 6: .same(proto: "RESULT_CONNECTION_ERROR"), + ] +} diff --git a/Sources/Mavsdk/Generated/server_utility.pb.swift b/Sources/Mavsdk/Generated/server_utility.pb.swift index 558a286..6e8495e 100644 --- a/Sources/Mavsdk/Generated/server_utility.pb.swift +++ b/Sources/Mavsdk/Generated/server_utility.pb.swift @@ -87,7 +87,7 @@ enum Mavsdk_Rpc_ServerUtility_StatusTextType: SwiftProtobuf.Enum { extension Mavsdk_Rpc_ServerUtility_StatusTextType: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_ServerUtility_StatusTextType] = [ + static let allCases: [Mavsdk_Rpc_ServerUtility_StatusTextType] = [ .debug, .info, .notice, @@ -206,7 +206,7 @@ struct Mavsdk_Rpc_ServerUtility_ServerUtilityResult { extension Mavsdk_Rpc_ServerUtility_ServerUtilityResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_ServerUtility_ServerUtilityResult.Result] = [ + static let allCases: [Mavsdk_Rpc_ServerUtility_ServerUtilityResult.Result] = [ .unknown, .success, .noSystem, diff --git a/Sources/Mavsdk/Generated/shell.pb.swift b/Sources/Mavsdk/Generated/shell.pb.swift index 5423bec..a208b99 100644 --- a/Sources/Mavsdk/Generated/shell.pb.swift +++ b/Sources/Mavsdk/Generated/shell.pb.swift @@ -151,7 +151,7 @@ struct Mavsdk_Rpc_Shell_ShellResult { extension Mavsdk_Rpc_Shell_ShellResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Shell_ShellResult.Result] = [ + static let allCases: [Mavsdk_Rpc_Shell_ShellResult.Result] = [ .unknown, .success, .noSystem, diff --git a/Sources/Mavsdk/Generated/telemetry.pb.swift b/Sources/Mavsdk/Generated/telemetry.pb.swift index 70bace8..4cb75b5 100644 --- a/Sources/Mavsdk/Generated/telemetry.pb.swift +++ b/Sources/Mavsdk/Generated/telemetry.pb.swift @@ -82,7 +82,7 @@ enum Mavsdk_Rpc_Telemetry_FixType: SwiftProtobuf.Enum { extension Mavsdk_Rpc_Telemetry_FixType: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Telemetry_FixType] = [ + static let allCases: [Mavsdk_Rpc_Telemetry_FixType] = [ .noGps, .noFix, .fix2D, @@ -201,7 +201,7 @@ enum Mavsdk_Rpc_Telemetry_FlightMode: SwiftProtobuf.Enum { extension Mavsdk_Rpc_Telemetry_FlightMode: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Telemetry_FlightMode] = [ + static let allCases: [Mavsdk_Rpc_Telemetry_FlightMode] = [ .unknown, .ready, .takeoff, @@ -289,7 +289,7 @@ enum Mavsdk_Rpc_Telemetry_StatusTextType: SwiftProtobuf.Enum { extension Mavsdk_Rpc_Telemetry_StatusTextType: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Telemetry_StatusTextType] = [ + static let allCases: [Mavsdk_Rpc_Telemetry_StatusTextType] = [ .debug, .info, .notice, @@ -355,7 +355,7 @@ enum Mavsdk_Rpc_Telemetry_LandedState: SwiftProtobuf.Enum { extension Mavsdk_Rpc_Telemetry_LandedState: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Telemetry_LandedState] = [ + static let allCases: [Mavsdk_Rpc_Telemetry_LandedState] = [ .unknown, .onGround, .inAir, @@ -418,7 +418,7 @@ enum Mavsdk_Rpc_Telemetry_VtolState: SwiftProtobuf.Enum { extension Mavsdk_Rpc_Telemetry_VtolState: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Telemetry_VtolState] = [ + static let allCases: [Mavsdk_Rpc_Telemetry_VtolState] = [ .undefined, .transitionToFw, .transitionToMc, @@ -2806,7 +2806,7 @@ struct Mavsdk_Rpc_Telemetry_Odometry { 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] = [ + static let allCases: [Mavsdk_Rpc_Telemetry_Odometry.MavFrame] = [ .undef, .bodyNed, .visionNed, @@ -3191,7 +3191,7 @@ struct Mavsdk_Rpc_Telemetry_TelemetryResult { extension Mavsdk_Rpc_Telemetry_TelemetryResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Telemetry_TelemetryResult.Result] = [ + static let allCases: [Mavsdk_Rpc_Telemetry_TelemetryResult.Result] = [ .unknown, .success, .noSystem, diff --git a/Sources/Mavsdk/Generated/telemetry_server.pb.swift b/Sources/Mavsdk/Generated/telemetry_server.pb.swift index 356a5e7..af4dafa 100644 --- a/Sources/Mavsdk/Generated/telemetry_server.pb.swift +++ b/Sources/Mavsdk/Generated/telemetry_server.pb.swift @@ -82,7 +82,7 @@ enum Mavsdk_Rpc_TelemetryServer_FixType: SwiftProtobuf.Enum { extension Mavsdk_Rpc_TelemetryServer_FixType: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_TelemetryServer_FixType] = [ + static let allCases: [Mavsdk_Rpc_TelemetryServer_FixType] = [ .noGps, .noFix, .fix2D, @@ -147,7 +147,7 @@ enum Mavsdk_Rpc_TelemetryServer_VtolState: SwiftProtobuf.Enum { extension Mavsdk_Rpc_TelemetryServer_VtolState: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_TelemetryServer_VtolState] = [ + static let allCases: [Mavsdk_Rpc_TelemetryServer_VtolState] = [ .undefined, .transitionToFw, .transitionToMc, @@ -225,7 +225,7 @@ enum Mavsdk_Rpc_TelemetryServer_StatusTextType: SwiftProtobuf.Enum { extension Mavsdk_Rpc_TelemetryServer_StatusTextType: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_TelemetryServer_StatusTextType] = [ + static let allCases: [Mavsdk_Rpc_TelemetryServer_StatusTextType] = [ .debug, .info, .notice, @@ -291,7 +291,7 @@ enum Mavsdk_Rpc_TelemetryServer_LandedState: SwiftProtobuf.Enum { extension Mavsdk_Rpc_TelemetryServer_LandedState: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_TelemetryServer_LandedState] = [ + static let allCases: [Mavsdk_Rpc_TelemetryServer_LandedState] = [ .unknown, .onGround, .inAir, @@ -1458,7 +1458,7 @@ struct Mavsdk_Rpc_TelemetryServer_Odometry { extension Mavsdk_Rpc_TelemetryServer_Odometry.MavFrame: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_TelemetryServer_Odometry.MavFrame] = [ + static let allCases: [Mavsdk_Rpc_TelemetryServer_Odometry.MavFrame] = [ .undef, .bodyNed, .visionNed, @@ -1823,7 +1823,7 @@ struct Mavsdk_Rpc_TelemetryServer_TelemetryServerResult { extension Mavsdk_Rpc_TelemetryServer_TelemetryServerResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_TelemetryServer_TelemetryServerResult.Result] = [ + static let allCases: [Mavsdk_Rpc_TelemetryServer_TelemetryServerResult.Result] = [ .unknown, .success, .noSystem, diff --git a/Sources/Mavsdk/Generated/transponder.pb.swift b/Sources/Mavsdk/Generated/transponder.pb.swift index 2909fa8..b065076 100644 --- a/Sources/Mavsdk/Generated/transponder.pb.swift +++ b/Sources/Mavsdk/Generated/transponder.pb.swift @@ -147,7 +147,7 @@ enum Mavsdk_Rpc_Transponder_AdsbEmitterType: SwiftProtobuf.Enum { extension Mavsdk_Rpc_Transponder_AdsbEmitterType: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Transponder_AdsbEmitterType] = [ + static let allCases: [Mavsdk_Rpc_Transponder_AdsbEmitterType] = [ .noInfo, .light, .small, @@ -362,7 +362,7 @@ struct Mavsdk_Rpc_Transponder_TransponderResult { extension Mavsdk_Rpc_Transponder_TransponderResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Transponder_TransponderResult.Result] = [ + static let allCases: [Mavsdk_Rpc_Transponder_TransponderResult.Result] = [ .unknown, .success, .noSystem, diff --git a/Sources/Mavsdk/Generated/tune.pb.swift b/Sources/Mavsdk/Generated/tune.pb.swift index 9ce618e..28526d9 100644 --- a/Sources/Mavsdk/Generated/tune.pb.swift +++ b/Sources/Mavsdk/Generated/tune.pb.swift @@ -152,7 +152,7 @@ enum Mavsdk_Rpc_Tune_SongElement: SwiftProtobuf.Enum { extension Mavsdk_Rpc_Tune_SongElement: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Tune_SongElement] = [ + static let allCases: [Mavsdk_Rpc_Tune_SongElement] = [ .styleLegato, .styleNormal, .styleStaccato, @@ -312,7 +312,7 @@ struct Mavsdk_Rpc_Tune_TuneResult { extension Mavsdk_Rpc_Tune_TuneResult.Result: CaseIterable { // The compiler won't synthesize support with the UNRECOGNIZED case. - static var allCases: [Mavsdk_Rpc_Tune_TuneResult.Result] = [ + static let allCases: [Mavsdk_Rpc_Tune_TuneResult.Result] = [ .unknown, .success, .invalidTempo, diff --git a/Sources/Mavsdk/proto b/Sources/Mavsdk/proto index e74179a..17d7076 160000 --- a/Sources/Mavsdk/proto +++ b/Sources/Mavsdk/proto @@ -1 +1 @@ -Subproject commit e74179a049fd74c570ece9fc19b95388cdc4068d +Subproject commit 17d707685a8cbe5e0b6c930850b5a2c75b85bbd8