diff --git a/GroundSdk.podspec b/GroundSdk.podspec index c6d7362..d837c9f 100644 --- a/GroundSdk.podspec +++ b/GroundSdk.podspec @@ -1,17 +1,17 @@ Pod::Spec.new do |s| s.name = "GroundSdk" - s.version = "7.3.0" + s.version = "7.4.0" s.summary = "Parrot Drone SDK" s.homepage = "https://developer.parrot.com" s.license = "{ :type => 'BSD 3-Clause License', :file => 'LICENSE' }" s.author = 'Parrot Drone SAS' - s.source = { :git => 'https://github.com/Parrot-Developers/pod_groundsdk.git', :tag => "7.3.0" } + s.source = { :git => 'https://github.com/Parrot-Developers/pod_groundsdk.git', :tag => "7.4.0" } s.platform = :ios s.ios.deployment_target = '12.0' s.source_files = 'GroundSdk/**/*.{swift,h,m}' s.resources = 'GroundSdk/**/*.{vsh,fsh,txt,png}' - s.dependency 'SdkCore', '7.3.0' + s.dependency 'SdkCore', '7.4.0' s.public_header_files = ["GroundSdk/GroundSdk.h"] s.swift_version = '5' s.pod_target_xcconfig = {'SWIFT_VERSION' => '5'} diff --git a/GroundSdk/Device/DeviceModel.swift b/GroundSdk/Device/DeviceModel.swift index 52bd3ed..5284e84 100644 --- a/GroundSdk/Device/DeviceModel.swift +++ b/GroundSdk/Device/DeviceModel.swift @@ -100,7 +100,8 @@ public enum DeviceModel: CustomStringConvertible { } /// List of devices that can be connectable through usb. - private static var usbDevices: Set = [.rc(.skyCtrl3), .rc(.skyCtrl4), .rc(.skyCtrlUA)] + private static var usbDevices: Set = [.rc(.skyCtrl3), .rc(.skyCtrl4), .rc(.skyCtrl4Black), + .rc(.skyCtrlUA)] /// List of devices that can be connectable through wifi. private static var wifiDevices: Set = [.drone(.anafi4k), .drone(.anafiThermal), .drone(.anafi2), diff --git a/GroundSdk/Device/DeviceState.swift b/GroundSdk/Device/DeviceState.swift index e2505cd..74ee1c8 100644 --- a/GroundSdk/Device/DeviceState.swift +++ b/GroundSdk/Device/DeviceState.swift @@ -137,7 +137,7 @@ public class DeviceState: NSObject { /// Debug description. override public var description: String { - return "[\(connectionState)[\(connectionStateCause)]) \(connectors.debugDescription)]" + return "[\(connectionState)[\(connectionStateCause)] \(connectors.debugDescription)]" } } diff --git a/GroundSdk/Device/Instrument/Alarms.swift b/GroundSdk/Device/Instrument/Alarms.swift index 51b0c90..8d80d44 100644 --- a/GroundSdk/Device/Instrument/Alarms.swift +++ b/GroundSdk/Device/Instrument/Alarms.swift @@ -61,6 +61,9 @@ public class Alarm: NSObject { /// Battery authentication has failed. case batteryAuthenticationFailure + /// Battery poor connection. + case batteryPoorConnection + /// Hovering is difficult due to a lack of GPS positioning and not enough light to use its vertical camera. case hoveringDifficultiesNoGpsTooDark @@ -193,6 +196,15 @@ public class Alarm: NSObject { /// Stereo camera is decalibrated. case stereoCameraDecalibrated + /// Propeller are critically iced, so forced landing auto trigger is planned. + case automaticLandingPropellerIcingIssue + + /// Battery is too hot, so forced landing auto trigger is planned. + case automaticLandingBatteryTooHot + + /// Battery is too cold, so forced landing auto trigger is planned. + case automaticLandingBatteryTooCold + /// Debug description. public var description: String { switch self { @@ -204,6 +216,7 @@ public class Alarm: NSObject { case .batteryTooCold: return "batteryTooCold" case .batteryGaugeUpdateRequired: return "batteryGaugeUpdateRequired" case .batteryAuthenticationFailure: return "batteryAuthenticationFailure" + case .batteryPoorConnection: return "batteryPoorConnection" case .hoveringDifficultiesNoGpsTooDark: return "hoveringDifficultiesNoGpsTooDark" case .hoveringDifficultiesNoGpsTooHigh: return "hoveringDifficultiesNoGpsTooHigh" case .automaticLandingBatteryIssue: return "automaticLandingBatteryIssue" @@ -234,13 +247,16 @@ public class Alarm: NSObject { case .obstacleAvoidanceFreeze: return "obstacleAvoidanceFreeze" case .freeFallDetected: return "freeFallDetected" case .stereoCameraDecalibrated: return "stereoCameraDecalibrated" + case .automaticLandingPropellerIcingIssue: return "automaticLandingPropellerIcingIssue" + case .automaticLandingBatteryTooHot: return "automaticLandingBatteryTooHot" + case .automaticLandingBatteryTooCold: return "automaticLandingBatteryTooCold" } } /// Set containing all possible kinds of alarm. public static let allCases: Set = [ .power, .motorCutOut, .userEmergency, .motorError, .batteryTooHot, .batteryTooCold, - .batteryGaugeUpdateRequired, .batteryAuthenticationFailure, + .batteryGaugeUpdateRequired, .batteryAuthenticationFailure, .batteryPoorConnection, .hoveringDifficultiesNoGpsTooDark, .hoveringDifficultiesNoGpsTooHigh, .automaticLandingBatteryIssue, .wind, .verticalCamera, .strongVibrations, .magnetometerPertubation, .magnetometerLowEarthField, .unreliableControllerLocation, @@ -252,7 +268,8 @@ public class Alarm: NSObject { .obstacleAvoidancePoorGps, .obstacleAvoidanceComputationalError, .obstacleAvoidanceBlindMotionDirection, .inclinationTooHigh, .horizontalGeofenceReached, .verticalGeofenceReached, .obstacleAvoidanceFreeze, .freeFallDetected, - .stereoCameraDecalibrated] + .stereoCameraDecalibrated, .automaticLandingPropellerIcingIssue, .automaticLandingBatteryTooHot, + .automaticLandingBatteryTooCold] } /// Alarm level. diff --git a/GroundSdk/Device/Instrument/BatteryInfo.swift b/GroundSdk/Device/Instrument/BatteryInfo.swift index 22d5427..6e3aa71 100644 --- a/GroundSdk/Device/Instrument/BatteryInfo.swift +++ b/GroundSdk/Device/Instrument/BatteryInfo.swift @@ -76,6 +76,10 @@ public protocol BatteryInfo: Instrument { /// - note: The size of this array if not empty is expected to be equal to /// `batteryDescription.cellCount`. var cellVoltages: [UInt?] { get } + + /// Battery components' versions. + /// `nil` if not available. This can happen if the drone does not know or provide this information. + var version: BatteryVersion? { get } } /// The battery description. @@ -138,6 +142,33 @@ public struct BatteryCapacity: Equatable { } } +/// The battery components' versions. +public struct BatteryVersion: Equatable { + /// The battery hardware revision. + public let hardwareRevision: UInt + /// The battery firmware version. + public let firmwareVersion: String + /// The battery gauge version. + public let gaugeVersion: String + /// The battery USB version. + public let usbVersion: String + + /// Constructor + /// + /// - Parameters: + /// - hardwareRevision: the battery hardware revision + /// - firmwareVersion: the battery firmware version + /// - gaugeVersion: the battery gauge version + /// - usbVersion: the battery USB version + public init(hardwareRevision: UInt, firmwareVersion: String, gaugeVersion: String, + usbVersion: String) { + self.hardwareRevision = hardwareRevision + self.firmwareVersion = firmwareVersion + self.gaugeVersion = gaugeVersion + self.usbVersion = usbVersion + } +} + // MARK: Objective-C API /// Instrument that informs a device's battery. diff --git a/GroundSdk/Device/Instrument/CellularLinkStatus.swift b/GroundSdk/Device/Instrument/CellularLink.swift similarity index 87% rename from GroundSdk/Device/Instrument/CellularLinkStatus.swift rename to GroundSdk/Device/Instrument/CellularLink.swift index ab282e5..30e8313 100644 --- a/GroundSdk/Device/Instrument/CellularLinkStatus.swift +++ b/GroundSdk/Device/Instrument/CellularLink.swift @@ -30,7 +30,7 @@ import Foundation /// Cellular link status. -public enum CellularLinkStatusStatus: CustomStringConvertible, Equatable { +public enum CellularLinkStatus: CustomStringConvertible, Equatable { /// Interface is down. case down /// Interface is up with IP connectivity. @@ -79,23 +79,23 @@ public enum CellularLinkStatusError: String, CustomStringConvertible, CaseIterab public var description: String { rawValue } } -/// CellularLinkStatus instrument. +/// CellularLink instrument. /// /// This instrument provides status of cellular link. /// /// This instrument can be retrieved by: /// ``` -/// device.getInstrument(Instruments.cellularLinkStatus) +/// device.getInstrument(Instruments.cellularLink) /// ``` -public protocol CellularLinkStatus: Instrument { +public protocol CellularLink: Instrument { /// Celullar link status, or `nil` if not available. - var status: CellularLinkStatusStatus? { get } + var status: CellularLinkStatus? { get } } /// :nodoc: /// Instrument descriptor. -public class CellularLinkStatusDesc: NSObject, InstrumentClassDesc { - public typealias ApiProtocol = CellularLinkStatus - public let uid = InstrumentUid.cellularLinkStatus.rawValue +public class CellularLinkDesc: NSObject, InstrumentClassDesc { + public typealias ApiProtocol = CellularLink + public let uid = InstrumentUid.cellularLink.rawValue public let parent: ComponentDescriptor? = nil } diff --git a/GroundSdk/Device/Instrument/CellularSession.swift b/GroundSdk/Device/Instrument/CellularSession.swift new file mode 100644 index 0000000..e630f48 --- /dev/null +++ b/GroundSdk/Device/Instrument/CellularSession.swift @@ -0,0 +1,207 @@ +// Copyright (C) 2022 Parrot Drones SAS +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in +// the documentation and/or other materials provided with the +// distribution. +// * Neither the name of the Parrot Company nor the names +// of its contributors may be used to endorse or promote products +// derived from this software without specific prior written +// permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// PARROT COMPANY BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +// OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +// AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +// OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT +// OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF +// SUCH DAMAGE. + +import Foundation + +/// Cellular session status. +public enum CellularSessionStatus: Hashable, Equatable, CaseIterable, CustomStringConvertible { + /* Modem status. */ + public enum Modem: Hashable, Equatable, CaseIterable { + case off + case offline + case updating + case online + case error + } + + /* SIM status. */ + public enum Sim: Hashable, Equatable, CaseIterable { + case locked + case ready + case absent + case error + } + + /* Network registration status. */ + public enum Network: Hashable, Equatable, CaseIterable { + case searching + case home + case roaming + case registrationDenied + case activationDenied + } + + /* Parrot server connection status. */ + public enum Server: Hashable, Equatable, CaseIterable { + case waitApcToken + case connecting + case connected + case unreachableDns + case unreachableConnect + case unreachableAuth + } + + /* Drone/controller connection status. */ + public enum Connection: Hashable, Equatable, CaseIterable { + case offline + case connecting + case established + case error + case errorCommLink + case errorTimeout + case errorMismatch + } + + case unknown + case modem(Modem) + case sim(Sim) + case network(Network) + case server(Server) + case connection(Connection) + + public static var allCases: [CellularSessionStatus] { + [CellularSessionStatus.unknown] + + Modem.allCases.map { CellularSessionStatus.modem($0) } + + Sim.allCases.map { CellularSessionStatus.sim($0) } + + Network.allCases.map { CellularSessionStatus.network($0) } + + Server.allCases.map { CellularSessionStatus.server($0) } + + Connection.allCases.map { CellularSessionStatus.connection($0) } + } + + /// Debug description + public var description: String { + switch self { + case .modem(let sub): + switch sub { + case .off: return "modemOff" + case .offline: return "modemOffline" + case .updating: return "modemUpdating" + case .online: return "modemOnline" + case .error: return "modemError" + } + case .sim(let sub): + switch sub { + case .locked: return "simLocked" + case .ready: return "simReady" + case .absent: return "simAbsent" + case .error: return "simError" + } + case .network(let sub): + switch sub { + case .searching: return "networkSearching" + case .home: return "networkHome" + case .roaming: return "networkRoaming" + case .registrationDenied: return "networkRegistrationDenied" + case .activationDenied: return "networkActivationDenied" + } + case .server(let sub): + switch sub { + case .waitApcToken: return "serverWaitApcToken" + case .connecting: return "serverConnecting" + case .connected: return "serverConnected" + case .unreachableDns: return "serverUnreachableDns" + case .unreachableConnect: return "serverUnreachableConnect" + case .unreachableAuth: return "serverUnreachableAuth" + } + case .connection(let sub): + switch sub { + case .offline: return "connectionOffline" + case .connecting: return "connectionConnecting" + case .established: return "connectionEstablished" + case .error: return "connectionError" + case .errorCommLink: return "connectionErrorCommLink" + case .errorTimeout: return "connectionErrorTimeout" + case .errorMismatch: return "connectionErrorMismatch" + } + case .unknown: + return "unknown" + } + } + + /// States indicating a functioning cellular session. + public static var nominalStates: Set { + [.modem(.online), .sim(.ready), .network(.home), .network(.roaming), + .server(.connected), .connection(.established)] + } + + /// States indicating a transition of the cellular session from a nominal state towards a new + /// nominal state or an new error state. + public static var transitoryStates: Set { + [.modem(.off), .modem(.offline), .modem(.updating), + .sim(.locked), .sim(.absent), + .network(.searching), + .server(.waitApcToken), .server(.connecting), + .connection(.offline), .connection(.connecting)] + } + + /// States indicating an error on the cellular session. + public static var errorStates: Set { + [.modem(.error), .sim(.error), + .network(.registrationDenied), .network(.activationDenied), + .server(.unreachableDns), .server(.unreachableConnect), .server(.unreachableAuth), + .connection(.error), .connection(.errorCommLink), .connection(.errorTimeout), + .connection(.errorMismatch)] + } + + /// Whether the receiver is a nominal state. + public var isNominal: Bool { + CellularSessionStatus.nominalStates.contains(self) + } + + /// Whether the receiver is an error state. + public var isError: Bool { + CellularSessionStatus.errorStates.contains(self) + } + + /// Whether the receiver is a transitory state. + public var isTransitory: Bool { + CellularSessionStatus.transitoryStates.contains(self) + } +} + +/// CellularSession instrument. +/// +/// This instrument provides status of cellular session. +/// +/// This instrument can be retrieved by: +/// ``` +/// device.getInstrument(Instruments.cellularSession) +/// ``` +public protocol CellularSession: Instrument { + /// Celullar link status, or `nil` if not available. + var status: CellularSessionStatus? { get } +} + +/// :nodoc: +/// Instrument descriptor. +public class CellularSessionDesc: NSObject, InstrumentClassDesc { + public typealias ApiProtocol = CellularSession + public let uid = InstrumentUid.cellularSession.rawValue + public let parent: ComponentDescriptor? = nil +} diff --git a/GroundSdk/Device/Instrument/Instrument.swift b/GroundSdk/Device/Instrument/Instrument.swift index 7cbd815..393cc30 100644 --- a/GroundSdk/Device/Instrument/Instrument.swift +++ b/GroundSdk/Device/Instrument/Instrument.swift @@ -44,58 +44,61 @@ public protocol InstrumentClassDesc: ComponentApiDescriptor { @objcMembers @objc(GSInstruments) public class Instruments: NSObject { - /// Flying indicators instrument. - public static let flyingIndicators = FlyingIndicatorsDesc() /// Alarms information instrument. public static let alarms = AlarmsDesc() - /// Location instrument. - public static let gps = GpsDesc() - /// Heading instrument. - public static let compass = CompassDesc() /// Altimeter instrument. - public static let altimeter = AltimeterDesc() - /// Speedometer instrument. - public static let speedometer = SpeedometerDesc() + public static let altimeter = AltimeterDesc() /// Attitude instrument. public static let attitudeIndicator = AttitudeIndicatorDesc() - /// Radio instrument. - public static let radio = RadioDesc() /// Battery information instrument. public static let batteryInfo = BatteryInfoDesc() - /// Flight meter instrument. - public static let flightMeter = FlightMeterDesc() /// Camera exposure values instrument. public static let cameraExposureValues = CameraExposureValuesDesc() - /// Photo progress instrument. - public static let photoProgressIndicator = PhotoProgressIndicatorDesc() - /// Flight info instrument. - public static let flightInfo = FlightInfoDesc() + /// Cellular link status instrument. + public static let cellularLink = CellularLinkDesc() /// Cellular logs instrument. public static let cellularLogs = CellularLogsDesc() + /// Cellular session status instrument. + public static let cellularSession = CellularSessionDesc() + /// Heading instrument. + public static let compass = CompassDesc() + /// Flight info instrument. + public static let flightInfo = FlightInfoDesc() + /// Flight meter instrument. + public static let flightMeter = FlightMeterDesc() + /// Flying indicators instrument. + public static let flyingIndicators = FlyingIndicatorsDesc() + /// Location instrument. + public static let gps = GpsDesc() + /// Photo progress instrument. + public static let photoProgressIndicator = PhotoProgressIndicatorDesc() + /// Radio instrument. + public static let radio = RadioDesc() + /// Speedometer instrument. + public static let speedometer = SpeedometerDesc() /// Takeoff checklist instrument. public static let takeoffChecklist = TakeoffChecklistDesc() - /// Cellular link status instrument. - public static let cellularLinkStatus = CellularLinkStatusDesc() } /// Instruments uid. enum InstrumentUid: Int { - case flyingIndicators = 1 case alarms - case gps - case compass case altimeter - case speedometer case attitudeIndicator - case radio case batteryInfo - case flightMeter case cameraExposureValues - case photoProgressIndicator - case flightInfo + case cellularLink case cellularLogs + case cellularSession + case compass + case flightInfo + case flightMeter + case flyingIndicators + case gps + case photoProgressIndicator + case radio + case speedometer case takeoffChecklist - case cellularLinkStatus } /// Objective-C wrapper of Ref. Required because swift generics can't be used from Objective-C. diff --git a/GroundSdk/Device/Instrument/TakeoffChecklist.swift b/GroundSdk/Device/Instrument/TakeoffChecklist.swift index f474b57..ef6d023 100644 --- a/GroundSdk/Device/Instrument/TakeoffChecklist.swift +++ b/GroundSdk/Device/Instrument/TakeoffChecklist.swift @@ -46,6 +46,9 @@ public class TakeoffAlarm: NSObject { /// Battery level check case batteryLevel + /// Battery poor connection + case batteryPoorConnection + /// Battery under temperature check case batteryTooCold @@ -92,6 +95,7 @@ public class TakeoffAlarm: NSObject { case .batteryGaugeUpdateRequired: return "batteryGaugeUpdateRequired" case .batteryIdentification: return "batteryIdentification" case .batteryLevel: return "batteryLevel" + case .batteryPoorConnection: return "batteryPoorConnection" case .batteryTooCold: return "batteryTooCold" case .batteryTooHot: return "batteryTooHot" case .batteryUsbPortConnection: return "batteryUsbPortConnection" @@ -110,9 +114,9 @@ public class TakeoffAlarm: NSObject { /// Set containing all possible kinds of alarm. public static let allCases: Set = [ - .baro, .batteryGaugeUpdateRequired, .batteryIdentification, .batteryLevel, .batteryTooCold, .batteryTooHot, - .batteryUsbPortConnection, .cellularModemFirmwareUpdate, .droneInclination, .gps, .gyro, .magneto, - .magnetoCalibration, .ultrasound, .updateOngoing, .vcam, .verticalTof] + .baro, .batteryGaugeUpdateRequired, .batteryIdentification, .batteryLevel, .batteryPoorConnection, + .batteryTooCold, .batteryTooHot, .batteryUsbPortConnection, .cellularModemFirmwareUpdate, .droneInclination, + .gps, .gyro, .magneto, .magnetoCalibration, .ultrasound, .updateOngoing, .vcam, .verticalTof] } /// Alarm level. diff --git a/GroundSdk/Device/Peripheral/DebugShell.swift b/GroundSdk/Device/Peripheral/DebugShell.swift new file mode 100644 index 0000000..b63aeff --- /dev/null +++ b/GroundSdk/Device/Peripheral/DebugShell.swift @@ -0,0 +1,82 @@ +// Copyright (C) 2022 Parrot Drones SAS +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in +// the documentation and/or other materials provided with the +// distribution. +// * Neither the name of the Parrot Company nor the names +// of its contributors may be used to endorse or promote products +// derived from this software without specific prior written +// permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// PARROT COMPANY BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +// OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +// AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +// OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT +// OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF +// SUCH DAMAGE. + +import Foundation + +/// Debug shell state. +public enum DebugShellState: Equatable, CustomStringConvertible, CustomDebugStringConvertible { + /// The debug shell is disabled. + case disabled + /// The debug shell is enabled for the given public key. + case enabled(publicKey: String) + + public var description: String { + switch self { + case .enabled(let key): return "enabled publicKey: \"\(key.prefix(3))...\(key.suffix(3))\"" + case .disabled: return "disabled" + } + } + + public var debugDescription: String { + switch self { + case .enabled(let key): return "enabled publicKey: \"\(key)\"" + case .disabled: return "disabled" + } + } +} + +/// Setting providing access to the DebugShellState. +public protocol DebugShellStateSetting: AnyObject { + /// Tells if the setting value has been changed and is waiting for change confirmation. + var updating: Bool { get } + + /// Debug shell state value. + var value: DebugShellState { get set } +} + +/// DebugShell peripheral interface. +/// +/// This peripheral provides access to DebugShell settings. +/// +/// This peripheral can be retrieved by: +/// ``` +/// device.getPeripheral(Peripherals.debugShell) +/// ``` +public protocol DebugShell: Peripheral { + /// DebugShell state setting. + var state: DebugShellStateSetting { get } +} + +/// :nodoc: +/// DebugShell description +public class DebugShellDesc: NSObject, PeripheralClassDesc { + public typealias ApiProtocol = DebugShell + public let uid = PeripheralUid.debugShell.rawValue + public let parent: ComponentDescriptor? = nil +} diff --git a/GroundSdk/Device/Peripheral/LatestLogDownloader.swift b/GroundSdk/Device/Peripheral/LatestLogDownloader.swift new file mode 100644 index 0000000..a57b7e0 --- /dev/null +++ b/GroundSdk/Device/Peripheral/LatestLogDownloader.swift @@ -0,0 +1,57 @@ +// Copyright (C) 2022 Parrot Drones SAS +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in +// the documentation and/or other materials provided with the +// distribution. +// * Neither the name of the Parrot Company nor the names +// of its contributors may be used to endorse or promote products +// derived from this software without specific prior written +// permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// PARROT COMPANY BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +// OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +// AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +// OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT +// OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF +// SUCH DAMAGE. + +import Foundation + +/// Latest Log Downloader peripheral interface. +/// +/// This internal peripheral allows to retrieve latest logs (FDR) from the device. +/// +/// This peripheral can be retrieved by: +/// ``` +/// device.getPeripheral(Peripherals.latestLogDownloader) +/// ``` +public protocol LatestLogDownloader: Peripheral { + /// State of the log collection. + var state: LogCollectorState { get } + + /// Downloads the device logs for the current boot id. + func downloadLogs(toDirectory directory: URL) + + /// Cancels an ongoing log download. + func cancelDownload() +} + +/// :nodoc: +/// LatestLogDownloader description +class LatestLogDownloaderDesc: NSObject, PeripheralClassDesc { + public typealias ApiProtocol = LatestLogDownloader + public let uid = PeripheralUid.latestLogDownloader.rawValue + public let parent: ComponentDescriptor? = nil +} diff --git a/GroundSdk/Device/Peripheral/LogControl.swift b/GroundSdk/Device/Peripheral/LogControl.swift index 580ecf6..e32294b 100644 --- a/GroundSdk/Device/Peripheral/LogControl.swift +++ b/GroundSdk/Device/Peripheral/LogControl.swift @@ -52,6 +52,9 @@ public protocol LogControl: Peripheral { /// /// - Returns: `true` if the deactivation has been asked, `false` otherwise func deactivateLogs() -> Bool + + /// Setting controlling whether mission logs are recorded. + var missionLogs: BoolSetting? { get } } /// :nodoc: diff --git a/GroundSdk/Device/Peripheral/Peripheral.swift b/GroundSdk/Device/Peripheral/Peripheral.swift index ab0d97f..1f02e56 100644 --- a/GroundSdk/Device/Peripheral/Peripheral.swift +++ b/GroundSdk/Device/Peripheral/Peripheral.swift @@ -44,163 +44,171 @@ public protocol PeripheralClassDesc: ComponentApiDescriptor { @objcMembers @objc(GSPeripherals) public class Peripherals: NSObject { - /// Magnetometer peripheral. - public static let magnetometer = MagnetometerDesc() - /// 3-steps calibration magnetometer peripheral. - public static let magnetometerWith3StepCalibration = MagnetometerWith3StepCalibrationDesc() - /// 1-step calibration magnetometer peripheral. - public static let magnetometerWith1StepCalibration = MagnetometerWith1StepCalibrationDesc() - /// Drone finder peripheral. - public static let droneFinder = DroneFinderDesc() - /// Video stream peripheral. - public static let streamServer = StreamServerDesc() - /// Main camera peripheral. - public static let mainCamera = MainCameraDesc() - /// Thermal camera peripheral. - public static let thermalCamera = ThermalCameraDesc() + /// Anti-flicker. + public static let antiflicker = AntiflickerDesc() + /// Battery gauge updater. + public static let batteryGaugeUpdater = BatteryGaugeUpdaterDesc() + /// Beeper. + public static let beeper = BeeperDesc() /// Blended thermal camera peripheral. public static let blendedThermalCamera = BlendedThermalCameraDesc() - /// Main camera 2 peripheral. - public static let mainCamera2 = MainCamera2Desc() - /// System info peripheral. - public static let systemInfo = SystemInfoDesc() - /// Media store peripheral. - public static let mediaStore = MediaStoreDesc() - /// Virtual gamepad peripheral. - public static let virtualGamepad = VirtualGamepadDesc() - /// SkyController3 gamepad peripheral. - public static let skyCtrl3Gamepad = SkyCtrl3GamepadDesc() - /// SkyController4 gamepad peripheral. - public static let skyCtrl4Gamepad = SkyCtrl4GamepadDesc() - /// Firmware updater peripheral. - public static let updater = UpdaterDesc() + /// Cellular. + public static let cellular = CellularDesc() + /// Certificate Uploader. + public static let certificateUploader = CertificateUploaderDesc() + /// Copilot. + public static let copilot = CopilotDesc() /// Copter motors peripheral. public static let copterMotors = CopterMotorsDesc() - /// Wifi scanner peripheral. - public static let wifiScanner = WifiScannerDesc() /// Crash report downloader peripheral. public static let crashReportDownloader = CrashReportDownloaderDesc() - /// Wifi access point peripheral. - public static let wifiAccessPoint = WifiAccessPointDesc() - /// Removable user storage. - public static let removableUserStorage = RemovableUserStorageDesc() - /// Internal user storage. - public static let internalUserStorage = InternalUserStorageDesc() - /// Beeper. - public static let beeper = BeeperDesc() - /// Gimbal. - public static let gimbal = GimbalDesc() - /// Front Stereo Gimbal. + /// Debug shell peripheral. + public static let debugShell = DebugShellDesc() + /// Development toolbox. + public static let devToolbox = DevToolboxDesc() + /// Dri. + public static let dri = DriDesc() + /// Drone finder peripheral. + public static let droneFinder = DroneFinderDesc() + /// Flight camera record downloader. + public static let flightCameraRecordDownloader = FlightCameraRecordDownloaderDesc() + /// Flight camera recorder. + public static let flightCameraRecorder = FlightCameraRecorderDesc() + /// Flight data (PUD) downloader. + public static let flightDataDownloader = FlightDataDownloaderDesc() + /// Flight log (FDR-lite) downloader. + public static let flightLogDownloader = FlightLogDownloaderDesc() + /// Front stereo gimbal. public static let frontStereoGimbal = FrontStereoGimbalDesc() - /// Anti-flicker. - public static let antiflicker = AntiflickerDesc() - /// Target Tracker - public static let targetTracker = TargetTrackerDesc() /// Geofence. public static let geofence = GeofenceDesc() - /// File Data (PUD) downloader. - public static let flightDataDownloader = FlightDataDownloaderDesc() - /// Flight Log downloader. - public static let flightLogDownloader = FlightLogDownloaderDesc() - /// Flight camera record downloader. - public static let flightCameraRecordDownloader = FlightCameraRecordDownloaderDesc() - /// Precise home. - public static let preciseHome = PreciseHomeDesc() - /// Thermal control. - public static let thermalControl = ThermalControlDesc() + /// Gimbal. + public static let gimbal = GimbalDesc() + /// Internal user storage. + public static let internalUserStorage = InternalUserStorageDesc() /// Leds. public static let leds = LedsDesc() - /// Copilot. - public static let copilot = CopilotDesc() - /// Piloting control. - public static let pilotingControl = PilotingControlDesc() - /// Radio control. - public static let radioControl = RadioControlDesc() - /// Onboard tracker. - public static let onboardTracker = OnboardTrackerDesc() - /// Battery gauge updater. - public static let batteryGaugeUpdater = BatteryGaugeUpdaterDesc() - /// Development toolbox. - public static let devToolbox = DevToolboxDesc() - /// Dri. - public static let dri = DriDesc() - /// Stereo vision sensor. - public static let stereoVisionSensor = StereoVisionSensorDesc() + /// Log control. + public static let logControl = LogControlDesc() + /// Magnetometer peripheral. + public static let magnetometer = MagnetometerDesc() + /// 1-step calibration magnetometer peripheral. + public static let magnetometerWith1StepCalibration = MagnetometerWith1StepCalibrationDesc() + /// 3-steps calibration magnetometer peripheral. + public static let magnetometerWith3StepCalibration = MagnetometerWith3StepCalibrationDesc() + /// Main camera peripheral. + public static let mainCamera = MainCameraDesc() + /// Main camera 2 peripheral. + public static let mainCamera2 = MainCamera2Desc() + /// Media store peripheral. + public static let mediaStore = MediaStoreDesc() + /// Microhard. + public static let microhard = MicrohardDesc() /// Missions. public static let missionManager = MissionManagerDesc() /// Mission Store. public static let missionsUpdater = MissionUpdaterDesc() - /// Log Control. - public static let logControl = LogControlDesc() - /// Certificate Uploader - public static let certificateUploader = CertificateUploaderDesc() - /// Cellular. - public static let cellular = CellularDesc() /// Network control. public static let networkControl = NetworkControlDesc() /// Obstacle avoidance. public static let obstacleAvoidance = ObstacleAvoidanceDesc() - /// FlightCameraRecorder - public static let flightCameraRecorder = FlightCameraRecorderDesc() + /// Onboard tracker. + public static let onboardTracker = OnboardTrackerDesc() + /// Piloting control. + public static let pilotingControl = PilotingControlDesc() + /// Precise home. + public static let preciseHome = PreciseHomeDesc() + /// Radio control. + public static let radioControl = RadioControlDesc() + /// Removable user storage. + public static let removableUserStorage = RemovableUserStorageDesc() /// SecureElement. public static let secureElement = SecureElementDesc() - /// Microhard. - public static let microhard = MicrohardDesc() + /// SkyController3 gamepad peripheral. + public static let skyCtrl3Gamepad = SkyCtrl3GamepadDesc() + /// SkyController4 gamepad peripheral. + public static let skyCtrl4Gamepad = SkyCtrl4GamepadDesc() + /// Stereo vision sensor. + public static let stereoVisionSensor = StereoVisionSensorDesc() + /// Video stream peripheral. + public static let streamServer = StreamServerDesc() + /// System info peripheral. + public static let systemInfo = SystemInfoDesc() + /// Target Tracker. + public static let targetTracker = TargetTrackerDesc() + /// Thermal camera peripheral. + public static let thermalCamera = ThermalCameraDesc() + /// Thermal control. + public static let thermalControl = ThermalControlDesc() + /// Firmware updater peripheral. + public static let updater = UpdaterDesc() + /// Virtual gamepad peripheral. + public static let virtualGamepad = VirtualGamepadDesc() + /// Wifi access point peripheral. + public static let wifiAccessPoint = WifiAccessPointDesc() + /// Wifi scanner peripheral. + public static let wifiScanner = WifiScannerDesc() + + // Internal peripherals. + /// Latest flight log (FDR) downloader. + internal static let latestLogDownloader = LatestLogDownloaderDesc() } /// Peripheral uid. enum PeripheralUid: Int { - case magnetometer - case magnetometerWith1StepCalibration - case magnetometerWith3StepCalibration - case droneFinder - case streamServer - case mainCamera - case thermalCamera + case antiflicker + case batteryGaugeUpdater + case beeper case blendedThermalCamera - case mainCamera2 - case systemInfo - case mediaStore - case virtualGamepad - case skyCtrl3Gamepad - case skyCtrl4Gamepad - case updater + case cellular + case certificateUploader + case copilot case copterMotors - case wifiScanner - case wifiAccessPoint case crashReportDownloader - case removableUserStorage - case internalUserStorage - case beeper - case gimbal - case frontStereoGimbal - case antiflicker - case targetTracker - case geofence + case debugShell + case devToolbox + case dri + case droneFinder + case flightCameraRecordDownloader + case flightCameraRecorder case flightDataDownloader case flightLogDownloader - case flightCameraRecordDownloader - case preciseHome - case thermalControl + case frontStereoGimbal + case geofence + case gimbal + case internalUserStorage + case latestLogDownloader case leds - case copilot - case pilotingControl - case radioControl - case onboardTracker - case batteryGaugeUpdater - case devToolbox - case dri - case stereoVisionSensor + case logControl + case magnetometer + case magnetometerWith1StepCalibration + case magnetometerWith3StepCalibration + case mainCamera + case mainCamera2 + case mediaStore + case microhard case missionManager case missionUpdater - case logControl - case certificateUploader - case cellular case networkControl case obstacleAvoidance - case flightCameraRecorder + case onboardTracker + case pilotingControl + case preciseHome + case radioControl + case removableUserStorage case secureElement - case microhard + case skyCtrl3Gamepad + case skyCtrl4Gamepad + case stereoVisionSensor + case streamServer + case systemInfo + case targetTracker + case thermalCamera + case thermalControl + case updater + case virtualGamepad + case wifiAccessPoint + case wifiScanner } /// Objective-C wrapper of Ref. Required because swift generics can't be used from Objective-C. diff --git a/GroundSdk/Device/PilotingItf/FlightPlanPilotingItf.swift b/GroundSdk/Device/PilotingItf/FlightPlanPilotingItf.swift index e3d5c04..b9ae8c1 100644 --- a/GroundSdk/Device/PilotingItf/FlightPlanPilotingItf.swift +++ b/GroundSdk/Device/PilotingItf/FlightPlanPilotingItf.swift @@ -188,7 +188,7 @@ public enum FlightPlanDisconnectionPolicy { /// /// Allows to make the drone execute predefined flight plans. /// A flight plan is defined using a file in Mavlink format. For further information, please refer to -/// [Parrot FlightPlan Mavlink documentation](https://developer.parrot.com/docs/mavlink-flightplan). +/// [Parrot FlightPlan Mavlink documentation](https://developer.parrot.com/docs/mavlink-flightplan/overview.html). /// /// This piloting interface remains `.unavailable` until all `FlightPlanUnavailabilityReason` have /// been cleared: @@ -403,6 +403,28 @@ public protocol FlightPlanPilotingItf: PilotingItf, ActivablePilotingItf { /// - Returns: a clean media resources cancelable request func cleanBeforeRecovery(customId: String, resourceId: String, completion: @escaping (_ result: CleanBeforeRecoveryResult) -> Void) -> CancelableCore? + + /// - important: DO NOT USE THIS METHOD, IT IS UNSTABLE, EXPERIMENTAL AND + /// WILL DISAPPEAR ON THE NEXT VERSION + /// + /// TODO: remove + /// + /// Prepares the drone for the upcoming flight plan activation. + /// + /// The drone will prepare the execution of a flight plan. This includes storing the current + /// camera settings that will be restored at the end of the flight plan. + /// + /// This method should be called: + /// * **after** uploading the flight plan (cf `uploadFlightPlan(filepath:customFlightPlanId:)` + /// * but **before** modifying the camera settings (camera settings that should be effective + /// during the flight plan execution) + /// * and **before** activating the flight plan (cf `activate(restart:)`, + /// `activate(restart:interpreter:)` `activate(restart:interpreter:missionItem:)` and + /// `activate(restart:interpreter:missionItem:disconnectionPolicy:)`). + /// + /// - note: The preparation is in a best-effort basis and thus can fail. In that case the drone + /// will perform _no_ action of restoring any setting. + func prepareForFlightPlanActivation() } /// Flight Plan piloting interface for drones. diff --git a/GroundSdk/Device/PilotingItf/PilotingItf.swift b/GroundSdk/Device/PilotingItf/PilotingItf.swift index a00b79e..2199735 100644 --- a/GroundSdk/Device/PilotingItf/PilotingItf.swift +++ b/GroundSdk/Device/PilotingItf/PilotingItf.swift @@ -44,34 +44,34 @@ public protocol PilotingItfClassDesc: ComponentApiDescriptor { @objcMembers @objc(GSPilotingItfs) public class PilotingItfs: NSObject { - /// Piloting interface of a copter for manual piloting. - public static let manualCopter = ManualCopterPilotingItfs() - /// Piloting interface for the return home feature. - public static let returnHome = ReturnHomePilotingItfs() - /// Piloting interface for the flight plan. - public static let flightPlan = FlightPlanPilotingItfs() /// Piloting interface for the animations. public static let animation = AnimationPilotingItfs() + /// Piloting interface for the flight plan. + public static let flightPlan = FlightPlanPilotingItfs() + /// Piloting interface for FollowMe mode. + public static let followMe = FollowMePilotingItfs() /// Piloting interface for guided piloting. public static let guided = GuidedPilotingItfs() - /// Piloting interface for Point Of Interest piloting. - public static let pointOfInterest = PointOfInterestPilotingItfs() /// Piloting interface for LookAt Mode. public static let lookAt = LookAtPilotingItfs() - /// Piloting interface for FollowMe mode. - public static let followMe = FollowMePilotingItfs() + /// Piloting interface of a copter for manual piloting. + public static let manualCopter = ManualCopterPilotingItfs() + /// Piloting interface for Point Of Interest piloting. + public static let pointOfInterest = PointOfInterestPilotingItfs() + /// Piloting interface for the return home feature. + public static let returnHome = ReturnHomePilotingItfs() } /// Piloting interfaces uid. enum PilotingItfUid: Int { - case manualCopter - case returnHome - case flightPlan case animation + case flightPlan + case followMe case guided - case pointOfInterest case lookAt - case followMe + case manualCopter + case pointOfInterest + case returnHome } /// Objective-C wrapper of Ref. Required because swift generics can't be used from Objective-C. diff --git a/GroundSdk/Device/PilotingItf/ReturnHomePilotingItf.swift b/GroundSdk/Device/PilotingItf/ReturnHomePilotingItf.swift index 30d2944..9d58b81 100644 --- a/GroundSdk/Device/PilotingItf/ReturnHomePilotingItf.swift +++ b/GroundSdk/Device/PilotingItf/ReturnHomePilotingItf.swift @@ -109,7 +109,7 @@ public enum ReturnHomeTarget: Int, CustomStringConvertible { /// Set containing all possible values of return home target. public static let allCases: Set = [.none, .takeOffPosition, .customPosition, .controllerPosition, - .trackedTargetPosition] + .trackedTargetPosition] } /// Return Home ending behavior @@ -142,21 +142,27 @@ public enum ReturnHomeReason: Int, CustomStringConvertible, CaseIterable { case powerLow /// Returning home because the drone's propeller(s) are critically iced. case icedPropeller + /// Returning home because the battery is not connected properly. + case batteryPoorConnection /// Return home is finished and is not active anymore. case finished /// Return to home could not find a path to home. case blocked + /// Return home after a flightplan + case flightplan /// Debug description. public var description: String { switch self { - case .none: return "none" - case .userRequested: return "userRequested" - case .connectionLost: return "connectionLost" - case .powerLow: return "powerLow" - case .icedPropeller: return "icedPropeller" - case .finished: return "finished" - case .blocked: return "blocked" + case .none: return "none" + case .userRequested: return "userRequested" + case .connectionLost: return "connectionLost" + case .powerLow: return "powerLow" + case .icedPropeller: return "icedPropeller" + case .batteryPoorConnection: return "batteryPoorConnection" + case .finished: return "finished" + case .blocked: return "blocked" + case .flightplan: return "flightplan" } } } diff --git a/GroundSdk/Device/RemoteControl.swift b/GroundSdk/Device/RemoteControl.swift index 6b7840c..b920cd1 100644 --- a/GroundSdk/Device/RemoteControl.swift +++ b/GroundSdk/Device/RemoteControl.swift @@ -46,26 +46,31 @@ public class RemoteControl: NSObject, InstrumentProvider, PeripheralProvider { /// Sky Controller UA remote control. case skyCtrlUA + /// Sky Controller 4 Black remote control. + case skyCtrl4Black + /// Internal unique identifier. public var internalId: Int { switch self { - case .skyCtrl3: return 0x0918 - case .skyCtrl4: return 0x091d - case .skyCtrlUA: return 0x091c + case .skyCtrl3: return 0x0918 + case .skyCtrl4: return 0x091d + case .skyCtrl4Black: return 0x0921 + case .skyCtrlUA: return 0x091c } } /// Debug description. public var description: String { switch self { - case .skyCtrl3: return "skyCtrl3" - case .skyCtrl4: return "skyCtrl4" - case .skyCtrlUA: return "skyCtrlUA" + case .skyCtrl3: return "skyCtrl3" + case .skyCtrl4: return "skyCtrl4" + case .skyCtrl4Black: return "skyCtrl4Black" + case .skyCtrlUA: return "skyCtrlUA" } } /// Set containing all possible models of remote controls. - static let allCases: Set = [.skyCtrl3, .skyCtrl4, .skyCtrlUA] + static let allCases: Set = [.skyCtrl3, .skyCtrl4, .skyCtrl4Black, .skyCtrlUA] } /// Remote control unique identifier, persistant between sessions. diff --git a/GroundSdk/Facility/Facility.swift b/GroundSdk/Facility/Facility.swift index 4b3b156..e4dc162 100644 --- a/GroundSdk/Facility/Facility.swift +++ b/GroundSdk/Facility/Facility.swift @@ -46,47 +46,47 @@ public protocol FacilityClassDesc: ComponentApiDescriptor { public class Facilities: NSObject { /// Automatic connection facility. public static let autoConnection = AutoConnectionDesc() + /// Black box reporter facility. + public static let blackBoxReporter = BlackBoxReporterDesc() /// Crash reporter facility. public static let crashReporter = CrashReporterDesc() + /// Event logger facility. + public static let eventLogger = EventLoggerDesc() /// Firmware update facility. public static let firmwareManager = UpdateManagerDesc() - /// Black box reporter facility. - public static let blackBoxReporter = BlackBoxReporterDesc() - /// User location facility. - public static let userLocation = UserLocationDesc() - /// User heading facility. - public static let userHeading = UserHeadingDesc() - /// Reverse geocoder facility. - public static let reverseGeocoder = ReverseGeocoderDesc() + /// Flight camera record reporter facility. + public static let flightCameraRecordReporter = FlightCameraRecordReporterDesc() /// Flight data manager facility. public static let flightDataManager = FlightDataManagerDesc() - /// User account facility. - public static let userAccount = UserAccountDesc() /// Flight log reporter facility. public static let flightLogReporter = FlightLogReporterDesc() - /// Flight camera record reporter facility. - public static let flightCameraRecordReporter = FlightCameraRecordReporterDesc() /// Gutma log manager facility. public static let gutmaLogManager = GutmaLogManagerDesc() - /// Event logger facility. - public static let eventLogger = EventLoggerDesc() + /// Reverse geocoder facility. + public static let reverseGeocoder = ReverseGeocoderDesc() + /// User account facility. + public static let userAccount = UserAccountDesc() + /// User heading facility. + public static let userHeading = UserHeadingDesc() + /// User location facility. + public static let userLocation = UserLocationDesc() } /// Facilities uid. enum FacilityUid: Int { - case autoConnection = 1 + case autoConnection + case blackBoxReporter case crashReporter + case eventLogger case firmwareManager - case blackBoxReporter - case userLocation - case userHeading - case reverseGeocoder + case flightCameraRecordReporter case flightDataManager - case userAccount case flightLogReporter - case flightCameraRecordReporter case gutmaLogManager - case eventLogger + case reverseGeocoder + case userAccount + case userHeading + case userLocation } /// Objective-C wrapper of Ref. Required because swift generics can't be used from Objective-C diff --git a/GroundSdk/GroundSdk.swift b/GroundSdk/GroundSdk.swift index 508b1c2..ca50289 100644 --- a/GroundSdk/GroundSdk.swift +++ b/GroundSdk/GroundSdk.swift @@ -278,6 +278,20 @@ public class GroundSdk: NSObject { observer: @escaping (_ stream: FileReplay?) -> Void) -> Ref? { return session.newFileReplay(source: source, observer: observer) } + + /// Collects latest logs from the given sources and bundles them in an archive in the given destination directory. + /// + /// - Parameters: + /// - sources: sources of the logs to collect + /// - directory: destination directory + /// - observer: observer called when the LogCollector changes, indicating collection progress + /// - Returns: a reference on a LogCollector. Caller must keep this instance referenced until all logs are + /// collected. Setting it to `nil` cancels the collection. + public func collectLogs(from sources: Set, + toDirectory directory: URL, + observer: @escaping (LogCollector?) -> Void) -> Ref { + return session.newLogCollector(from: sources, toDirectory: directory, observer: observer) + } } /// Objective-C extension adding GroundSdk swift methods that can't be automatically converted. diff --git a/GroundSdk/Hmd/internal/GroundGL/GGLView.swift b/GroundSdk/Hmd/internal/GroundGL/GGLView.swift index 6aa9b1a..f02db22 100644 --- a/GroundSdk/Hmd/internal/GroundGL/GGLView.swift +++ b/GroundSdk/Hmd/internal/GroundGL/GGLView.swift @@ -99,7 +99,7 @@ internal class GGLView: GLKView { } private func contextInit() { - context = EAGLContext.init(api: EAGLRenderingAPI.openGLES3)! + context = EAGLContext(api: EAGLRenderingAPI.openGLES3)! contentScaleFactor = UIScreen.main.scale self.drawableMultisample = .multisample4X self.drawableColorFormat = .RGBA8888 diff --git a/GroundSdk/Internal/Device/Instrument/BatteryInfoCore.swift b/GroundSdk/Internal/Device/Instrument/BatteryInfoCore.swift index 30d985c..0bcafc6 100644 --- a/GroundSdk/Internal/Device/Instrument/BatteryInfoCore.swift +++ b/GroundSdk/Internal/Device/Instrument/BatteryInfoCore.swift @@ -68,6 +68,9 @@ public class BatteryInfoCore: InstrumentCore, BatteryInfo { /// Battery cell voltages in mV public private(set) var cellVoltages: [UInt?] = [] + /// Battery components' versions + public private(set) var version: BatteryVersion? + /// Debug description public override var description: String { return "BatteryInfo: level = \(batteryLevel)" @@ -208,6 +211,21 @@ extension BatteryInfoCore { } return self } + + /// Changes battery version. + /// + /// - Parameters: + /// - version: the battery version to set + /// + /// - Returns: self to allow call chaining + /// - Note: Changes are not notified until notifyUpdated() is called. + @discardableResult public func update(version newValue: BatteryVersion) -> BatteryInfoCore { + if version != newValue { + version = newValue + markChanged() + } + return self + } } // MARK: Objective-C API diff --git a/GroundSdk/Internal/Device/Instrument/CellularLinkStatusCore.swift b/GroundSdk/Internal/Device/Instrument/CellularLinkCore.swift similarity index 82% rename from GroundSdk/Internal/Device/Instrument/CellularLinkStatusCore.swift rename to GroundSdk/Internal/Device/Instrument/CellularLinkCore.swift index 9314872..91bbb2d 100644 --- a/GroundSdk/Internal/Device/Instrument/CellularLinkStatusCore.swift +++ b/GroundSdk/Internal/Device/Instrument/CellularLinkCore.swift @@ -29,35 +29,35 @@ import Foundation -/// CellularLinkStatus instrument implementation. -public class CellularLinkStatusCore: InstrumentCore, CellularLinkStatus { +/// CellularLink instrument implementation. +public class CellularLinkCore: InstrumentCore, CellularLink { /// Celullar link status, or `nil` if not available. - public var status: CellularLinkStatusStatus? + public var status: CellularLinkStatus? /// Debug description public override var description: String { - return "CellularLinkStatusCore: status \(status?.description ?? "nil")" + return "CellularLinkCore: status \(status?.description ?? "nil")" } /// Constructor. /// /// - Parameter store: component store owning this component public init(store: ComponentStoreCore) { - super.init(desc: Instruments.cellularLinkStatus, store: store) + super.init(desc: Instruments.cellularLink, store: store) } } /// Backend callback methods. -extension CellularLinkStatusCore { +extension CellularLinkCore { /// Updates cellular link status. /// - /// - Parameter status: new status + /// - Parameter status: new cellular link status /// - Returns: self to allow call chaining /// - Note: Changes are not notified until notifyUpdated() is called. @discardableResult - public func update(status newValue: CellularLinkStatusStatus?) -> CellularLinkStatusCore { + public func update(status newValue: CellularLinkStatus?) -> CellularLinkCore { if status != newValue { markChanged() status = newValue diff --git a/GroundSdk/Internal/Device/Instrument/CellularSessionCore.swift b/GroundSdk/Internal/Device/Instrument/CellularSessionCore.swift new file mode 100644 index 0000000..d003c76 --- /dev/null +++ b/GroundSdk/Internal/Device/Instrument/CellularSessionCore.swift @@ -0,0 +1,67 @@ +// Copyright (C) 2022 Parrot Drones SAS +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in +// the documentation and/or other materials provided with the +// distribution. +// * Neither the name of the Parrot Company nor the names +// of its contributors may be used to endorse or promote products +// derived from this software without specific prior written +// permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// PARROT COMPANY BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +// OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +// AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +// OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT +// OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF +// SUCH DAMAGE. + +import Foundation + +/// CellularSession instrument implementation. +public class CellularSessionCore: InstrumentCore, CellularSession { + + /// Celullar session status, or `nil` if not available. + public var status: CellularSessionStatus? + + /// Debug description + public override var description: String { + return "CellularSessionCore: status \(status?.description ?? "nil")" + } + + /// Constructor. + /// + /// - Parameter store: component store owning this component + public init(store: ComponentStoreCore) { + super.init(desc: Instruments.cellularSession, store: store) + } +} + +/// Backend callback methods. +extension CellularSessionCore { + + /// Updates cellular session status. + /// + /// - Parameter status: new cellular session status + /// - Returns: self to allow call chaining + /// - Note: Changes are not notified until notifyUpdated() is called. + @discardableResult + public func update(status newValue: CellularSessionStatus?) -> CellularSessionCore { + if status != newValue { + markChanged() + status = newValue + } + return self + } +} diff --git a/GroundSdk/Internal/Device/Peripheral/DebugShellCore.swift b/GroundSdk/Internal/Device/Peripheral/DebugShellCore.swift new file mode 100644 index 0000000..82a050d --- /dev/null +++ b/GroundSdk/Internal/Device/Peripheral/DebugShellCore.swift @@ -0,0 +1,172 @@ +// Copyright (C) 2022 Parrot Drones SAS +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in +// the documentation and/or other materials provided with the +// distribution. +// * Neither the name of the Parrot Company nor the names +// of its contributors may be used to endorse or promote products +// derived from this software without specific prior written +// permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// PARROT COMPANY BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +// OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +// AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +// OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT +// OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF +// SUCH DAMAGE. + +import Foundation + +/// Debug shell backend part. +public protocol DebugShellBackend: AnyObject { + /// Sets debug shell state + /// + /// - Parameter state: the new debug shell state + /// - Returns: `true` if the command has been sent, `false` if not connected. + func set(state: DebugShellState) -> Bool +} + +/// Debug shell parameter +class DebugShellStateSettingCore: DebugShellStateSetting, CustomStringConvertible { + /// Delegate called when the setting value is changed by setting `value` property + private unowned let didChangeDelegate: SettingChangeDelegate + + /// Timeout object. + /// + /// Visibility is internal for testing purposes + let timeout = SettingTimeout() + + /// Tells if the setting value has been changed and is waiting for change confirmation + var updating: Bool { timeout.isScheduled } + + var value: DebugShellState { + get { _value } + set { + if _value != newValue { + if backend(newValue) { + let oldValue = _value + // value sent to the backend, update setting value and mark it updating + _value = newValue + timeout.schedule { [weak self] in + if let `self` = self, self.update(value: oldValue) { + self.didChangeDelegate.userDidChangeSetting() + } + } + didChangeDelegate.userDidChangeSetting() + } + } + } + } + + /// Current debug shell state value + private var _value: DebugShellState = .disabled + + /// Closure to call to change the value. Return true if the new value has been sent and setting + /// must become updating + private let backend: (DebugShellState) -> Bool + + /// Constructor + /// + /// - Parameters: + /// - didChangeDelegate: delegate called when the setting value is changed by setting `value` + /// property + /// - backend: closure to call to change the setting value + init(didChangeDelegate: SettingChangeDelegate, + backend: @escaping (DebugShellState) -> Bool) { + self.didChangeDelegate = didChangeDelegate + self.backend = backend + } + + /// Called by the backend, change the setting data + /// + /// - Parameter value: new state + /// - Returns: `true` if the setting has been changed, `false` otherwise + func update(value newValue: DebugShellState) -> Bool { + if updating || _value != newValue { + _value = newValue + timeout.cancel() + return true + } + return false + } + + /// Cancels any pending rollback. + /// + /// - Parameter completionClosure: block that will be called if a rollback was pending + func cancelRollback(completionClosure: () -> Void) { + if timeout.cancel() { + completionClosure() + } + } + + var description: String { + "DebugShellStateSetting: \(_value) updating: [\(updating)]" + } + +} + +/// Internal Debug Shell peripheral implementation +public class DebugShellCore: PeripheralCore, DebugShell { + + public var state: DebugShellStateSetting { _state } + + /// State setting internal implementation + private var _state: DebugShellStateSettingCore! + + /// Implementation backend + private unowned let backend: DebugShellBackend + + /// Constructor + /// + /// - Parameters: + /// - store: store where this peripheral will be stored + /// - backend: DebugShell backend + public init(store: ComponentStoreCore, backend: DebugShellBackend) { + self.backend = backend + super.init(desc: Peripherals.debugShell, store: store) + _state = DebugShellStateSettingCore(didChangeDelegate: self) { [unowned self] state in + self.backend.set(state: state) + } + } + + public override var description: String { + "DebugShell: state = \(state)" + } +} + +/// Backend callback methods +extension DebugShellCore { + /// Changes current state. + /// + /// - Parameter enabled: new value + /// - Returns: self to allow call chaining + /// - Note: Changes are not notified until notifyUpdated() is called. + @discardableResult public func update(state newState: DebugShellState) -> Self { + if _state.update(value: newState) { + markChanged() + } + return self + } + + /// Cancels all pending settings rollbacks. + /// + /// - Returns: self to allow call chaining + /// - Note: Changes are not notified until notifyUpdated() is called. + @discardableResult + public func cancelSettingsRollback() -> Self { + _state.cancelRollback { markChanged() } + return self + } +} diff --git a/GroundSdk/Internal/Device/Peripheral/DroneFinderCore.swift b/GroundSdk/Internal/Device/Peripheral/DroneFinderCore.swift index 2126957..c227c24 100644 --- a/GroundSdk/Internal/Device/Peripheral/DroneFinderCore.swift +++ b/GroundSdk/Internal/Device/Peripheral/DroneFinderCore.swift @@ -65,7 +65,7 @@ public class DiscoveredDroneCore: DiscoveredDrone { } } -/// Internal manual copter piloting interface implementation +/// Internal drone finder implementation public class DroneFinderCore: PeripheralCore, DroneFinder { /// Implementation backend diff --git a/GroundSdk/Internal/Device/Peripheral/LatestLogDownloaderCore.swift b/GroundSdk/Internal/Device/Peripheral/LatestLogDownloaderCore.swift new file mode 100644 index 0000000..222fb3e --- /dev/null +++ b/GroundSdk/Internal/Device/Peripheral/LatestLogDownloaderCore.swift @@ -0,0 +1,111 @@ +// Copyright (C) 2022 Parrot Drones SAS +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in +// the documentation and/or other materials provided with the +// distribution. +// * Neither the name of the Parrot Company nor the names +// of its contributors may be used to endorse or promote products +// derived from this software without specific prior written +// permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// PARROT COMPANY BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +// OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +// AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +// OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT +// OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF +// SUCH DAMAGE. + +import Foundation + +/// LatestLogDownloader backend part. +public protocol LatestLogDownloaderBackend: AnyObject { + + /// Downloads the device logs for the current boot id. + func downloadLogs(toDirectory directory: URL) + + /// Cancels an ongoing log download. + func cancelDownload() +} + +/// Internal implementation of the LatestLogDownloader. +public class LatestLogDownloaderCore: PeripheralCore, LatestLogDownloader { + + /// Implementation backend. + private unowned let backend: LatestLogDownloaderBackend + + public private(set) var state: LogCollectorState + + /// Constructor + /// + /// - Parameters: + /// - store: store where this peripheral will be stored + /// - backend: LatestLogDownloader backend + public init(store: ComponentStoreCore, backend: LatestLogDownloaderBackend) { + state = LogCollectorState() + self.backend = backend + super.init(desc: Peripherals.latestLogDownloader, store: store) + } + + public func downloadLogs(toDirectory directory: URL) { + backend.downloadLogs(toDirectory: directory) + } + + public func cancelDownload() { + backend.cancelDownload() + } +} + +/// Backend callback methods +extension LatestLogDownloaderCore { + + /// Updates download status. + /// + /// - Parameter status: new status + /// - Returns: self to allow call chaining + /// - Note: Changes are not notified until notifyUpdated() is called. + @discardableResult public func update(status: LogCollectorStatus) -> LatestLogDownloaderCore { + if state.status != status { + state.status = status + markChanged() + } + return self + } + + /// Updates total size. + /// + /// - Parameter totalSize: new total size + /// - Returns: self to allow call chaining + /// - Note: Changes are not notified until notifyUpdated() is called. + @discardableResult public func update(totalSize: UInt64?) -> LatestLogDownloaderCore { + if state.totalSize != totalSize { + state.totalSize = totalSize + markChanged() + } + return self + } + + /// Updates collected size. + /// + /// - Parameter collectedSize: new collected size + /// - Returns: self to allow call chaining + /// - Note: Changes are not notified until notifyUpdated() is called. + @discardableResult public func update(collectedSize: UInt64?) -> LatestLogDownloaderCore { + if state.collectedSize != collectedSize { + state.collectedSize = collectedSize + markChanged() + } + return self + } +} diff --git a/GroundSdk/Internal/Device/Peripheral/LogControlCore.swift b/GroundSdk/Internal/Device/Peripheral/LogControlCore.swift index 026283d..2cfe7a0 100644 --- a/GroundSdk/Internal/Device/Peripheral/LogControlCore.swift +++ b/GroundSdk/Internal/Device/Peripheral/LogControlCore.swift @@ -38,10 +38,18 @@ public protocol LogControlBackend: AnyObject { /// /// - Returns: `true` if the deactivation has been asked, `false` otherwise func deactivateLogs() -> Bool + + /// Requests the (de)activation of mission logs. + /// + /// - Parameter activate: Whether to activate or deactivate the mission logs. + /// + /// - Returns: `true` if the (de)activation has been asked `false` otherwise. + func activateMissionLogs(_ activate: Bool) -> Bool } /// Internal log control peripheral implementation public class LogControlCore: PeripheralCore, LogControl { + /// Implementation backend private unowned let backend: LogControlBackend @@ -51,6 +59,14 @@ public class LogControlCore: PeripheralCore, LogControl { /// Indicates if the deactivate command is supported private (set) public var canDeactivateLogs: Bool = false + /// Indicates if the mission logs are enabled on the drone. + public var missionLogs: BoolSetting? { + _missionLogs + } + + /// Internal storage for mission logs setting. + private var _missionLogs: BoolSettingCore? + /// Constructor /// /// - Parameters: @@ -59,12 +75,20 @@ public class LogControlCore: PeripheralCore, LogControl { public init(store: ComponentStoreCore, backend: LogControlBackend) { self.backend = backend super.init(desc: Peripherals.logControl, store: store) + self._missionLogs = BoolSettingCore(didChangeDelegate: self, backend: { value in + backend.activateMissionLogs(value) + }) } /// Requests the deactivation of logs. public func deactivateLogs() -> Bool { return backend.deactivateLogs() } + + /// Requests the (de)activation of mission logs. + public func activateMissionLogs(_ activate: Bool) -> Bool { + backend.activateMissionLogs(activate) + } } extension LogControlCore { @@ -93,4 +117,11 @@ extension LogControlCore { } return self } + + @discardableResult public func update(areMissionLogsEnabled newValue: Bool) -> LogControlCore { + if _missionLogs!.update(value: newValue) { + markChanged() + } + return self + } } diff --git a/GroundSdk/Internal/Device/Peripheral/NetworkControlCore.swift b/GroundSdk/Internal/Device/Peripheral/NetworkControlCore.swift index 1e14e10..0a1f74a 100644 --- a/GroundSdk/Internal/Device/Peripheral/NetworkControlCore.swift +++ b/GroundSdk/Internal/Device/Peripheral/NetworkControlCore.swift @@ -78,7 +78,7 @@ class NetworkControlRoutingSettingCore: NetworkControlRoutingSetting, CustomDebu let oldValue = _policy // value sent to the backend, update setting value and mark it updating _policy = newValue - timeout.schedule { [weak self] in + timeout.schedule(timeout: 10) { [weak self] in if let `self` = self, self.update(policy: oldValue) { self.didChangeDelegate.userDidChangeSetting() } diff --git a/GroundSdk/Internal/Device/PilotingItf/FlightPlanPilotingItfCore.swift b/GroundSdk/Internal/Device/PilotingItf/FlightPlanPilotingItfCore.swift index 1a12d26..da7d95f 100644 --- a/GroundSdk/Internal/Device/PilotingItf/FlightPlanPilotingItfCore.swift +++ b/GroundSdk/Internal/Device/PilotingItf/FlightPlanPilotingItfCore.swift @@ -77,6 +77,17 @@ public protocol FlightPlanPilotingItfBackend: ActivablePilotingItfBackend { /// - Returns: a clean media resources cancelable request func cleanBeforeRecovery(customId: String, resourceId: String, completion: @escaping (_ result: CleanBeforeRecoveryResult) -> Void) -> CancelableCore? + + /// - important: DO NOT USE THIS METHOD, IT IS UNSTABLE, EXPERIMENTAL AND + /// WILL DISAPPEAR ON THE NEXT VERSION + /// + /// TODO: remove + /// + /// Prepares the drone for the upcoming flight plan activation. + /// + /// The drone will prepare the execution of a flight plan. This includes storing the current + /// camera settings that will be restored at the end of the flight plan. + func prepareForFlightPlanActivation() } /// Core implementation of the `FlightPlanPilotingItf`. @@ -206,6 +217,10 @@ public class FlightPlanPilotingItfCore: ActivablePilotingItfCore, FlightPlanPilo completion: @escaping (CleanBeforeRecoveryResult) -> Void) -> CancelableCore? { flightPlanBackend.cleanBeforeRecovery(customId: customId, resourceId: resourceId, completion: completion) } + + public func prepareForFlightPlanActivation() { + flightPlanBackend.prepareForFlightPlanActivation() + } } /// Backend callback methods diff --git a/GroundSdk/Internal/Engine/BlackBox/BlackBoxCollector.swift b/GroundSdk/Internal/Engine/BlackBox/BlackBoxCollector.swift index 220b98b..a7874cd 100644 --- a/GroundSdk/Internal/Engine/BlackBox/BlackBoxCollector.swift +++ b/GroundSdk/Internal/Engine/BlackBox/BlackBoxCollector.swift @@ -233,10 +233,11 @@ class BlackBoxCollector { /// - Note: This function **must** be called from the `ioQueue`. /// - Parameter url: url of the black box to delete private func doDeleteBlackBox(at url: URL) { + ULog.d(.parrotCloudBlackBoxTag, "Delete black box \(url)") do { try FileManager.default.removeItem(at: url) } catch let err { - ULog.e(.blackBoxEngineTag, "Failed to delete \(url.path): \(err)") + ULog.e(.parrotCloudBlackBoxTag, "Failed to delete \(url.path): \(err)") } } } diff --git a/GroundSdk/Internal/Engine/BlackBox/BlackBoxUploader.swift b/GroundSdk/Internal/Engine/BlackBox/BlackBoxUploader.swift index fea1fa0..20173c8 100644 --- a/GroundSdk/Internal/Engine/BlackBox/BlackBoxUploader.swift +++ b/GroundSdk/Internal/Engine/BlackBox/BlackBoxUploader.swift @@ -34,45 +34,44 @@ class BlackBoxUploader { /// Uploader error enum UploadError: Error { - /// Report is not well formed. Hence, it can be deleted. - case badReport - /// Server error. crash report should not be deleted because another try might succeed. + /// Black box is not well formed. Hence, it can be deleted. + case badBlackBox + /// Server error, black box should not be deleted because another try might succeed. case serverError - /// Connection error, crash report should not be deleted because another try might succeed. + /// Connection error, black box should not be deleted because another try might succeed. case connectionError - /// Request sent had an error. Crash report can be deleted even though the file is not corrupted to avoid + /// Request sent had an error, black box can be deleted even though the file is not corrupted to avoid /// infinite retry. /// This kind of error is a development error and can normally be fixed in the code. case badRequest - /// Upload has been canceled. Crash report should be kept in order to retry its upload later. + /// Upload has been canceled, black box should be kept in order to retry its upload later. case canceled } /// Prototype of the callback of upload completion /// /// - Parameters: - /// - report: the report that should have been uploaded + /// - blackBox: the black box that should have been uploaded /// - error: the error if upload was not successful, nil otherwise - public typealias CompletionCallback = (_ report: BlackBox, _ error: UploadError?) -> Void + public typealias CompletionCallback = (_ blackBox: BlackBox, _ error: UploadError?) -> Void /// Cloud server utility private let cloudServer: CloudServerCore /// Constructor. /// - /// - Parameter cloudServer: the cloud server to upload reports with + /// - Parameter cloudServer: the cloud server to upload black boxes with init(cloudServer: CloudServerCore) { self.cloudServer = cloudServer } - /// Upload a crash report on Parrot cloud server. + /// Upload a black box on Parrot cloud server. /// /// - Parameters: /// - blackBox: the black box to upload /// - completionCallback: closure that will be called when the upload completes. /// - Returns: a request that can be canceled. func upload(blackBox: BlackBox, completionCallback: @escaping CompletionCallback) -> CancelableCore { - ULog.d(.crashReportEngineTag, "Will upload black box \(blackBox.url)") return cloudServer.sendFile( api: "/apiv1/bbox", fileUrl: blackBox.url, method: .post, @@ -92,8 +91,8 @@ class BlackBoxUploader { _ where errorCode >= 500: // server error, try again later uploadError = .serverError default: - // by default, blame the error on the report in order to delete it. - uploadError = .badReport + // by default, blame the error on the black box in order to delete it. + uploadError = .badBlackBox } case .error(let error): switch (error as NSError).urlError { @@ -102,8 +101,8 @@ class BlackBoxUploader { case .connectionError: uploadError = .connectionError case .otherError: - // by default, blame the error on the report in order to delete it. - uploadError = .badReport + // by default, blame the error on the black box in order to delete it. + uploadError = .badBlackBox } case .canceled: uploadError = .canceled diff --git a/GroundSdk/Internal/Engine/BlackBoxEngine.swift b/GroundSdk/Internal/Engine/BlackBoxEngine.swift index 02562ee..8733219 100644 --- a/GroundSdk/Internal/Engine/BlackBoxEngine.swift +++ b/GroundSdk/Internal/Engine/BlackBoxEngine.swift @@ -54,7 +54,7 @@ class BlackBoxEngine: EngineBaseCore { let workDir: URL /// Name of the directory in which the black boxes should be stored - private let reportsDirName = "BlackBoxes" + private let blackBoxesDirName = "BlackBoxes" /// Monitor of the connectivity changes private var connectivityMonitor: MonitorCore! @@ -65,16 +65,16 @@ class BlackBoxEngine: EngineBaseCore { /// User account information private var userAccountInfo: UserAccountInfoCore? - /// Black box reports collector + /// Black box collector private var collector: BlackBoxCollector? - /// List of reports waiting for upload. + /// List of black boxes waiting for upload. /// - /// This list is used as a queue: new reports are added at the end, report to upload is the first one. - /// The report to upload is removed from this list after it is fully and correctly uploaded. + /// This list is used as a queue: new black boxes are added at the end, black box to upload is the first one. + /// The black box to upload is removed from this list after it is fully and correctly uploaded. /// /// - Note: visibility is internal for testing purposes only. - private(set) var pendingReports: [BlackBox] = [] + private(set) var pendingBlackBoxes: [BlackBox] = [] /// The uploader. /// `nil` until engine is started. @@ -94,7 +94,7 @@ class BlackBoxEngine: EngineBaseCore { ULog.d(.blackBoxEngineTag, "Loading BlackBoxEngine.") let cacheDirUrl = FileManager.default.urls(for: .cachesDirectory, in: .userDomainMask).first! - engineDir = cacheDirUrl.appendingPathComponent(reportsDirName, isDirectory: true) + engineDir = cacheDirUrl.appendingPathComponent(blackBoxesDirName, isDirectory: true) workDir = engineDir.appendingPathComponent(UUID().uuidString, isDirectory: true) spaceQuotaInMb = GroundSdkConfig.sharedInstance.blackBoxQuotaMb ?? 0 @@ -117,7 +117,7 @@ class BlackBoxEngine: EngineBaseCore { || (newInfo?.account != nil && newInfo?.dataUploadPolicy != .deny // keep old data until upload is allowed && newInfo?.oldDataPolicy == .denyUpload)) { - ULog.d(.myparrot, + ULog.d(.parrotCloudBlackBoxTag, "User account change with private mode or old data upload denied -> delete all black boxes") self.stopAndDropAllBlackBoxes() self.userAccountInfo = newInfo @@ -135,7 +135,8 @@ class BlackBoxEngine: EngineBaseCore { collector = createCollector() collector?.collectBlackBoxes { [weak self] blackBoxes in if let `self` = self, self.started { - self.pendingReports.append(contentsOf: blackBoxes) + ULog.d(.parrotCloudBlackBoxTag, "Black boxes locally collected: \(blackBoxes)") + self.pendingBlackBoxes.append(contentsOf: blackBoxes) self.startBlackBoxUploadProcess() } } @@ -164,7 +165,7 @@ class BlackBoxEngine: EngineBaseCore { uploader = nil collector?.cancelCollection() collector = nil - pendingReports = [] + pendingBlackBoxes = [] connectivityMonitor.stop() } @@ -175,9 +176,9 @@ class BlackBoxEngine: EngineBaseCore { guard userAccountInfo?.privateMode == false else { return } - collector?.archive(blackBoxData: blackBoxData) { [weak self] report in - self?.pendingReports.append(report) - ULog.d(.myparrot, "BLACKBOX append \(report)") + collector?.archive(blackBoxData: blackBoxData) { [weak self] blackBox in + ULog.d(.parrotCloudBlackBoxTag, "Add a file: \(blackBox)") + self?.pendingBlackBoxes.append(blackBox) self?.startBlackBoxUploadProcess() } } @@ -196,9 +197,11 @@ class BlackBoxEngine: EngineBaseCore { /// uploading process is only started when it is not already uploading files. private func startBlackBoxUploadProcess() { guard !blackBoxReporter.isUploading else { - blackBoxReporter.update(pendingCount: pendingReports.count) + blackBoxReporter.update(pendingCount: pendingBlackBoxes.count) + ULog.d(.parrotCloudBlackBoxTag, "Did not start black box upload process (already uploading)") return } + ULog.d(.parrotCloudBlackBoxTag, "Start black box upload process") processNextBlackBox() } @@ -208,92 +211,108 @@ class BlackBoxEngine: EngineBaseCore { /// is available, and if userAccount is set. A filter will be done on creation date if user deny upload of old /// file created before the user account was present. private func processNextBlackBox() { - blackBoxReporter.update(pendingCount: pendingReports.count) - if self.userAccountInfo?.account == nil - || (self.userAccountInfo?.dataUploadPolicy != .full - && self.userAccountInfo?.dataUploadPolicy != .noMedia) - || utilities.getUtility(Utilities.internetConnectivity)?.internetAvailable == false { + blackBoxReporter.update(pendingCount: pendingBlackBoxes.count) + + // Check if upload process can go on + let abortReason: String? + if userAccountInfo?.account == nil { + abortReason = "no account" + } else if userAccountInfo!.dataUploadPolicy != .full && userAccountInfo!.dataUploadPolicy != .noMedia { + abortReason = "denied by policy" + } else if uploader == nil { + abortReason = "no uploader" + } else if utilities.getUtility(Utilities.internetConnectivity)?.internetAvailable == false { + abortReason = "no internet" + } else if currentUploadRequest != nil { + abortReason = "upload request in progress" + } else { + abortReason = nil + } + + if let reason = abortReason { + ULog.d(.parrotCloudBlackBoxTag, "Stop black box upload process (\(reason))") blackBoxReporter.update(isUploading: false).notifyUpdated() - ULog.d(.myparrot, "BLACKBOX (no internet or no user, or upload denied))") return } - if let uploader = uploader, - currentUploadRequest == nil { - if let blackBox = pendingReports.first { - if self.userAccountInfo!.oldDataPolicy == .denyUpload { - // check if the file is before the authentication date - // if yes, we remove the file because the user did not accept the download of the data collected - // before the authentication - let toRemove: Bool - if let attrs = try? FileManager.default.attributesOfItem( - atPath: blackBox.url.path), let creationDate = attrs[.creationDate] as? Date, - let userDate = userAccountInfo?.changeDate { - toRemove = creationDate < userDate - if toRemove { - ULog.d(.myparrot, "BLACKBOX remove (creationDate < userDate)") - } - } else { - ULog.d(.myparrot, "BLACKBOX remove (no date)") - toRemove = true - } - if toRemove { - self.deleteBlackBox(blackBox) - self.processNextBlackBox() - return - } - } + guard let blackBox = pendingBlackBoxes.first else { + ULog.d(.parrotCloudBlackBoxTag, "Stop black box upload process (no file left)") + blackBoxReporter.update(isUploading: false).notifyUpdated() + return + } - blackBoxReporter.update(isUploading: true) - currentUploadRequest = uploader.upload(blackBox: blackBox) { report, error in - self.currentUploadRequest = nil - - if let error = error { - switch error { - case .badRequest: - ULog.d(.myparrot, "BLACKBOX .badRequest \(report)") - ULog.w(.blackBoxEngineTag, "Bad request sent to the server. This should be a dev error.") - // delete file and stop uploading to avoid multiple errors - self.deleteBlackBox(report) - self.blackBoxReporter.update(isUploading: false).notifyUpdated() - case .badReport: - ULog.d(.myparrot, "BLACKBOX .badReport \(report)") - self.deleteBlackBox(report) - self.processNextBlackBox() - case .serverError, - .connectionError: - ULog.d(.myparrot, "BLACKBOX .serverError, connectionError \(blackBox)") - // Stop uploading if the server is not accessible - self.blackBoxReporter.update(isUploading: false).notifyUpdated() - case .canceled: - ULog.d(.myparrot, "BLACKBOX .canceled \(report)") - self.blackBoxReporter.update(isUploading: false).notifyUpdated() - } - } else { // success - ULog.d(.myparrot, "BLACKBOX SUCCESS \(report)") - self.deleteBlackBox(report) - self.processNextBlackBox() - } + ULog.d(.parrotCloudBlackBoxTag, "Process next black box \(blackBox.url.absoluteString)") + + if userAccountInfo!.oldDataPolicy == .denyUpload { + // check if the file is before the authentication date + // if yes, we remove the file because the user did not accept the download of the data collected + // before the authentication + let toRemove: Bool + if let attrs = try? FileManager.default.attributesOfItem( + atPath: blackBox.url.path), let creationDate = attrs[.creationDate] as? Date, + let userDate = userAccountInfo?.changeDate { + toRemove = creationDate < userDate + if toRemove { + ULog.d(.parrotCloudBlackBoxTag, "Remove (creationDate < userDate)") } } else { - blackBoxReporter.update(isUploading: false) + ULog.d(.parrotCloudBlackBoxTag, "Remove (no date)") + toRemove = true + } + if toRemove { + deleteBlackBox(blackBox) + processNextBlackBox() + return + } + } + + ULog.d(.parrotCloudBlackBoxTag, "Start uploading \(blackBox.name)") + blackBoxReporter.update(isUploading: true) + + currentUploadRequest = uploader?.upload(blackBox: blackBox) { blackBox, error in + self.currentUploadRequest = nil + + if let error = error { + switch error { + case .badRequest: + ULog.d(.parrotCloudBlackBoxTag, "Upload error (bad request) \(blackBox.name)") + // delete file and stop uploading to avoid multiple errors + self.deleteBlackBox(blackBox) + self.blackBoxReporter.update(isUploading: false).notifyUpdated() + case .badBlackBox: + ULog.d(.parrotCloudBlackBoxTag, "Upload error (bad black box) \(blackBox.name)") + self.deleteBlackBox(blackBox) + self.processNextBlackBox() + case .serverError, + .connectionError: + ULog.d(.parrotCloudBlackBoxTag, "Upload error (server or connection) \(blackBox.name)") + // Stop uploading if the server is not accessible + self.blackBoxReporter.update(isUploading: false).notifyUpdated() + case .canceled: + ULog.d(.parrotCloudBlackBoxTag, "Upload canceled \(blackBox.name)") + self.blackBoxReporter.update(isUploading: false).notifyUpdated() + } + } else { // success + ULog.d(.parrotCloudBlackBoxTag, "Black box successfully uploaded \(blackBox.name)") + self.deleteBlackBox(blackBox) + self.processNextBlackBox() } } blackBoxReporter.notifyUpdated() } - /// Remove the given report from the pending ones and delete it from the file system. + /// Remove the given black box from the pending ones and delete it from the file system. /// - /// - Parameter blackBox: the black box report to delete + /// - Parameter blackBox: the black box to delete private func deleteBlackBox(_ blackBox: BlackBox) { - ULog.d(.myparrot, "BLACKBOX deleteBlackBox \(blackBox)") - if pendingReports.first == blackBox { - pendingReports.remove(at: 0) + ULog.d(.parrotCloudBlackBoxTag, "Delete black box \(blackBox.name)") + if pendingBlackBoxes.first == blackBox { + pendingBlackBoxes.remove(at: 0) } else { - ULog.w(.blackBoxEngineTag, "Uploaded report is not the first one of the pending") + ULog.w(.parrotCloudBlackBoxTag, "Black box to remove is not the first one of the pending list") // fallback - if let index: Int = pendingReports.firstIndex(where: {$0 == blackBox}) { - pendingReports.remove(at: index) + if let index: Int = pendingBlackBoxes.firstIndex(where: {$0 == blackBox}) { + pendingBlackBoxes.remove(at: index) } } @@ -302,7 +321,7 @@ class BlackBoxEngine: EngineBaseCore { /// Cancel the current upload if there is one. private func cancelCurrentUpload() { - ULog.d(.myparrot, "BLACKBOX cancel current upload request \(String(describing: self.currentUploadRequest))") + ULog.d(.parrotCloudBlackBoxTag, "Cancel current upload request \(String(describing: currentUploadRequest))") // stop current upload request self.currentUploadRequest?.cancel() self.currentUploadRequest = nil @@ -313,16 +332,16 @@ class BlackBoxEngine: EngineBaseCore { /// Note: this function is called when a user is no more identified (and has not accepted the terms of use and /// confidentiality). Blackboxes are only recorded, archived, and sent when a authorized account is present private func stopAndDropAllBlackBoxes() { - ULog.d(.myparrot, "BLACKBOX stopAndDropAllBlackBoxes") + ULog.d(.parrotCloudBlackBoxTag, "Stop and drop all black boxes") // stop the upload if any cancelCurrentUpload() - pendingReports.forEach { (blackBox) in + pendingBlackBoxes.forEach { (blackBox) in collector?.deleteBlackBox(at: blackBox.url) } // clear all pending blackBoxes - pendingReports.removeAll() + pendingBlackBoxes.removeAll() // update the facility blackBoxReporter.update(isUploading: false).update(pendingCount: 0).notifyUpdated() diff --git a/GroundSdk/Internal/Engine/CrashReportEngine.swift b/GroundSdk/Internal/Engine/CrashReportEngine.swift index 6a7f326..467bbcc 100644 --- a/GroundSdk/Internal/Engine/CrashReportEngine.swift +++ b/GroundSdk/Internal/Engine/CrashReportEngine.swift @@ -121,7 +121,7 @@ class CrashReportEngine: EngineBaseCore { || (newInfo?.account != nil && newInfo?.dataUploadPolicy != .deny // keep old data until upload is allowed && newInfo?.oldDataPolicy == .denyUpload)) { - ULog.d(.myparrot, + ULog.d(.crashReportEngineTag, "User account change with private mode or old data upload denied -> delete all reports") self.dropReports() self.userAccountInfo = newInfo diff --git a/GroundSdk/Internal/Engine/EventLogEngine.swift b/GroundSdk/Internal/Engine/EventLogEngine.swift index a083773..c20958d 100644 --- a/GroundSdk/Internal/Engine/EventLogEngine.swift +++ b/GroundSdk/Internal/Engine/EventLogEngine.swift @@ -279,15 +279,10 @@ private class FolderMonitor { if let self = self, let files = try? FileManager.default.contentsOfDirectory( at: self.url, includingPropertiesForKeys: nil, options: .skipsHiddenFiles) { - var newFile: URL? - for file in files { - if !(self.folderContent?.contains(file) ?? false) { - newFile = file - break - } - } self.folderContent = files - if let newFile = newFile { + if let newFile = files.first(where: { file in + self.folderContent?.contains(file) ?? false + }) { self.onNewFile(newFile) } } diff --git a/GroundSdk/Internal/Engine/FlightCameraRecordEngine.swift b/GroundSdk/Internal/Engine/FlightCameraRecordEngine.swift index 8f9be8c..a11e081 100644 --- a/GroundSdk/Internal/Engine/FlightCameraRecordEngine.swift +++ b/GroundSdk/Internal/Engine/FlightCameraRecordEngine.swift @@ -229,7 +229,7 @@ class FlightCameraRecordEngine: EngineBaseCore { || (newInfo?.account != nil && newInfo?.dataUploadPolicy != .deny // keep old data until upload is allowed && newInfo?.oldDataPolicy == .denyUpload)) { - ULog.d(.myparrot, + ULog.d(.parrotCloudFcrTag, "User account change with private mode or old data upload denied -> delete all records") self.dropFlightCameraRecords() self.userAccountInfo = newInfo diff --git a/GroundSdk/Internal/Engine/FlightLog/FlightLogCollector.swift b/GroundSdk/Internal/Engine/FlightLog/FlightLogCollector.swift index af16339..72e4345 100644 --- a/GroundSdk/Internal/Engine/FlightLog/FlightLogCollector.swift +++ b/GroundSdk/Internal/Engine/FlightLog/FlightLogCollector.swift @@ -152,11 +152,11 @@ class FlightLogCollector { /// - Note: This function **must** be called from the `ioQueue`. /// - Parameter url: url of the flightLog report to delete private func doDeleteFlightLog(at url: URL) { - ULog.d(.myparrot, "Delete FlightLog \(url)") + ULog.d(.parrotCloudFlightLogTag, "Delete flight log \(url)") do { try FileManager.default.removeItem(at: url) } catch let err { - ULog.e(.flightLogEngineTag, "Failed to delete \(url.path): \(err)") + ULog.e(.parrotCloudFlightLogTag, "Failed to delete \(url.path): \(err)") } } } diff --git a/GroundSdk/Internal/Engine/FlightLog/FlightLogUploader.swift b/GroundSdk/Internal/Engine/FlightLog/FlightLogUploader.swift index 4537406..2dda359 100644 --- a/GroundSdk/Internal/Engine/FlightLog/FlightLogUploader.swift +++ b/GroundSdk/Internal/Engine/FlightLog/FlightLogUploader.swift @@ -90,7 +90,6 @@ class FlightLogUploader { /// - Returns: a request that can be canceled. func upload(baseUrl: URL, flightLogUrl: URL, token: String, completionCallback: @escaping CompletionCallback) -> CancelableCore { - ULog.d(.flightLogEngineTag, "Will upload flightLog \(flightLogUrl)") var api: String = "" var sha256: String = "" diff --git a/GroundSdk/Internal/Engine/FlightLogConverterEngine.swift b/GroundSdk/Internal/Engine/FlightLogConverterEngine.swift index c2b7cde..dbb0d27 100644 --- a/GroundSdk/Internal/Engine/FlightLogConverterEngine.swift +++ b/GroundSdk/Internal/Engine/FlightLogConverterEngine.swift @@ -62,8 +62,8 @@ class FlightLogConverterEngine: FlightLogEngineBase { public override func startEngine() { super.startEngine() ULog.d(.flightLogConverterEngineTag, "Starting FlightLogConverterEngine.") - gutmaLogStorage = utilities.getUtility(Utilities.gutmaLogStorage) - flightLogStorage = utilities.getUtility(Utilities.flightLogStorage) + gutmaLogStorage = utilities.getUtility(Utilities.gutmaLogStorage) + flightLogStorage = utilities.getUtility(Utilities.flightLogStorage) } public override func stopEngine() { @@ -108,7 +108,7 @@ class FlightLogConverterEngine: FlightLogEngineBase { do { try FileManager.default.moveItem(at: flightLog, to: processingFlightLog) } catch { - ULog.e(.fileManagerExtensionTag, "Failed to rename flight log to processing file :" + ULog.e(.flightLogConverterEngineTag, "Failed to rename flight log to processing file :" + "\(flightLog.absoluteString)") if !pendingFlightLogUrls.isEmpty { pendingFlightLogUrls.removeFirst() @@ -135,7 +135,7 @@ class FlightLogConverterEngine: FlightLogEngineBase { try FileManager.default.moveItem(at: processingFlightLog, to: finalFlightLog) strongSelf.flightLogStorage.notifyFlightLogReady(flightLogUrl: finalFlightLog) } catch { - ULog.e(.fileManagerExtensionTag, "Failed to rename processing to flight log" + ULog.e(.flightLogConverterEngineTag, "Failed to rename processing to flight log" + "file :\(processingFlightLog.absoluteString)") strongSelf.flightLogStorage.notifyFlightLogReady(flightLogUrl: processingFlightLog) } diff --git a/GroundSdk/Internal/Engine/FlightLogEngine.swift b/GroundSdk/Internal/Engine/FlightLogEngine.swift index 3a5bbbc..a53b501 100644 --- a/GroundSdk/Internal/Engine/FlightLogEngine.swift +++ b/GroundSdk/Internal/Engine/FlightLogEngine.swift @@ -84,7 +84,7 @@ class FlightLogEngine: FlightLogEngineBase { || (newInfo?.account != nil && newInfo?.dataUploadPolicy != .deny // keep old data until upload is allowed && newInfo?.oldDataPolicy == .denyUpload)) { - ULog.d(.myparrot, + ULog.d(.parrotCloudFlightLogTag, "User account change with private mode or old data upload denied -> delete all flight logs") self.dropFlightLogs() self.userAccountInfo = newInfo @@ -98,14 +98,14 @@ class FlightLogEngine: FlightLogEngineBase { try? FileManager.cleanOldInDirectory(url: engineDir, fileExt: "bin", totalMaxSizeMb: spaceQuotaInMb, includingSubfolders: true) } - ULog.d(.myparrot, "FLIGHTLOG active connectivityMonitor") + connectivityMonitor = utilities.getUtility(Utilities.internetConnectivity)! .startMonitoring { [unowned self] internetAvailable in if internetAvailable { - ULog.d(.myparrot, "FLIGHTLOG internet ready") + ULog.d(.parrotCloudFlightLogTag, "Internet ready") self.startFlightLogUploadProcess() } else { - ULog.d(.myparrot, "FLIGHTLOG internet NOT ready") + ULog.d(.parrotCloudFlightLogTag, "Internet NOT ready") self.cancelCurrentUpload() } } @@ -128,7 +128,6 @@ class FlightLogEngine: FlightLogEngineBase { /// Queue for processing flight logs override func queueForProcessing() { - ULog.d(.myparrot, "FLIGHTLOG (local) \(pendingFlightLogUrls)") if userAccountInfo?.privateMode == true { dropFlightLogs() } else { @@ -136,20 +135,21 @@ class FlightLogEngine: FlightLogEngineBase { } } - /// Start the uploading process of flight log files + /// Starts the uploading process of flight log files. /// - /// if an upload is already started we are only updating the pending count - /// uploading process is only started when it is not already uploading files. + /// If an uploading process is already started, we only update the pending count. private func startFlightLogUploadProcess() { - ULog.d(.myparrot, "startFlightLogUploadProcess") - guard !flightLogReporter.isUploading, - GroundSdkConfig.sharedInstance.flightLogServer != nil, - GroundSdkConfig.sharedInstance.applicationKey != nil, userAccountInfo?.token != nil, - self.userAccountInfo!.token! != "" else { - flightLogReporter.update(pendingCount: pendingFlightLogUrls.count) - ULog.d(.myparrot, "startFlightLogUploadProcess abort (was uploading)") + guard GroundSdkConfig.sharedInstance.flightLogServer != nil, + GroundSdkConfig.sharedInstance.applicationKey != nil else { + ULog.d(.parrotCloudFlightLogTag, "Flight log server or application key not defined.") + return + } + guard !flightLogReporter.isUploading else { + flightLogReporter.update(pendingCount: pendingFlightLogUrls.count).notifyUpdated() + ULog.d(.parrotCloudFlightLogTag, "Did not start flight log upload process (already uploading)") return } + ULog.d(.parrotCloudFlightLogTag, "Start flight log upload process") processNextFlightLog() } @@ -158,71 +158,86 @@ class FlightLogEngine: FlightLogEngineBase { /// It will only start the upload if the engine is not currently uploading a flightLog, if Internet connectivity /// is available, if user account is present, if a token is present, and if data upload is allowed. private func processNextFlightLog() { - ULog.d(.myparrot, "processNextFlightLog") flightLogReporter.update(pendingCount: pendingFlightLogUrls.count) - if userAccountInfo?.account == nil - || userAccountInfo?.token == nil - || userAccountInfo?.token == "" - || userAccountInfo?.dataUploadPolicy == .deny - || utilities.getUtility(Utilities.internetConnectivity)?.internetAvailable == false { + + // Check if upload process can go on + let abortReason: String? + if userAccountInfo?.account == nil { + abortReason = "no account" + } else if userAccountInfo!.token == nil || userAccountInfo!.token! == "" { + abortReason = "no token" + } else if userAccountInfo!.dataUploadPolicy == .deny { + abortReason = "denied by policy" + } else if uploader == nil { + abortReason = "no uploader" + } else if utilities.getUtility(Utilities.internetConnectivity)?.internetAvailable == false { + abortReason = "no internet" + } else { + abortReason = nil + } + + if let reason = abortReason { + ULog.d(.parrotCloudFlightLogTag, "Stop flight log upload process (\(reason))") flightLogReporter.update(isUploading: false).notifyUpdated() - ULog.d(.myparrot, "processNextFlightLog nothing to do") return } - if uploader != nil, let baseUrl = URL(string: GroundSdkConfig.sharedInstance.flightLogServer!), - currentUploadRequest == nil { - if let flightLog = pendingFlightLogUrls.first { - if userAccountInfo?.oldDataPolicy == .denyUpload { - // check if the file is before the authentication date - // if yes, we remove the file because the user did not accept the download of the data collected - // before the authentication - let toRemove: Bool - if let attrs = try? FileManager.default.attributesOfItem( - atPath: flightLog.path), let creationDate = attrs[.creationDate] as? Date, - let userDate = userAccountInfo?.changeDate { - toRemove = creationDate < userDate - if toRemove { - ULog.d(.myparrot, "FLIGHTLOG remove (creationDate < userDate)") - } - } else { - ULog.d(.myparrot, "FLIGHTLOG remove (no date)") - toRemove = true - } - if toRemove { - deleteFlightLog(at: flightLog, reason: "denied") - processNextFlightLog() - return - } - } + guard let baseUrl = URL(string: GroundSdkConfig.sharedInstance.flightLogServer!) else { + ULog.d(.parrotCloudFlightLogTag, "Stop flight log upload process (server incorrectly configured)") + flightLogReporter.update(isUploading: false).notifyUpdated() + return + } - if let attrs = try? FileManager.default.attributesOfItem( - atPath: flightLog.path) { - let fileSize = attrs[.size] as? UInt64 - ULog.d(.myparrot, "FLIGHTLOG SIZE: \(String(describing: fileSize)) \(flightLog)") - } + guard let flightLog = pendingFlightLogUrls.first else { + ULog.d(.parrotCloudFlightLogTag, "Stop flight log upload process (no file left)") + flightLogReporter.update(isUploading: false).notifyUpdated() + return + } - /// Anonymize file if necessary. - switch userAccountInfo?.dataUploadPolicy { - case .anonymous: - anonymize(baseUrl: baseUrl, flightLog: flightLog, profile: .ANONYMOUS_PROFILE) - case .noGps: - anonymize(baseUrl: baseUrl, flightLog: flightLog, profile: .NO_GPS_PROFILE) - case .full, .noMedia: - uploadFlight(baseUrl: baseUrl, flightLogUrl: flightLog) - case .deny, .none: - /// should not happen - break + ULog.d(.parrotCloudFlightLogTag, "Process next flight log \(flightLog.absoluteString)") + + if userAccountInfo?.oldDataPolicy == .denyUpload { + // check if the file is before the authentication date + // if yes, we remove the file because the user did not accept the download of the data collected + // before the authentication + let toRemove: Bool + if let attrs = try? FileManager.default.attributesOfItem( + atPath: flightLog.path), let creationDate = attrs[.creationDate] as? Date, + let userDate = userAccountInfo?.changeDate { + toRemove = creationDate < userDate + if toRemove { + ULog.d(.parrotCloudFlightLogTag, "Remove (creationDate < userDate)") } } else { - flightLogReporter.update(isUploading: false) - flightLogReporter.notifyUpdated() + ULog.d(.parrotCloudFlightLogTag, "Remove (no date)") + toRemove = true + } + if toRemove { + deleteFlightLog(at: flightLog, reason: "denied") + processNextFlightLog() + return } - } else { - ULog.d(.myparrot, "FLIGHTLOG / process Next flight log abort (no uploader)") - flightLogReporter.notifyUpdated() } - } + + if let attrs = try? FileManager.default.attributesOfItem(atPath: flightLog.path) { + let fileSize = attrs[.size] as? UInt64 + ULog.d(.parrotCloudFlightLogTag, + "Flight log \(flightLog.lastPathComponent) size: \(String(describing: fileSize))") + } + + /// Anonymize file if necessary. + switch userAccountInfo?.dataUploadPolicy { + case .anonymous: + anonymize(baseUrl: baseUrl, flightLog: flightLog, profile: .ANONYMOUS_PROFILE) + case .noGps: + anonymize(baseUrl: baseUrl, flightLog: flightLog, profile: .NO_GPS_PROFILE) + case .full, .noMedia: + uploadFlight(baseUrl: baseUrl, flightLogUrl: flightLog) + case .deny, .none: + /// should not happen + break + } + } /// Anonymization of flight log /// @@ -249,7 +264,7 @@ class FlightLogEngine: FlightLogEngineBase { do { try fileManager.moveItem(at: flightLog, to: processingFlightLog) } catch { - ULog.e(.myparrot, "FLIGHTLOG - Anonymization: move flight log failed.") + ULog.e(.parrotCloudFlightLogTag, "Failed to rename log to processing file \(flightLog.absoluteString)") return } queue.async { @@ -259,7 +274,8 @@ class FlightLogEngine: FlightLogEngineBase { do { try fileManager.moveItem(at: processingFlightLog, to: flightLog) } catch { - ULog.e(.myparrot, "FLIGHTLOG - Anonymization: move flight log back failed.") + ULog.e(.parrotCloudFlightLogTag, + "Failed to rename processing file to log \(flightLog.absoluteString)") return } if result == AnonymizerResult.SUCCESS { @@ -281,39 +297,45 @@ class FlightLogEngine: FlightLogEngineBase { /// - baseUrl: url of the server /// - flightLogUrl: url of the flight log to upload private func uploadFlight(baseUrl: URL, flightLogUrl: URL) { - self.flightLogReporter.update(isUploading: true) - self.currentUploadRequest = uploader?.upload(baseUrl: baseUrl, flightLogUrl: flightLogUrl, - token: self.userAccountInfo!.token!) { flightLogUrl, error in + let logFileName = flightLogUrl.lastPathComponent + ULog.d(.parrotCloudFlightLogTag, "Start uploading \(logFileName)") + + guard currentUploadRequest == nil else { + ULog.d(.parrotCloudFlightLogTag, "Did not upload flight log (upload request in progress)") + flightLogReporter.update(isUploading: false).notifyUpdated() + return + } + + flightLogReporter.update(isUploading: true).notifyUpdated() + currentUploadRequest = uploader?.upload(baseUrl: baseUrl, flightLogUrl: flightLogUrl, + token: self.userAccountInfo!.token!) { flightLogUrl, error in self.currentUploadRequest = nil if let error = error { switch error { case .badRequest: - ULog.d(.myparrot, "FLIGHTLOG .badRequest \(flightLogUrl)") - ULog.w(.flightLogEngineTag, "Bad request sent to the server. This should be a dev error.") + ULog.d(.parrotCloudFlightLogTag, "Upload error (bad request) \(logFileName)") // delete file and stop uploading to avoid multiple errors self.deleteFlightLog(at: flightLogUrl, reason: "error") self.flightLogReporter.update(isUploading: false).notifyUpdated() case .badFlightLog: - ULog.d(.myparrot, "FLIGHTLOG .badFlightLog \(flightLogUrl)") + ULog.d(.parrotCloudFlightLogTag, "Upload error (bad flight log) \(logFileName)") self.deleteFlightLog(at: flightLogUrl, reason: "error") self.processNextFlightLog() case .serverError, .connectionError: // Stop uploading if the server is not accessible - ULog.d(.myparrot, "FLIGHTLOG .serverError or .connectionError \(flightLogUrl)") + ULog.d(.parrotCloudFlightLogTag, "Upload error (server or connection) \(logFileName)") self.flightLogReporter.update(isUploading: false).notifyUpdated() case .canceled: - ULog.d(.myparrot, "FLIGHTLOG .canceled \(flightLogUrl)") + ULog.d(.parrotCloudFlightLogTag, "Upload canceled \(logFileName)") self.flightLogReporter.update(isUploading: false).notifyUpdated() } } else { // success - ULog.d(.myparrot, "FLIGHTLOG SUCCESS \(flightLogUrl)") + ULog.d(.parrotCloudFlightLogTag, "Flight log successfully uploaded \(logFileName)") self.deleteFlightLog(at: flightLogUrl, reason: "sent") self.processNextFlightLog() } } - - self.flightLogReporter.notifyUpdated() } /// Remove the given flightLog from the pending ones and delete it from the file system. @@ -331,14 +353,16 @@ class FlightLogEngine: FlightLogEngineBase { } /// remove original file - ULog.d(.myparrot, "FLIGHTLOG remove (in upload list) : \(flightLogUrlReal)") - if self.pendingFlightLogUrls.first == flightLogUrlReal { - self.pendingFlightLogUrls.remove(at: 0) + ULog.d(.parrotCloudFlightLogTag, "Delete flight log (\(reason)) \(flightLogUrl.lastPathComponent)") + if pendingFlightLogUrls.first == flightLogUrlReal { + pendingFlightLogUrls.remove(at: 0) } else { - ULog.w(.flightLogEngineTag, "Uploaded flightLog is not the first one of the pending") + ULog.w(.parrotCloudFlightLogTag, "Flight log to remove is not the first one of the pending list") // fallback - if let index: Int = self.pendingFlightLogUrls.firstIndex(where: {$0 == flightLogUrlReal}) { - self.pendingFlightLogUrls.remove(at: index) + if let index: Int = pendingFlightLogUrls.firstIndex(where: {$0 == flightLogUrlReal}) { + pendingFlightLogUrls.remove(at: index) + } else { + ULog.w(.parrotCloudFlightLogTag, "Flight log not found in the pending list") } } collector?.deleteFlightLog(at: flightLogUrlReal) diff --git a/GroundSdk/Internal/Engine/FlightLogEngineBase.swift b/GroundSdk/Internal/Engine/FlightLogEngineBase.swift index 763964d..f759b95 100644 --- a/GroundSdk/Internal/Engine/FlightLogEngineBase.swift +++ b/GroundSdk/Internal/Engine/FlightLogEngineBase.swift @@ -94,6 +94,7 @@ class FlightLogEngineBase: EngineBaseCore { collector = createCollector() collector?.collectFlightLogs { [weak self] flightLogs in if let `self` = self, self.started { + ULog.d(.parrotCloudFlightLogTag, "Logs locally collected: \(flightLogs)") self.pendingFlightLogUrls.append(contentsOf: flightLogs) self.queueForProcessing() } @@ -110,9 +111,9 @@ class FlightLogEngineBase: EngineBaseCore { /// Cancel the current upload if there is one. public func cancelCurrentUpload() { // stop current upload request - ULog.d(.myparrot, "FLIGHTLOG cancel current upload request \(String(describing: self.currentUploadRequest))") - self.currentUploadRequest?.cancel() - self.currentUploadRequest = nil + ULog.d(.parrotCloudFlightLogTag, "Cancel current upload request \(String(describing: currentUploadRequest))") + currentUploadRequest?.cancel() + currentUploadRequest = nil } /// Creates a collector @@ -128,7 +129,7 @@ class FlightLogEngineBase: EngineBaseCore { /// If the upload was not started and the upload may start, it will start. /// - Parameter flightLogUrl: local url of the flightLog that have just been added func add(flightLogUrl: URL) { - ULog.d(.myparrot, "FLIGHTLOG add a file: \(flightLogUrl)") + ULog.d(.parrotCloudFlightLogTag, "Add a file: \(flightLogUrl)") pendingFlightLogUrls.append(flightLogUrl) queueForProcessing() } @@ -158,7 +159,7 @@ class FlightLogEngineBase: EngineBaseCore { do { try FileManager.default.createDirectory(at: debugDir, withIntermediateDirectories: true) } catch let err { - ULog.e(.myparrot, "Failed to create folder at \(debugDir.path): \(err)") + ULog.e(.flightLogEngineTag, "Failed to create folder at \(debugDir.path): \(err)") } } @@ -176,7 +177,7 @@ class FlightLogEngineBase: EngineBaseCore { try FileManager.default.removeItem(at: file) } } catch { - ULog.e(.myparrot, "Failed to recover file: \(file)") + ULog.e(.flightLogEngineTag, "Failed to recover file: \(file)") } } } diff --git a/GroundSdk/Internal/Engine/GutmaLogEngine.swift b/GroundSdk/Internal/Engine/GutmaLogEngine.swift index 9870593..91ff76e 100644 --- a/GroundSdk/Internal/Engine/GutmaLogEngine.swift +++ b/GroundSdk/Internal/Engine/GutmaLogEngine.swift @@ -101,7 +101,7 @@ class GutmaLogEngine: EngineBaseCore { // If the user account changes and if private mode is set, we delete all files if newInfo?.changeDate != self.userAccountInfo?.changeDate && newInfo?.privateMode == true { - ULog.d(.myparrot, "User account change with private mode -> delete all gutma logs") + ULog.d(.gutmaLogEngineTag, "User account change with private mode -> delete all gutma logs") self.dropGutmaLogs() } self.userAccountInfo = newInfo diff --git a/GroundSdk/Internal/Engine/UserAccountEngine.swift b/GroundSdk/Internal/Engine/UserAccountEngine.swift index eb1ef02..8a07f99 100644 --- a/GroundSdk/Internal/Engine/UserAccountEngine.swift +++ b/GroundSdk/Internal/Engine/UserAccountEngine.swift @@ -130,8 +130,8 @@ class UserAccountEngine: EngineBaseCore { private var userAccountInfo: UserAccountInfoCore? { didSet { + ULog.d(.parrotCloudTag, "Set user account \(String(describing: userAccountInfo))") userAccountUtilityCoreImpl.update(userAccountInfo: userAccountInfo) - ULog.d(.myparrot, "Engine set user \(String(describing: userAccountInfo))") } } @@ -292,21 +292,20 @@ extension UserAccountEngine { /// Save persisting data private func saveData() { + ULog.d(.parrotCloudTag, "Save user account \(String(describing: userAccountInfo))") let encoder = PropertyListEncoder() do { let data = try encoder.encode(userAccountInfo) let savedDictionary = [PersistingDataKeys.userAccountData.rawValue: data] groundSdkUserDefaults.storeData(savedDictionary) - ULog.d(.myparrot, "save user data\(String(describing: userAccountInfo))") } catch { - // Handle error - ULog.e(.userAccountEngineTag, "saveData: " + error.localizedDescription) + ULog.e(.parrotCloudTag, "Failed to save user account: \(error)") } } /// Load persisting data private func loadData() { - ULog.d(.myparrot, "try to load previous user") + ULog.d(.parrotCloudTag, "Load persisting user account, if any") let loadedDictionary = groundSdkUserDefaults.loadData() as? [String: Any] if let accountData = loadedDictionary?[PersistingDataKeys.userAccountData.rawValue] as? Data { let decoder = PropertyListDecoder() diff --git a/GroundSdk/Internal/FileManagerExtension.swift b/GroundSdk/Internal/FileManagerExtension.swift index 929fb85..5f9f6ab 100644 --- a/GroundSdk/Internal/FileManagerExtension.swift +++ b/GroundSdk/Internal/FileManagerExtension.swift @@ -111,10 +111,10 @@ extension FileManager { totalSize += size if totalSize > totalMaxSizeMb * 1024 * 1024 { do { - ULog.d(.myparrot, "delete file (quota) \(elt.url)") + ULog.d(.parrotCloudTag, "Delete file (quota) \(elt.url)") try FileManager.default.removeItem(at: elt.url) } catch { - ULog.e(.fileManagerExtensionTag, "deleting \(elt.url.lastPathComponent) - \(error)") + ULog.e(.parrotCloudTag, "Failed to delete \(elt.url.lastPathComponent): \(error)") } } } diff --git a/GroundSdk/Internal/GroundSdkCore.swift b/GroundSdk/Internal/GroundSdkCore.swift index 781d67f..02127b4 100644 --- a/GroundSdk/Internal/GroundSdkCore.swift +++ b/GroundSdk/Internal/GroundSdkCore.swift @@ -198,6 +198,20 @@ public class GroundSdkCore: NSObject { let fileReplayCore = FileReplayCore(source: source) return FileReplayRefCore(stream: fileReplayCore, observer: observer) } + + /// Collects latest logs from the given sources and bundles them in an archive in the given destination + /// directory. + /// + /// - Parameters: + /// - sources: sources of the logs to collect + /// - directory: destination directory + /// - observer: observer called when the LogCollector changes, indicating collection progress + /// - Returns: a reference on a LogCollector + public func newLogCollector(from sources: Set, + toDirectory directory: URL, + observer: @escaping (LogCollector?) -> Void) -> Ref { + return LogCollectorRefCore(from: sources, toDirectory: directory, observer: observer) + } } /// Singleton instance diff --git a/GroundSdk/Internal/HttpSessionCore.swift b/GroundSdk/Internal/HttpSessionCore.swift index 04835ac..2f5e19f 100644 --- a/GroundSdk/Internal/HttpSessionCore.swift +++ b/GroundSdk/Internal/HttpSessionCore.swift @@ -124,43 +124,42 @@ public class HttpSessionCore: NSObject { /// - result: the request result /// - data: the data that has been get. `nil` if result is not `.success` /// - Returns: the request - public func getData( - request: URLRequest, completion: @escaping (_ result: Result, _ data: Data?) -> Void) -> CancelableCore { + public func getData(request: URLRequest, + completion: @escaping (_ result: Result, _ data: Data?) -> Void) -> CancelableCore { + var request = request + request.httpMethod = "GET" - var request = request - request.httpMethod = "GET" + var taskIdentifier: Int? + let task = session.dataTask(with: request) { data, response, error in - var taskIdentifier: Int? - let task = session.dataTask(with: request) { data, response, error in - - let result: Result - if let error = error { - if (error as NSError).urlError == .canceled { - result = .canceled - } else { - result = .error(error) - } - } else if let response = response as? HTTPURLResponse { - if response.statusCode == 200 { - result = .success(response.statusCode) - } else { - result = .httpError(response.statusCode) - } + let result: Result + if let error = error { + if (error as NSError).urlError == .canceled { + result = .canceled } else { - result = HttpSessionCore.defaultError + result = .error(error) } - - // as we are in the delegateQueue, executes the call back in main thread - DispatchQueue.main.async { - ULog.d(.httpClientTag, "Task \(taskIdentifier ?? -1) (\(request.url?.description ?? "")) " + - "did complete with result: \(result)") - completion(result, data) + } else if let response = response as? HTTPURLResponse { + if response.statusCode == 200 { + result = .success(response.statusCode) + } else { + result = .httpError(response.statusCode) } + } else { + result = HttpSessionCore.defaultError + } + + // as we are in the delegateQueue, executes the call back in main thread + DispatchQueue.main.async { + ULog.d(.httpClientTag, "Task \(taskIdentifier ?? -1) (\(request.url?.description ?? "")) " + + "did complete with result: \(result)") + completion(result, data) } - taskIdentifier = task.taskIdentifier - task.resume() - return task } + taskIdentifier = task.taskIdentifier + task.resume() + return task + } /// Send data /// @@ -173,44 +172,42 @@ public class HttpSessionCore: NSObject { /// - result: the request result /// - data: the data that has been get. `nil` if result is not `.success` /// - Returns: the request - public func sendData( - request: URLRequest, method: SendMethod = .put, - completion: @escaping (_ result: Result, _ data: Data?) -> Void) -> CancelableCore { - - var request = request - request.httpMethod = method.rawValue + public func sendData(request: URLRequest, method: SendMethod = .put, + completion: @escaping (_ result: Result, _ data: Data?) -> Void) -> CancelableCore { + var request = request + request.httpMethod = method.rawValue - var taskIdentifier: Int? - let task = session.dataTask(with: request) { data, response, error in + var taskIdentifier: Int? + let task = session.dataTask(with: request) { data, response, error in - let result: Result - if let error = error { - if (error as NSError).urlError == .canceled { - result = .canceled - } else { - result = .error(error) - } - } else if let response = response as? HTTPURLResponse { - if response.statusCode == 200 { - result = .success(response.statusCode) - } else { - result = .httpError(response.statusCode) - } + let result: Result + if let error = error { + if (error as NSError).urlError == .canceled { + result = .canceled } else { - result = HttpSessionCore.defaultError + result = .error(error) } - - // as we are in the delegateQueue, executes the call back in main thread - DispatchQueue.main.async { - ULog.d(.httpClientTag, "Task \(taskIdentifier ?? -1) (\(request.url?.description ?? "")) " + - "did complete with result: \(result)") - completion(result, data) + } else if let response = response as? HTTPURLResponse { + if response.statusCode == 200 { + result = .success(response.statusCode) + } else { + result = .httpError(response.statusCode) } + } else { + result = HttpSessionCore.defaultError + } + + // as we are in the delegateQueue, executes the call back in main thread + DispatchQueue.main.async { + ULog.d(.httpClientTag, "Task \(taskIdentifier ?? -1) (\(request.url?.description ?? "")) " + + "did complete with result: \(result)") + completion(result, data) } - taskIdentifier = task.taskIdentifier - task.resume() - return task } + taskIdentifier = task.taskIdentifier + task.resume() + return task + } /// Send a file with a put request /// @@ -226,51 +223,49 @@ public class HttpSessionCore: NSObject { /// - result: the request result /// - data: data returned in the response body /// - Returns: the request - public func sendFile( - request: URLRequest, method: SendMethod = .put, fileUrl: URL, - progress: @escaping (_ progressValue: Int) -> Void, - completion: @escaping (_ result: Result, _ data: Data?) -> Void) -> CancelableCore { + public func sendFile(request: URLRequest, method: SendMethod = .put, fileUrl: URL, + progress: @escaping (_ progressValue: Int) -> Void, + completion: @escaping (_ result: Result, _ data: Data?) -> Void) -> CancelableCore { + var request = request + request.httpMethod = method.rawValue - var request = request - request.httpMethod = method.rawValue + var taskIdentifier: Int? + let task = session.uploadTask(with: request, fromFile: fileUrl) { [weak self] data, response, error in - var taskIdentifier: Int? - let task = session.uploadTask(with: request, fromFile: fileUrl) { [weak self] data, response, error in - - let result: Result - if let error = error { - if (error as NSError).urlError == .canceled { - result = .canceled - } else { - result = .error(error) - } - } else if let response = response as? HTTPURLResponse { - if response.statusCode == 200 { - result = .success(response.statusCode) - } else { - result = .httpError(response.statusCode) - } + let result: Result + if let error = error { + if (error as NSError).urlError == .canceled { + result = .canceled } else { - result = HttpSessionCore.defaultError + result = .error(error) } - // as we are in the delegateQueue, executes the call back in main thread - DispatchQueue.main.async { - if let taskId = taskIdentifier { - self?.progressCbs[taskId] = nil - } - ULog.d(.httpClientTag, "Task \(taskIdentifier ?? -1) (\(request.url?.description ?? "")) " + - "did complete with result: \(result)") - completion(result, data) + } else if let response = response as? HTTPURLResponse { + if response.statusCode == 200 { + result = .success(response.statusCode) + } else { + result = .httpError(response.statusCode) } + } else { + result = HttpSessionCore.defaultError + } + // as we are in the delegateQueue, executes the call back in main thread + DispatchQueue.main.async { + if let taskId = taskIdentifier { + self?.progressCbs[taskId] = nil + } + ULog.d(.httpClientTag, "Task \(taskIdentifier ?? -1) (\(request.url?.description ?? "")) " + + "did complete with result: \(result)") + completion(result, data) } - taskIdentifier = task.taskIdentifier - progressCbs[task.taskIdentifier] = progress - task.resume() - ULog.d(.httpClientTag, "Task \(task.taskIdentifier) (\(request.url?.description ?? "")) " + - "started") - - return task } + taskIdentifier = task.taskIdentifier + progressCbs[task.taskIdentifier] = progress + task.resume() + ULog.d(.httpClientTag, "Task \(task.taskIdentifier) (\(request.url?.description ?? "")) " + + "started") + + return task + } /// Download a file with a get request /// @@ -286,20 +281,19 @@ public class HttpSessionCore: NSObject { /// - localFileUrl: the local file url of the downloaded file. Note that when the completion closure exits, this /// local file will deleted. /// - Returns: the request - public func downloadFile( - request: URLRequest, destination: URL, progress: @escaping (_ progressValue: Int) -> Void, - completion: @escaping (_ result: Result, _ localFileUrl: URL?) -> Void) -> CancelableCore { - - var request = request - request.httpMethod = "GET" - - let task = session.downloadTask(with: request) - progressCbs[task.taskIdentifier] = progress - dlCompletionCbs[task.taskIdentifier] = DownloadCompletionCb(destination: destination, callback: completion) - task.resume() - - return task - } + public func downloadFile(request: URLRequest, destination: URL, + progress: @escaping (_ progressValue: Int) -> Void, + completion: @escaping (_ result: Result, _ localFileUrl: URL?) -> Void) -> CancelableCore { + var request = request + request.httpMethod = "GET" + + let task = session.downloadTask(with: request) + progressCbs[task.taskIdentifier] = progress + dlCompletionCbs[task.taskIdentifier] = DownloadCompletionCb(destination: destination, callback: completion) + task.resume() + + return task + } /// Download a file with a get request, using a FileStreamDecoder /// @@ -315,21 +309,19 @@ public class HttpSessionCore: NSObject { /// - localFileUrl: the local file url of the downloaded file. Note that when the completion closure exits, this /// local file will deleted. /// - Returns: the request - public func downloadFile( - streamDecoder: StreamDecoder, request: URLRequest, destination: URL, - completion: @escaping (_ result: Result, _ localFileUrl: URL?) -> Void) -> CancelableCore { - - var request = request - request.httpMethod = "GET" - - let task = session.dataTask(with: request) - streamDlCompletionCbs[task.taskIdentifier] = DownloadCompletionCb( - destination: destination, callback: completion) - streamWriters[task.taskIdentifier] = StreamWriter(withFileUrl: destination, streamDecoder: streamDecoder) - task.resume() - - return task - } + public func downloadFile(streamDecoder: StreamDecoder, request: URLRequest, destination: URL, + completion: @escaping (_ result: Result, _ localFileUrl: URL?) -> Void) -> CancelableCore { + var request = request + request.httpMethod = "GET" + + let task = session.dataTask(with: request) + streamDlCompletionCbs[task.taskIdentifier] = DownloadCompletionCb( + destination: destination, callback: completion) + streamWriters[task.taskIdentifier] = StreamWriter(withFileUrl: destination, streamDecoder: streamDecoder) + task.resume() + + return task + } /// Request a delete /// @@ -338,49 +330,50 @@ public class HttpSessionCore: NSObject { /// - completion: completion callback /// - result: the request result /// - Returns: the request - public func delete( - request: URLRequest, completion: @escaping (_ result: Result) -> Void) -> CancelableCore { - - var request = request - request.httpMethod = "DELETE" - - var taskIdentifier: Int? - let task = session.dataTask(with: request) { _, response, error in - let result: Result - if let error = error { - if (error as NSError).urlError == .canceled { - result = .canceled - } else { - result = .error(error) - } - } else if let response = response as? HTTPURLResponse { - if response.statusCode == 200 { - result = .success(response.statusCode) - } else { - result = .httpError(response.statusCode) - } + public func delete(request: URLRequest, + completion: @escaping (_ result: Result) -> Void) -> CancelableCore { + var request = request + request.httpMethod = "DELETE" + + var taskIdentifier: Int? + let task = session.dataTask(with: request) { _, response, error in + let result: Result + if let error = error { + if (error as NSError).urlError == .canceled { + result = .canceled } else { - result = HttpSessionCore.defaultError + result = .error(error) } - - // as we are in the delegateQueue, executes the call back in main thread - DispatchQueue.main.async { - ULog.d(.httpClientTag, "Task \(taskIdentifier ?? -1) (\(request.url?.description ?? "")) " + - "did complete with result: \(result)") - completion(result) + } else if let response = response as? HTTPURLResponse { + if response.statusCode == 200 { + result = .success(response.statusCode) + } else { + result = .httpError(response.statusCode) } + } else { + result = HttpSessionCore.defaultError } - taskIdentifier = task.taskIdentifier - task.resume() - return task + // as we are in the delegateQueue, executes the call back in main thread + DispatchQueue.main.async { + ULog.d(.httpClientTag, "Task \(taskIdentifier ?? -1) (\(request.url?.description ?? "")) " + + "did complete with result: \(result)") + completion(result) + } } + taskIdentifier = task.taskIdentifier + task.resume() + + return task + } } /// Extension of HttpSessionCore that implements all kind of URLSession delegates extension HttpSessionCore: URLSessionDelegate, URLSessionDataDelegate, URLSessionTaskDelegate { - public func urlSession(_ session: URLSession, dataTask: URLSessionDataTask, didReceive data: Data) { + public func urlSession(_ session: URLSession, + dataTask: URLSessionDataTask, + didReceive data: Data) { // check if the task is a streamDownload task if let streamWriter = streamWriters[dataTask.taskIdentifier] { do { @@ -402,23 +395,27 @@ extension HttpSessionCore: URLSessionDelegate, URLSessionDataDelegate, URLSessio } } - public func urlSession( - _ session: URLSession, task: URLSessionTask, didSendBodyData bytesSent: Int64, totalBytesSent: Int64, - totalBytesExpectedToSend: Int64) { + public func urlSession(_ session: URLSession, + task: URLSessionTask, + didSendBodyData bytesSent: Int64, + totalBytesSent: Int64, + totalBytesExpectedToSend: Int64) { - // as we are in the delegateQueue, executes the call back in main thread - DispatchQueue.main.async { - guard let progressCb = self.progressCbs[task.taskIdentifier] else { - ULog.e(.httpClientTag, "Progress callback not found for task \(task.taskIdentifier)") - return - } - let progress = Int((Double(totalBytesSent) / Double(totalBytesExpectedToSend)) * 100) - ULog.d(.httpClientTag, "Upload progress of task \(task.taskIdentifier): \(progress)") - progressCb(progress) + // as we are in the delegateQueue, executes the call back in main thread + DispatchQueue.main.async { + guard let progressCb = self.progressCbs[task.taskIdentifier] else { + ULog.e(.httpClientTag, "Progress callback not found for task \(task.taskIdentifier)") + return } + let progress = Int((Double(totalBytesSent) / Double(totalBytesExpectedToSend)) * 100) + ULog.d(.httpClientTag, "Upload progress of task \(task.taskIdentifier): \(progress)") + progressCb(progress) } + } - public func urlSession(_ session: URLSession, task: URLSessionTask, didCompleteWithError error: Error?) { + public func urlSession(_ session: URLSession, + task: URLSessionTask, + didCompleteWithError error: Error?) { // this function is only called when no completion closure is directly passed to the task, that happens // on download tasks or for streamDownload Tasks @@ -500,75 +497,75 @@ extension HttpSessionCore: URLSessionDelegate, URLSessionDataDelegate, URLSessio } extension HttpSessionCore: URLSessionDownloadDelegate { - public func urlSession( - _ session: URLSession, downloadTask: URLSessionDownloadTask, didFinishDownloadingTo location: URL) { - - // as we are in the delegateQueue, executes the call back in main thread - DispatchQueue.main.sync { - guard let completionCb = self.dlCompletionCbs[downloadTask.taskIdentifier] else { - ULog.e(.httpClientTag, "Completion callback not found for task \(downloadTask.taskIdentifier)") - return - } + public func urlSession(_ session: URLSession, + downloadTask: URLSessionDownloadTask, + didFinishDownloadingTo location: URL) { + // as we are in the delegateQueue, executes the call back in main thread + DispatchQueue.main.sync { + guard let completionCb = self.dlCompletionCbs[downloadTask.taskIdentifier] else { + ULog.e(.httpClientTag, "Completion callback not found for task \(downloadTask.taskIdentifier)") + return + } - var result: Result - if let response = downloadTask.response as? HTTPURLResponse { - if response.statusCode == 200 { - result = .success(response.statusCode) - } else { - result = .httpError(response.statusCode) - } + var result: Result + if let response = downloadTask.response as? HTTPURLResponse { + if response.statusCode == 200 { + result = .success(response.statusCode) } else { - result = .httpError(403) + result = .httpError(response.statusCode) } + } else { + result = .httpError(403) + } - var localFileUrlUsed: URL? + var localFileUrlUsed: URL? - if case .success = result { - let localFileUrl = completionCb.destination - if FileManager.default.fileExists(atPath: localFileUrl.path) { - do { - try FileManager.default.removeItem(atPath: localFileUrl.path) - } catch let error { - ULog.w(.httpClientTag, "Failed to remove file at \(localFileUrl): " + - error.localizedDescription) - } - } + if case .success = result { + let localFileUrl = completionCb.destination + if FileManager.default.fileExists(atPath: localFileUrl.path) { do { - try FileManager.default.createDirectory( - at: localFileUrl.deletingLastPathComponent(), withIntermediateDirectories: true, - attributes: nil) - try FileManager.default.moveItem(at: location, to: localFileUrl) - localFileUrlUsed = localFileUrl + try FileManager.default.removeItem(atPath: localFileUrl.path) } catch let error { - result = .error(error) - ULog.w(.httpClientTag, "Failed to move file at \(localFileUrl): " + + ULog.w(.httpClientTag, "Failed to remove file at \(localFileUrl): " + error.localizedDescription) } } - self.progressCbs[downloadTask.taskIdentifier] = nil - self.dlCompletionCbs[downloadTask.taskIdentifier] = nil - - ULog.d(.httpClientTag, "Task \(downloadTask.taskIdentifier) " + - "(\(downloadTask.currentRequest?.url?.description ?? "")) did complete with result: \(result)") - completionCb.callback(result, localFileUrlUsed) + do { + try FileManager.default.createDirectory( + at: localFileUrl.deletingLastPathComponent(), withIntermediateDirectories: true, + attributes: nil) + try FileManager.default.moveItem(at: location, to: localFileUrl) + localFileUrlUsed = localFileUrl + } catch let error { + result = .error(error) + ULog.w(.httpClientTag, "Failed to move file at \(localFileUrl): " + + error.localizedDescription) + } } - } + self.progressCbs[downloadTask.taskIdentifier] = nil + self.dlCompletionCbs[downloadTask.taskIdentifier] = nil - public func urlSession( - _ session: URLSession, downloadTask: URLSessionDownloadTask, didWriteData bytesWritten: Int64, - totalBytesWritten: Int64, totalBytesExpectedToWrite: Int64) { - - // as we are in the delegateQueue, executes the call back in main thread - DispatchQueue.main.async { - guard let progressCb = self.progressCbs[downloadTask.taskIdentifier] else { - ULog.e(.httpClientTag, "Progress callback not found for task \(downloadTask.taskIdentifier)") - return - } + ULog.d(.httpClientTag, "Task \(downloadTask.taskIdentifier) " + + "(\(downloadTask.currentRequest?.url?.description ?? "")) did complete with result: \(result)") + completionCb.callback(result, localFileUrlUsed) + } + } - let progress = Int((Double(totalBytesWritten) / Double(totalBytesExpectedToWrite)) * 100) - progressCb(progress) + public func urlSession(_ session: URLSession, + downloadTask: URLSessionDownloadTask, + didWriteData bytesWritten: Int64, + totalBytesWritten: Int64, totalBytesExpectedToWrite: Int64) { + // as we are in the delegateQueue, executes the call back in main thread + DispatchQueue.main.async { + guard let progressCb = self.progressCbs[downloadTask.taskIdentifier] else { + ULog.e(.httpClientTag, "Progress callback not found for task \(downloadTask.taskIdentifier)") + return } + + let progress = Int((Double(totalBytesWritten) / Double(totalBytesExpectedToWrite)) * 100) + progressCb(progress) } + } } diff --git a/GroundSdk/Internal/Log/LogCollectorRefCore.swift b/GroundSdk/Internal/Log/LogCollectorRefCore.swift new file mode 100644 index 0000000..8575b47 --- /dev/null +++ b/GroundSdk/Internal/Log/LogCollectorRefCore.swift @@ -0,0 +1,200 @@ +// Copyright (C) 2022 Parrot Drones SAS +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in +// the documentation and/or other materials provided with the +// distribution. +// * Neither the name of the Parrot Company nor the names +// of its contributors may be used to endorse or promote products +// derived from this software without specific prior written +// permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// PARROT COMPANY BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +// OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +// AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +// OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT +// OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF +// SUCH DAMAGE. + +import Foundation +import SdkCore + +/// LogCollector Reference implementation. +class LogCollectorRefCore: Ref { + + /// Queue where all I/O operations will run into. + private let ioQueue = DispatchQueue(label: "com.parrot.gsdk.logCollector", qos: .background) + + /// Destination directory URL. + private let destinationDirectory: URL + + /// Temporary directory URL. + private var temporaryDirectory: URL? + + /// References on active log downloaders. + private var downloaders: [Ref] = [] + + /// Collector states, by their associated source. + private var states: [LogCollectorSource: LogCollectorState] = [:] + + /// Constructor + /// + /// - Parameters: + /// - sources: sources of the logs to collect + /// - directory: destination directory + /// - observer: observer notified of download progress + init(from sources: Set, + toDirectory directory: URL, + observer: @escaping Observer) { + destinationDirectory = directory + super.init(observer: observer) + + // create temporary directories + let droneDir, remoteDir, appDir: URL + do { + let fileManager = FileManager.default + let tmpDir = try fileManager.url(for: .itemReplacementDirectory, in: .userDomainMask, + appropriateFor: directory, create: true) + droneDir = tmpDir.appendingPathComponent("drone") + remoteDir = tmpDir.appendingPathComponent("mpp") + appDir = tmpDir.appendingPathComponent("app") + try fileManager.createDirectory(at: droneDir, withIntermediateDirectories: true) + try fileManager.createDirectory(at: remoteDir, withIntermediateDirectories: true) + try fileManager.createDirectory(at: appDir, withIntermediateDirectories: true) + temporaryDirectory = tmpDir + } catch let err { + ULog.e(.logCollectorTag, "Failed to create temporary directories: \(err)") + update(newValue: LogCollector(globalStatus: .failed, states: states, destination: nil)) + return + } + + // start logs collection + for source in sources { + switch source { + case .drone(let drone): + let downloader = drone.getPeripheral(Peripherals.latestLogDownloader) { [weak self] downloader in + self?.states[source] = downloader?.state + self?.updateValue() + } + downloaders.append(downloader) + downloader.value?.downloadLogs(toDirectory: droneDir) + case .remoteControl(let rc): + let downloader = rc.getPeripheral(Peripherals.latestLogDownloader) { [weak self] downloader in + self?.states[source] = downloader?.state + self?.updateValue() + } + downloaders.append(downloader) + downloader.value?.downloadLogs(toDirectory: remoteDir) + case .application(let logDirectory): + let srcUrl = logDirectory.appendingPathComponent("log.bin") + let dstUrl = appDir.appendingPathComponent("log.bin") + var fileSize: UInt64? + states[source] = LogCollectorState(status: .collecting) + if let attrs = try? FileManager.default.attributesOfItem(atPath: srcUrl.path) { + fileSize = attrs[.size] as? UInt64 + states[source]?.totalSize = fileSize + } + updateValue() + + ioQueue.async { + do { + try FileManager.default.copyItem(at: srcUrl, to: dstUrl) + self.states[source]?.status = .collected + self.states[source]?.collectedSize = fileSize + } catch let err { + ULog.e(.logCollectorTag, "Failed to copy file at \(srcUrl) to \(dstUrl): \(err)") + self.states[source]?.status = .failed + } + DispatchQueue.main.async { + self.updateValue() + } + } + } + } + } + + /// Destructor + deinit { + for downloader in downloaders { + downloader.value?.cancelDownload() + } + } + + /// Updates the referenced LogCollector according to the states of all log collectors. + /// When logs collection has completed successfully for all sources, the archive is created. + private func updateValue() { + if value?.globalStatus == .collecting && states.values.allSatisfy({ $0.status == .collected }) { + update(newValue: LogCollector(globalStatus: .archiving, states: states, destination: nil)) + ioQueue.async { + let archiveUrl = self.createZipArchive() + DispatchQueue.main.async { + self.update(newValue: LogCollector(globalStatus: archiveUrl == nil ? .failed : .done, + states: self.states, + destination: archiveUrl)) + } + } + } else { + let collecting = states.values.contains(where: { $0.status == .collecting }) + let failed = states.values.contains(where: { $0.status == .failed }) + if collecting || failed { + update(newValue: LogCollector(globalStatus: failed ? .failed : .collecting, + states: states, + destination: nil)) + } + } + } + + /// Creates an archive file from the content of the temporary directory. + /// + /// - Returns: created archive file URL, or `nil` if an error occured + private func createZipArchive() -> URL? { + guard let tmpDir = temporaryDirectory else { + return nil + } + + // first remove any existing archive + let fileManager = FileManager.default + let dstUrl = destinationDirectory.appendingPathComponent("logs.zip") + do { + if fileManager.fileExists(atPath: dstUrl.path) { + try fileManager.removeItem(at: dstUrl) + } + } catch let err { + ULog.e(.logCollectorTag, "Failed to remove archive file \(dstUrl): \(err)") + } + + // zip directory content + var archiveUrl: URL? + var error: NSError? + let coordinator = NSFileCoordinator() + coordinator.coordinate(readingItemAt: tmpDir, options: [.forUploading], error: &error) { (zipUrl) in + // move archive file to a destination directory + do { + try fileManager.moveItem(at: zipUrl, to: dstUrl) + archiveUrl = dstUrl + } catch let err { + ULog.e(.logCollectorTag, "Failed to create archive file from \(tmpDir): \(err)") + } + } + + // remove temporary directory which is no longer needed + do { + try fileManager.removeItem(at: tmpDir) + } catch let err { + ULog.e(.logCollectorTag, "Failed to remove temporary directory \(tmpDir): \(err)") + } + + return archiveUrl + } +} diff --git a/GroundSdk/Internal/Settings/SettingTimeout.swift b/GroundSdk/Internal/Settings/SettingTimeout.swift index 02d2e5b..450077c 100644 --- a/GroundSdk/Internal/Settings/SettingTimeout.swift +++ b/GroundSdk/Internal/Settings/SettingTimeout.swift @@ -33,9 +33,11 @@ import Foundation class SettingTimeout { /// Timeout in seconds - private static let timeout = 5 + static let defaultTimeout: Int = 5 - private(set) var isScheduled = false + var isScheduled: Bool { + return dispatchWorkItem != nil + } /// Block that should be executed in case of a timeout. /// @@ -43,18 +45,31 @@ class SettingTimeout { private(set) var dispatchWorkItem: DispatchWorkItem? /// Schedules a timeout - func schedule(timeoutBlock: @escaping () -> Void) { + /// - Parameters: + /// - timeout: The timeout in seconds to use + /// - queue: The queue to use for the `timeoutBlock` + /// - timeoutBlock: The block to call when reaching the timeout + func schedule(timeout: Int = SettingTimeout.defaultTimeout, + queue: DispatchQueue = .main, + timeoutBlock: @escaping () -> Void) { // be sure to cancel any pending scheduled timeout cancel() - dispatchWorkItem = DispatchWorkItem(block: timeoutBlock) - DispatchQueue.main.asyncAfter(deadline: .now() + .seconds(SettingTimeout.timeout), execute: dispatchWorkItem!) - isScheduled = true + dispatchWorkItem = DispatchWorkItem { [weak self] in + guard let self = self else { return } + timeoutBlock() + self.dispatchWorkItem = nil + } + queue.asyncAfter(deadline: .now() + .seconds(timeout), + execute: dispatchWorkItem!) } /// Cancels the scheduled timeout - func cancel() { + @discardableResult + func cancel() -> Bool { + let cancelled = dispatchWorkItem != nil dispatchWorkItem?.cancel() - isScheduled = false + dispatchWorkItem = nil + return cancelled } } diff --git a/GroundSdk/Internal/Stream/FileReplayCore.swift b/GroundSdk/Internal/Stream/FileReplayCore.swift index ce9af60..2eaa3d8 100644 --- a/GroundSdk/Internal/Stream/FileReplayCore.swift +++ b/GroundSdk/Internal/Stream/FileReplayCore.swift @@ -36,9 +36,6 @@ public class FileReplayCore: ReplayCore, FileReplay { /// Played back file. public let source: FileReplaySource - /// Pomp loop for pdraw. - private var pompLoopUtil: PompLoopUtil? - /// Constructor /// /// - Parameter source: source to be played back diff --git a/GroundSdk/Internal/ULogTag.swift b/GroundSdk/Internal/ULogTag.swift index 7b4e686..393eb1a 100644 --- a/GroundSdk/Internal/ULogTag.swift +++ b/GroundSdk/Internal/ULogTag.swift @@ -115,20 +115,23 @@ extension ULogTag { /// Ephemeris tag of ground sdk ephemeris engine (internal) static let ephemerisEngineTag = ULogTag(name: "gsdk.core.engine.ephemeris") - /// FileManager Extension tag of ground sdk (internal) - static let fileManagerExtensionTag = ULogTag(name: "gsdk.core.filemanager") - /// Logging tag of stream in ground sdk core (internal) static let streamTag = ULogTag(name: "gsdk.core.stream") /// Logging tag of ground sdk video stream engine (internal) static let videoStreamEngineTag = ULogTag(name: "gsdk.core.engine.stream") - /// Logging tag of ground sdk flight camera record collecting and upload to Parrot Cloud + /// Logging tag of ground sdk file collecting and upload to Parrot Cloud (internal) + static let parrotCloudTag = ULogTag(name: "gsdk.parrotcloud") + + /// Logging tag of ground sdk flight log collecting and upload to Parrot Cloud (internal) + static let parrotCloudFlightLogTag = ULogTag(name: "gsdk.parrotcloud.flightlog") + + /// Logging tag of ground sdk flight camera record collecting and upload to Parrot Cloud (internal) static let parrotCloudFcrTag = ULogTag(name: "gsdk.parrotcloud.flightcamerarecord") - /// tag myparrot debug - static let myparrot = ULogTag(name: "MYPARROT-gsdkv1-") + /// Logging tag of ground sdk black box collecting and upload to Parrot Cloud (internal) + static let parrotCloudBlackBoxTag = ULogTag(name: "gsdk.parrotcloud.blackbox") /// tag Hmd static let hmdTag = ULogTag(name: "gsdk.hmd") @@ -138,4 +141,7 @@ extension ULogTag { /// tag MAVLink standard static let mavlinkStandardTag = ULogTag(name: "gsdk.mavlink-standard") + + /// Logging tag of ground sdk log collector (internal) + static let logCollectorTag = ULogTag(name: "gsdk.core.logcollector") } diff --git a/GroundSdk/Internal/Utility/CloudServerCore.swift b/GroundSdk/Internal/Utility/CloudServerCore.swift index f9214fe..5b8fe4a 100644 --- a/GroundSdk/Internal/Utility/CloudServerCore.swift +++ b/GroundSdk/Internal/Utility/CloudServerCore.swift @@ -275,7 +275,7 @@ public class CloudServerCore: UtilityCore { if let userAccountValue = userAccountUtility?.userAccountInfo?.account { // add the field "x-account" in the http header request.addValue(userAccountValue, forHTTPHeaderField: "x-account") - ULog.d(.myparrot, "Header: x-account \(userAccountValue)") + ULog.d(.parrotCloudTag, "Header: x-account \(userAccountValue)") } } } @@ -290,11 +290,11 @@ private extension URLSessionConfiguration { "(\(UIDevice.current.systemName); \(UIDevice.identifier); \(UIDevice.current.systemVersion)) " + "\(AppInfoCore.sdkBundle)/\(AppInfoCore.sdkVersion)" var additionalHeaders = ["User-Agent": userAgent] - ULog.d(.myparrot, "Header: User-Agent \(userAgent)") + ULog.d(.parrotCloudTag, "Header: User-Agent \(userAgent)") // Application key if present if let applicationKey = GroundSdkConfig.sharedInstance.applicationKey { additionalHeaders["x-api-key"] = applicationKey - ULog.d(.myparrot, "Header: x-api-key \(applicationKey)") + ULog.d(.parrotCloudTag, "Header: x-api-key \(applicationKey)") } httpAdditionalHeaders = additionalHeaders diff --git a/GroundSdk/Internal/Utility/UtilityCore.swift b/GroundSdk/Internal/Utility/UtilityCore.swift index 87e52b8..2b15bb5 100644 --- a/GroundSdk/Internal/Utility/UtilityCore.swift +++ b/GroundSdk/Internal/Utility/UtilityCore.swift @@ -31,77 +31,76 @@ import Foundation /// Utility descriptor public class Utilities: NSObject { - /// Internet connectivity monitoring utility. - public static let internetConnectivity = InternetConnectivityCoreDesc() - /// Drones store utility. - public static let droneStore = DroneStoreCoreDesc() - /// Remote controls store utility. - public static let remoteControlStore = RemoteControlStoreCoreDesc() + /// Black boxes storage utility. + public static let blackBoxStorage = BlackBoxStorageCoreDesc() + /// Blacklisted versions utility. + public static let blacklistedVersionStore = BlacklistedVersionStoreCoreDesc() + /// Certificate images storage utility. + public static let certificateImagesStorage = CertificateImagesStorageCoreDesc() + /// Cloud server utility. + public static let cloudServer = CloudServerCoreDesc() /// Crash report storage utility. public static let crashReportStorage = CrashReportStorageCoreDesc() + /// Drones store utility. + public static let droneStore = DroneStoreCoreDesc() + /// GPS ephemeris utility. + public static let ephemeris = EphemerisUtilityCoreDesc() + /// Event logs utility. + public static let eventLogger = EventLogUtilityCoreDesc() + /// FileReplayBackend provider utility. + public static let fileReplayBackendProvider = FileReplayBackendProviderCoreDesc() + /// Firmware downloader utility. + public static let firmwareDownloader = FirmwareDownloaderCoreDesc() + /// Firmwares stores utility. + public static let firmwareStore = FirmwareStoreCoreDesc() + /// Flight camera records storage utility. + public static let flightCameraRecordStorage = FlightCameraRecordStorageCoreDesc() /// Flight data storage utility. public static let flightDataStorage = FlightDataStorageCoreDesc() - /// Flight logs storage utility. - public static let flightLogStorage = FlightLogStorageCoreDesc() /// Flight log converter storage utility. public static let flightLogConverterStorage = FlightLogConverterStorageCoreDesc() - /// Flight camera records storage utility. - public static let flightCameraRecordStorage = FlightCameraRecordStorageCoreDesc() + /// Flight logs storage utility. + public static let flightLogStorage = FlightLogStorageCoreDesc() /// Converted logs storage utility. public static let gutmaLogStorage = GutmaLogStorageCoreDesc() - /// Event logs utility. - public static let eventLogger = EventLogUtilityCoreDesc() - /// Firmwares stores utility. - public static let firmwareStore = FirmwareStoreCoreDesc() - /// Firmware downloader utility. - public static let firmwareDownloader = FirmwareDownloaderCoreDesc() - /// Black boxes storage utility. - public static let blackBoxStorage = BlackBoxStorageCoreDesc() - /// System position utility. - public static let systemPosition = SystemPositionCoreDesc() - /// Cloud server utility. - public static let cloudServer = CloudServerCoreDesc() + /// Internet connectivity monitoring utility. + public static let internetConnectivity = InternetConnectivityCoreDesc() + /// Remote controls store utility. + public static let remoteControlStore = RemoteControlStoreCoreDesc() /// Reverse geocoder utility. public static let reverseGeocoder = ReverseGeocoderUtilityCoreDesc() /// System barometer utility. public static let systemBarometer = SystemBarometerCoreDesc() - /// Blacklisted versions utility. - public static let blacklistedVersionStore = BlacklistedVersionStoreCoreDesc() + /// System position utility. + public static let systemPosition = SystemPositionCoreDesc() /// User account utility. public static let userAccount = UserAccountUtilityCoreDesc() - /// GPS ephemeris utility. - public static let ephemeris = EphemerisUtilityCoreDesc() - /// Certificate images storage utility. - public static let certificateImagesStorage = CertificateImagesStorageCoreDesc() - /// FileReplayBackend provider utility. - public static let fileReplayBackendProvider = FileReplayBackendProviderCoreDesc() - } /// Utilities uid enum UtilityUid: Int { - case internetConnectivity = 1 - case droneStore - case remoteControlStore - case crashReportStorage - case firmwareStore - case firmwareDownloader case blackBoxStorage - case systemPosition - case cloudServer - case reverseGeocoder - case systemBarometer case blacklistedVersionStore - case flightDataStorage - case userAccount + case certificateImagesStorage + case cloudServer + case crashReportStorage + case droneStore case ephemeris - case flightLogStorage - case flightLogConverterStorage - case flightCameraRecordStorage - case gutmaLogStorage case eventLogger - case certificateImagesStorage case fileReplayBackendProvider + case firmwareDownloader + case firmwareStore + case flightCameraRecordStorage + case flightDataStorage + case flightLogConverterStorage + case flightLogStorage + case gutmaLogStorage + case internetConnectivity + case remoteControlStore + case reverseGeocoder + case systemBarometer + case systemPosition + case userAccount } /// Describe a Utility diff --git a/GroundSdk/Log/LogCollector.swift b/GroundSdk/Log/LogCollector.swift new file mode 100644 index 0000000..287dd6c --- /dev/null +++ b/GroundSdk/Log/LogCollector.swift @@ -0,0 +1,161 @@ +// Copyright (C) 2022 Parrot Drones SAS +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in +// the documentation and/or other materials provided with the +// distribution. +// * Neither the name of the Parrot Company nor the names +// of its contributors may be used to endorse or promote products +// derived from this software without specific prior written +// permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// PARROT COMPANY BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +// OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +// AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +// OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT +// OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF +// SUCH DAMAGE. + +import Foundation + +/// Log collector source. +public enum LogCollectorSource: Hashable, CustomStringConvertible { + /// A drone source. + case drone(Drone) + /// A remote control source. + case remoteControl(RemoteControl) + /// An application source. + case application(URL) + + /// Debug description. + public var description: String { + switch self { + case let .drone(device): + return "drone: \(device.name)" + case let .remoteControl(device): + return "remote control: \(device.name)" + case .application: + return "application" + } + } +} + +/// Status of the log collection for all sources. +public enum LogCollectorGlobalStatus: CustomStringConvertible { + /// Collection is in progress. + case collecting + /// Logs archiving is in progress. + case archiving + /// Collection process has completed successfully. + case done + /// Collection process has failed. + case failed + + /// Debug description. + public var description: String { + switch self { + case .collecting: + return "collecting" + case .archiving: + return "archiving" + case .done: + return "done" + case .failed: + return "failed" + } + } +} + +/// Status of the log collection for one source. +public enum LogCollectorStatus: CustomStringConvertible { + /// Collection is pending. + case pending + /// Collection is in progress. + case collecting + /// Collection has completed successfully. + case collected + /// Collection has failed. + case failed + /// Collection has been canceled. + case canceled + + /// Debug description. + public var description: String { + switch self { + case .pending: + return "pending" + case .collecting: + return "collecting" + case .collected: + return "collected" + case .failed: + return "failed" + case .canceled: + return "canceled" + } + } +} + +/// State of the log collection for one source. +public class LogCollectorState: CustomStringConvertible { + /// Status of the log collection. + public internal(set) var status: LogCollectorStatus + + /// Overall size of the logs that should be collected, in bytes. + public internal(set) var totalSize: UInt64? + + /// Size of the logs that have already been collected, in bytes. + public internal(set) var collectedSize: UInt64? + + /// Constructor. + /// + /// - Parameters: + /// - status: the initial status + /// - totalSize: the initial overall size + /// - collectedSize: the initial collected size + internal init(status: LogCollectorStatus = .pending, totalSize: UInt64? = nil, collectedSize: UInt64? = nil) { + self.status = status + self.totalSize = totalSize + self.collectedSize = collectedSize + } + + /// Debug description. + public var description: String { + return "\(status) \(String(describing: collectedSize))/\(String(describing: totalSize))" + } +} + +/// Latest logs collector interface. +public class LogCollector { + /// Overall status of the log collection. + public let globalStatus: LogCollectorGlobalStatus + + /// Collector states, by their associated source. + public let states: [LogCollectorSource: LogCollectorState] + + /// URL of archive file containing latest logs when global status is `collected`, nil in other cases. + public let destination: URL? + + /// Constructor. + /// + /// - Parameters: + /// - globalStatus: overall status + /// - states: states by sources + /// - destination: created archive file URL + init(globalStatus: LogCollectorGlobalStatus, states: [LogCollectorSource: LogCollectorState], destination: URL?) { + self.globalStatus = globalStatus + self.states = states + self.destination = destination + } +} diff --git a/GroundSdk/Mavlink/standard/CameraTriggerDistanceCommand.swift b/GroundSdk/Mavlink/standard/CameraTriggerDistanceCommand.swift index c9d7311..44cb5ed 100644 --- a/GroundSdk/Mavlink/standard/CameraTriggerDistanceCommand.swift +++ b/GroundSdk/Mavlink/standard/CameraTriggerDistanceCommand.swift @@ -71,8 +71,11 @@ extension MavlinkStandard { /// than trigger cycle time. Use -1 or 0 to ignore. The minimum value is -1 and the /// increment is 1. Ignored by Anafi. /// - triggerOnceImmediately: Trigger camera once immediately. Ignored by Anafi. - public init(distance: Double, shutterIntegration: Int = -1, triggerOnceImmediately: Bool) { + /// - frame: the reference frame of the coordinates. + public init(distance: Double, shutterIntegration: Int = -1, triggerOnceImmediately: Bool, + frame: Frame = .command) { super.init(type: .cameraTriggerDistance, + frame: frame, param1: distance, param2: Double(shutterIntegration), param3: triggerOnceImmediately ? 1.0 : 0.0) @@ -80,8 +83,10 @@ extension MavlinkStandard { /// Constructor from generic MAVLink parameters. /// - /// - Parameter parameters: the raw parameters of the command. - convenience init(parameters: [Double]) throws { + /// - Parameters: + /// - frame: the reference frame of the coordinates + /// - parameters: generic command parameters + convenience init(frame: Frame = .command, parameters: [Double]) throws { assert(parameters.count == 7) guard parameters.count == 7 else { throw MavlinkStandard.MavlinkCommand.ParseError @@ -92,7 +97,8 @@ extension MavlinkStandard { let triggerOnceImmediately = parameters[2] self.init(distance: distance, shutterIntegration: Int(shutterIntegration), - triggerOnceImmediately: triggerOnceImmediately != 0.0) + triggerOnceImmediately: triggerOnceImmediately != 0.0, + frame: frame) } } } diff --git a/GroundSdk/Mavlink/standard/CameraTriggerIntervalCommand.swift b/GroundSdk/Mavlink/standard/CameraTriggerIntervalCommand.swift index 8225aaf..5dd5eaf 100644 --- a/GroundSdk/Mavlink/standard/CameraTriggerIntervalCommand.swift +++ b/GroundSdk/Mavlink/standard/CameraTriggerIntervalCommand.swift @@ -63,17 +63,21 @@ extension MavlinkStandard { /// - triggerCycle: camera trigger cycle time in milliseconds. Use -1 or 0 to ignore. /// - shutterIntegration: camera shutter integration time in milliseconds. Use -1 or 0 to /// ignore. Should be less than trigger cycle time. Always ignored by Anafi. - public init(triggerCycle: Int, shutterIntegration: Int = -1) { + /// - frame: the reference frame of the coordinates + public init(triggerCycle: Int, shutterIntegration: Int = -1, frame: Frame = .command) { assert(shutterIntegration < triggerCycle) super.init(type: .cameraTriggerInterval, + frame: frame, param1: Double(triggerCycle), param2: Double(shutterIntegration)) } /// Constructor from generic MAVLink parameters. /// - /// - Parameter parameters: the raw parameters of the command. - convenience init(parameters: [Double]) throws { + /// - Parameters: + /// - frame: the reference frame of the coordinates + /// - parameters: generic command parameters + convenience init(frame: Frame = .command, parameters: [Double]) throws { assert(parameters.count == 7) guard parameters.count == 7 else { throw MavlinkStandard.MavlinkCommand.ParseError @@ -82,7 +86,8 @@ extension MavlinkStandard { let triggerCycle = parameters[0] let shutterIntegration = parameters[1] self.init(triggerCycle: Int(triggerCycle), - shutterIntegration: Int(shutterIntegration)) + shutterIntegration: Int(shutterIntegration), + frame: frame) } } } diff --git a/GroundSdk/Mavlink/standard/ChangeSpeedCommand.swift b/GroundSdk/Mavlink/standard/ChangeSpeedCommand.swift index 851d681..89c8cb8 100644 --- a/GroundSdk/Mavlink/standard/ChangeSpeedCommand.swift +++ b/GroundSdk/Mavlink/standard/ChangeSpeedCommand.swift @@ -84,10 +84,13 @@ extension MavlinkStandard { /// - speedType: speed type /// - speed: speed, in meters/second /// - relative: boolean indicate wether the speed change is absolute or relative + /// - frame: the reference frame of the coordinates public init(speedType: SpeedType, speed: Double, - relative: Bool = false) { + relative: Bool = false, + frame: Frame = .command) { super.init(type: .changeSpeed, + frame: frame, param1: Double(speedType.rawValue), param2: speed, param3: Constants.doNotChangeThrottle, @@ -96,8 +99,10 @@ extension MavlinkStandard { /// Constructor from generic MAVLink parameters. /// - /// - Parameter parameters: generic command parameters - convenience init(parameters: [Double]) throws { + /// - Parameters: + /// - frame: the reference frame of the coordinates + /// - parameters: generic command parameters + convenience init(frame: Frame = .command, parameters: [Double]) throws { assert(parameters.count == 7) guard parameters.count == 7 else { throw MavlinkStandard.MavlinkCommand.ParseError @@ -112,7 +117,8 @@ extension MavlinkStandard { let relative = parameters[3] self.init(speedType: speedType, speed: speed, - relative: relative != 0) + relative: relative != 0, + frame: frame) } } } diff --git a/GroundSdk/Mavlink/standard/CreatePanoramaCommand.swift b/GroundSdk/Mavlink/standard/CreatePanoramaCommand.swift index 2569ecf..2191912 100644 --- a/GroundSdk/Mavlink/standard/CreatePanoramaCommand.swift +++ b/GroundSdk/Mavlink/standard/CreatePanoramaCommand.swift @@ -61,15 +61,19 @@ extension MavlinkStandard { /// - horizontalSpeed: horizontal rotation speed, in degrees/second /// - verticalAngle: vertical rotation angle, in degrees /// - verticalSpeed: vertical rotation speed, in degrees/second - public init(horizontalAngle: Double, horizontalSpeed: Double, verticalAngle: Double, verticalSpeed: Double) { - super.init(type: .createPanorama, - param1: horizontalAngle, param2: verticalAngle, param3: horizontalSpeed, param4: verticalSpeed) + /// - frame: the reference frame of the coordinates + public init(horizontalAngle: Double, horizontalSpeed: Double, verticalAngle: Double, + verticalSpeed: Double, frame: Frame = .command) { + super.init(type: .createPanorama, frame: frame, param1: horizontalAngle, + param2: verticalAngle, param3: horizontalSpeed, param4: verticalSpeed) } /// Constructor from generic MAVLink parameters. /// - /// - Parameter parameters: generic command parameters - convenience init(parameters: [Double]) throws { + /// - Parameters: + /// - frame: the reference frame of the coordinates + /// - parameters: generic command parameters + convenience init(frame: Frame = .command, parameters: [Double]) throws { assert(parameters.count == 7) guard parameters.count == 7 else { throw MavlinkStandard.MavlinkCommand.ParseError @@ -79,8 +83,8 @@ extension MavlinkStandard { let verticalAngle = parameters[1] let horizontalSpeed = parameters[2] let verticalSpeed = parameters[3] - self.init(horizontalAngle: horizontalAngle, horizontalSpeed: horizontalSpeed, verticalAngle: verticalAngle, - verticalSpeed: verticalSpeed) + self.init(horizontalAngle: horizontalAngle, horizontalSpeed: horizontalSpeed, + verticalAngle: verticalAngle, verticalSpeed: verticalSpeed, frame: frame) } } } diff --git a/GroundSdk/Mavlink/standard/DelayCommand.swift b/GroundSdk/Mavlink/standard/DelayCommand.swift index 7296932..c6c73f1 100644 --- a/GroundSdk/Mavlink/standard/DelayCommand.swift +++ b/GroundSdk/Mavlink/standard/DelayCommand.swift @@ -41,22 +41,26 @@ extension MavlinkStandard { /// Constructor. /// - /// - Parameter delay: delay, in seconds (decimal). - public init(delay: Double) { - super.init(type: .delay, param1: delay) + /// - Parameters: + /// - delay: delay, in seconds (decimal). + /// - frame: the reference frame of the coordinates. + public init(delay: Double, frame: Frame = .command) { + super.init(type: .delay, frame: frame, param1: delay) } /// Constructor from generic MAVLink parameters. /// - /// - Parameter parameters: generic command parameters - convenience init(parameters: [Double]) throws { + /// - Parameters: + /// - frame: the reference frame of the coordinates + /// - parameters: generic command parameters + convenience init(frame: Frame = .command, parameters: [Double]) throws { assert(parameters.count == 7) guard parameters.count == 7 else { throw MavlinkStandard.MavlinkCommand.ParseError .incorrectNumberOfParameters("Expected 7 parameters but instead got \(parameters.count).") } let delay = parameters[0] - self.init(delay: delay) + self.init(delay: delay, frame: frame) } } } diff --git a/GroundSdk/Mavlink/standard/LandCommand.swift b/GroundSdk/Mavlink/standard/LandCommand.swift index c16b799..6586c69 100644 --- a/GroundSdk/Mavlink/standard/LandCommand.swift +++ b/GroundSdk/Mavlink/standard/LandCommand.swift @@ -68,11 +68,14 @@ extension MavlinkStandard { /// - latitude: latitude of the implicitly added waypoint, in degrees. /// - longitude: longitude of the implicitly added waypoint, in degrees. /// - altitude: altitude of the implicitly added waypoint above take off point, in meters. + /// - frame: the reference frame of the coordinates. public init(yaw: Double = .nan, latitude: Double = 0.0, longitude: Double = 0.0, - altitude: Double = 0.0) { + altitude: Double = 0.0, + frame: Frame = .relative) { super.init(type: .land, + frame: frame, param4: yaw, latitude: latitude, longitude: longitude, @@ -82,8 +85,9 @@ extension MavlinkStandard { /// Constructor from generic MAVLink parameters. /// /// - Parameters: - /// - parameters: generic command parameters. - convenience init(parameters: [Double]) throws { + /// - frame: the reference frame of the coordinates + /// - parameters: generic command parameters + convenience init(frame: Frame = .relative, parameters: [Double]) throws { assert(parameters.count == 7) guard parameters.count == 7 else { throw MavlinkStandard.MavlinkCommand.ParseError @@ -96,7 +100,8 @@ extension MavlinkStandard { self.init(yaw: yaw, latitude: latitude, longitude: longitude, - altitude: altitude) + altitude: altitude, + frame: frame) } } } diff --git a/GroundSdk/Mavlink/standard/MavlinkCommand.swift b/GroundSdk/Mavlink/standard/MavlinkCommand.swift index fb9973b..17c0a35 100644 --- a/GroundSdk/Mavlink/standard/MavlinkCommand.swift +++ b/GroundSdk/Mavlink/standard/MavlinkCommand.swift @@ -35,6 +35,8 @@ extension MavlinkStandard { /// A MAVLink command. /// + /// [Parrot FlightPlan Mavlink documentation](https://developer.parrot.com/docs/mavlink-flightplan/overview.html). + /// /// Clients of this API cannot instantiate this class directly, and must use /// one of the subclasses defining a specific MAVLink command. If a subclass /// does not describe the command you want to use use `OtherMavlinkCommand`. @@ -158,12 +160,21 @@ extension MavlinkStandard { } } + /// The reference frame of the command. + public enum Frame: UInt, Equatable { + /// Global coordinate frame WGS84 coordinate system. Altitude are expressed in over mean + /// sea level (MSL). + case global = 0 + /// Not a coordinate frame, indicates a mission command + case command = 2 + /// Coordinate frame, WGS84 coordinate system, relative altitude over ground with + /// respect to the home position. + case relative = 3 + } + /// Value always used for current waypoint; set to false. private static let currentWaypoint = 0 - /// Value always used for coordinate frame; set to global coordinate frame, relative altitude over ground. - private static let frame = 3 - /// Value always used for auto-continue; set to true. private static let autoContinue = 1 @@ -175,6 +186,9 @@ extension MavlinkStandard { /// The MAVLink command type. internal let rawType: Int + /// The coordinate frame; set to global coordinate frame or relative altitude over ground. + public let frame: Frame + /// The raw parameters of the command. internal let parameters: [Double] @@ -185,15 +199,18 @@ extension MavlinkStandard { /// `rawType` must be greater than 0. /// - rawType: the MAVLink raw type. If greater than zero then `type` /// must be `.other`. + /// - frame: the reference frame of the coordinates. /// - parameters: the raw parameters of the command. internal init(type: CommandType, rawType: Int = -1, + frame: Frame = .relative, parameters: [Double] = [.nan, .nan, .nan, .nan, .nan, .nan, .nan]) { assert((type == .other && rawType > 0) || (type != .other && rawType == -1)) assert(parameters.count == 7) self.rawType = type == .other ? rawType : type.rawValue self.parameters = parameters + self.frame = frame } /// Constructor. @@ -202,6 +219,7 @@ extension MavlinkStandard { /// - type: the MAVLink command type. If the type is `.other` then /// `rawType` must be greater than 0. /// - rawType: the MAVLink raw type. If greater than zero then `type` + /// - frame: the reference frame of the coordinates. /// - param1: the first parameter of the command. /// - param2: the second parameter of the command. /// - param3: the third parameter of the command. @@ -211,6 +229,7 @@ extension MavlinkStandard { /// - altitude: the altitude of the command internal init(type: CommandType, rawType: Int = -1, + frame: Frame = .relative, param1: Double = .nan, param2: Double = .nan, param3: Double = .nan, @@ -223,6 +242,7 @@ extension MavlinkStandard { self.rawType = type == .other ? rawType : type.rawValue self.parameters = [param1, param2, param3, param4, latitude, longitude, altitude] + self.frame = frame } public static func == (lhs: MavlinkCommand, rhs: MavlinkCommand) -> Bool { @@ -234,13 +254,14 @@ extension MavlinkStandard { return abs(a - b) < affinity } return lhs.rawType == rhs.rawType - && equal(lhs.parameters[0], rhs.parameters[0]) - && equal(lhs.parameters[1], rhs.parameters[1]) - && equal(lhs.parameters[2], rhs.parameters[2]) - && equal(lhs.parameters[3], rhs.parameters[3]) - && equal(lhs.parameters[4], rhs.parameters[4]) - && equal(lhs.parameters[5], rhs.parameters[5]) - && equal(lhs.parameters[6], rhs.parameters[6]) + && lhs.frame == rhs.frame + && equal(lhs.parameters[0], rhs.parameters[0]) + && equal(lhs.parameters[1], rhs.parameters[1]) + && equal(lhs.parameters[2], rhs.parameters[2]) + && equal(lhs.parameters[3], rhs.parameters[3]) + && equal(lhs.parameters[4], rhs.parameters[4]) + && equal(lhs.parameters[5], rhs.parameters[5]) + && equal(lhs.parameters[6], rhs.parameters[6]) } /// Writes the MAVLink command to the specified file. @@ -248,10 +269,12 @@ extension MavlinkStandard { /// - Parameters: /// - fileHandle: handle on the file the command is written to /// - index: the index of the command - func write(fileHandle: FileHandle, index: Int) { + /// - frame: the reference frame of the coordinates + func write(fileHandle: FileHandle, index: Int, frame: Frame = .relative) { doWrite(fileHandle: fileHandle, index: index, rawType: rawType, + frame: frame, param1: parameters[0], param2: parameters[1], param3: parameters[2], @@ -267,6 +290,7 @@ extension MavlinkStandard { /// - fileHandle: handle on the file the command is written to /// - index: the index of the command /// - rawType: the raw type of the command + /// - frame: the reference frame of the coordinates /// - param1: first parameter of the command, type dependant /// - param2: second parameter of the command, type dependant /// - param3: third parameter of the command, type dependant @@ -274,11 +298,11 @@ extension MavlinkStandard { /// - latitude: the latitude of the command /// - longitude: the longitude of the command /// - altitude: the altitude of the command - private func doWrite(fileHandle: FileHandle, index: Int, rawType: Int, param1: Double = .nan, - param2: Double = .nan, param3: Double = .nan, param4: Double = .nan, + private func doWrite(fileHandle: FileHandle, index: Int, rawType: Int, frame: Frame = .relative, + param1: Double = .nan, param2: Double = .nan, param3: Double = .nan, param4: Double = .nan, latitude: Double = .nan, longitude: Double = .nan, altitude: Double = .nan) { let line = String(format: "%d\t%d\t%d\t%d\t%f\t%f\t%f\t%f\t%f\t%f\t%f\t%d\n", - index, MavlinkCommand.currentWaypoint, MavlinkCommand.frame, rawType, + index, MavlinkCommand.currentWaypoint, frame.rawValue, rawType, param1, param2, param3, param4, latitude, longitude, altitude, MavlinkCommand.autoContinue) if let data = line.data(using: .utf8) { @@ -316,31 +340,38 @@ extension MavlinkStandard.MavlinkCommand { guard let type = CommandType(rawValue: rawType) else { return try MavlinkStandard.OtherMavlinkCommand(rawType: rawType, parameters: parameters) } - return try command(forType: type, parameters: parameters) + guard let frameRawValue = UInt(tokens[2]), let frame = Frame(rawValue: frameRawValue) else { + throw ParseError.invalidParameter("The mavlink frame is malformed") + } + return try command(forType: type, frame: frame, parameters: parameters) } /// Create a MAVLink command. /// /// - Parameters: /// - rawType: the integer that describes the type of the MAVLink command. + /// - frame: the reference frame of the coordinates. /// - parameters: the raw parameters of the command. /// - Throws: MavlinkStandard.MavlinkCommand.ParseError if the parameters are wrong. /// - Returns: A MAVLink command. - static func create(rawType: Int, parameters: [Double]) throws -> MavlinkStandard.MavlinkCommand { + static func create(rawType: Int, frame: Frame, parameters: [Double]) throws -> MavlinkStandard.MavlinkCommand { guard parameters.count == 7 else { throw MavlinkStandard.MavlinkCommand.ParseError .incorrectNumberOfParameters("Expected 7 parameters but instead got \(parameters.count).") } if let type = CommandType(rawValue: rawType) { - return try command(forType: type, parameters: parameters) + return try command(forType: type, frame: frame, parameters: parameters) } - return try MavlinkStandard.OtherMavlinkCommand(rawType: rawType, parameters: parameters) + return try MavlinkStandard.OtherMavlinkCommand(rawType: rawType, + frame: frame, + parameters: parameters) } /// Create a MAVLink command. /// /// - Parameters: /// - rawType: the integer that describes the type of the MAVLink command. + /// - frame: the reference frame of the coordinates. /// - param1: first parameter of the command, type dependant /// - param2: second parameter of the command, type dependant /// - param3: third parameter of the command, type dependant @@ -350,7 +381,9 @@ extension MavlinkStandard.MavlinkCommand { /// - altitude: the altitude of the command /// - Throws: MavlinkStandard.MavlinkCommand.ParseError if the parameters are wrong. /// - Returns: A MAVLink command. - static func create(rawType: Int, param1: Double = .nan, + static func create(rawType: Int, + frame: Frame, + param1: Double = .nan, param2: Double = .nan, param3: Double = .nan, param4: Double = .nan, @@ -358,6 +391,7 @@ extension MavlinkStandard.MavlinkCommand { longitude: Double = .nan, altitude: Double = .nan) throws -> MavlinkStandard.MavlinkCommand { return try create(rawType: rawType, + frame: frame, parameters: [param1, param2, param3, param4, latitude, longitude, altitude]) } @@ -371,6 +405,7 @@ extension MavlinkStandard.MavlinkCommand { /// /// - Parameters: /// - type: the command type. + /// - frame: the reference frame of the coordinates /// - param1: first parameter of the command, type dependant /// - param2: second parameter of the command, type dependant /// - param3: third parameter of the command, type dependant @@ -381,6 +416,7 @@ extension MavlinkStandard.MavlinkCommand { /// - Throws: MavlinkStandard.MavlinkCommand.ParseError if the parameters are wrong. /// - Returns: A MAVLink command. static private func command(forType type: CommandType, + frame: Frame = .relative, param1: Double = .nan, param2: Double = .nan, param3: Double = .nan, @@ -389,6 +425,7 @@ extension MavlinkStandard.MavlinkCommand { longitude: Double = .nan, altitude: Double = .nan) throws -> MavlinkStandard.MavlinkCommand { return try command(forType: type, + frame: frame, parameters: [param1, param2, param3, param4, latitude, longitude, altitude]) } @@ -397,50 +434,52 @@ extension MavlinkStandard.MavlinkCommand { /// /// - Parameters: /// - type: the command type. + /// - frame: the reference frame of the coordinates. /// - parameters: the raw parameters. /// - Throws: MavlinkStandard.MavlinkCommand.ParseError if the parameters are wrong. /// - Returns: A MAVLink command. static private func command(forType type: CommandType, + frame: Frame, parameters: [Double]) throws -> MavlinkStandard.MavlinkCommand { switch type { case .navigateToWaypoint: - return try MavlinkStandard.NavigateToWaypointCommand(parameters: parameters) + return try MavlinkStandard.NavigateToWaypointCommand(frame: frame, parameters: parameters) case .returnToLaunch: - return MavlinkStandard.ReturnToLaunchCommand() + return MavlinkStandard.ReturnToLaunchCommand(frame: frame) case .land: - return try MavlinkStandard.LandCommand(parameters: parameters) + return try MavlinkStandard.LandCommand(frame: frame, parameters: parameters) case .takeOff: - return try MavlinkStandard.TakeOffCommand(parameters: parameters) + return try MavlinkStandard.TakeOffCommand(frame: frame, parameters: parameters) case .delay: - return try MavlinkStandard.DelayCommand(parameters: parameters) + return try MavlinkStandard.DelayCommand(frame: frame, parameters: parameters) case .changeSpeed: - return try MavlinkStandard.ChangeSpeedCommand(parameters: parameters) + return try MavlinkStandard.ChangeSpeedCommand(frame: frame, parameters: parameters) case .setRoiLocation: - return try MavlinkStandard.SetRoiLocationCommand(parameters: parameters) + return try MavlinkStandard.SetRoiLocationCommand(frame: frame, parameters: parameters) case .setRoi: - return try MavlinkStandard.SetRoiCommand(parameters: parameters) + return try MavlinkStandard.SetRoiCommand(frame: frame, parameters: parameters) case .mountControl: - return try MavlinkStandard.MountControlCommand(parameters: parameters) + return try MavlinkStandard.MountControlCommand(frame: frame, parameters: parameters) case .cameraTriggerDistance: - return try MavlinkStandard.CameraTriggerDistanceCommand(parameters: parameters) + return try MavlinkStandard.CameraTriggerDistanceCommand(frame: frame, parameters: parameters) case .cameraTriggerInterval: - return try MavlinkStandard.CameraTriggerIntervalCommand(parameters: parameters) + return try MavlinkStandard.CameraTriggerIntervalCommand(frame: frame, parameters: parameters) case .startPhotoCapture: - return try MavlinkStandard.StartPhotoCaptureCommand(parameters: parameters) + return try MavlinkStandard.StartPhotoCaptureCommand(frame: frame, parameters: parameters) case .stopPhotoCapture: - return MavlinkStandard.StopPhotoCaptureCommand() + return MavlinkStandard.StopPhotoCaptureCommand(frame: frame) case .startVideoCapture: - return MavlinkStandard.StartVideoCaptureCommand() + return MavlinkStandard.StartVideoCaptureCommand(frame: frame) case .stopVideoCapture: - return MavlinkStandard.StopVideoCaptureCommand() + return MavlinkStandard.StopVideoCaptureCommand(frame: frame) case .createPanorama: - return try MavlinkStandard.CreatePanoramaCommand(parameters: parameters) + return try MavlinkStandard.CreatePanoramaCommand(frame: frame, parameters: parameters) case .setViewMode: - return try MavlinkStandard.SetViewModeCommand(parameters: parameters) + return try MavlinkStandard.SetViewModeCommand(frame: frame, parameters: parameters) case .setStillCaptureMode: - return try MavlinkStandard.SetStillCaptureModeCommand(parameters: parameters) + return try MavlinkStandard.SetStillCaptureModeCommand(frame: frame, parameters: parameters) case .setRoiNone: - return MavlinkStandard.SetRoiNoneCommand() + return MavlinkStandard.SetRoiNoneCommand(frame: frame) default: assert(false) // should not get to this point. throw ParseError.generic diff --git a/GroundSdk/Mavlink/standard/MavlinkFiles.swift b/GroundSdk/Mavlink/standard/MavlinkFiles.swift index 08c86eb..492342d 100644 --- a/GroundSdk/Mavlink/standard/MavlinkFiles.swift +++ b/GroundSdk/Mavlink/standard/MavlinkFiles.swift @@ -66,7 +66,7 @@ extension MavlinkStandard { if let fileHandle = FileHandle(forWritingAtPath: filepath) { fileHandle.seekToEndOfFile() for (index, command) in commands.enumerated() { - command.write(fileHandle: fileHandle, index: index) + command.write(fileHandle: fileHandle, index: index, frame: command.frame) } fileHandle.closeFile() } @@ -96,7 +96,7 @@ extension MavlinkStandard { ULog.e(.mavlinkStandardTag, "Invalid input. The provided MAVLink string is empty.") throw MavlinkStandard.MavlinkCommand.ParseError.generic } - let content = mavlinkString.components(separatedBy: .newlines) + let content = mavlinkString.components(separatedBy: .newlines).filter { !$0.isEmpty } guard !content.isEmpty else { ULog.e(.mavlinkStandardTag, "Invalid input. The provided MAVLink string does not contain any lines.") diff --git a/GroundSdk/Mavlink/standard/MountControlCommand.swift b/GroundSdk/Mavlink/standard/MountControlCommand.swift index ebd0b41..bea0163 100644 --- a/GroundSdk/Mavlink/standard/MountControlCommand.swift +++ b/GroundSdk/Mavlink/standard/MountControlCommand.swift @@ -99,9 +99,11 @@ extension MavlinkStandard { /// - mode: the mount mode. Only `.targeting` and `.neutral` are supported. When /// `.neutral` is used then *all* other parameters are *ignored* and the gimbal /// resets to its default position. - public init(tiltAngle: Double, yaw: Double, mode: Mode = .targeting) { + /// - frame: the reference frame of the coordinates. + public init(tiltAngle: Double, yaw: Double, mode: Mode = .targeting, frame: Frame = .command) { assert(mode == .neutral || mode == .targeting) super.init(type: .mountControl, + frame: frame, param1: tiltAngle, param3: yaw, altitude: Double(mode.rawValue)) @@ -109,8 +111,10 @@ extension MavlinkStandard { /// Constructor from generic MAVLink parameters. /// - /// - Parameter parameters: generic command parameters - convenience init(parameters: [Double]) throws { + /// - Parameters: + /// - frame: the reference frame of the coordinates + /// - parameters: generic command parameters + convenience init(frame: Frame = .command, parameters: [Double]) throws { assert(parameters.count == 7) guard parameters.count == 7 else { throw MavlinkStandard.MavlinkCommand.ParseError @@ -123,7 +127,7 @@ extension MavlinkStandard { throw MavlinkStandard.MavlinkCommand.ParseError .invalidParameter("Parameter 7 (mode) was out of range.") } - self.init(tiltAngle: tiltAngle, yaw: yaw, mode: mode) + self.init(tiltAngle: tiltAngle, yaw: yaw, mode: mode, frame: frame) } } } diff --git a/GroundSdk/Mavlink/standard/NavigateToWaypointCommand.swift b/GroundSdk/Mavlink/standard/NavigateToWaypointCommand.swift index b7e7011..8139fb9 100644 --- a/GroundSdk/Mavlink/standard/NavigateToWaypointCommand.swift +++ b/GroundSdk/Mavlink/standard/NavigateToWaypointCommand.swift @@ -75,16 +75,19 @@ extension MavlinkStandard { /// yaw to home, etc.). /// - holdTime: time to stay at waypoint, in seconds /// - acceptanceRadius: acceptance radius, in meters + /// - frame: the reference frame of the coordinates public init(latitude: Double, longitude: Double, altitude: Double, yaw: Double, holdTime: Double = 0, - acceptanceRadius: Double = 5) { - super.init(type: .navigateToWaypoint, param1: holdTime, param2: acceptanceRadius, + acceptanceRadius: Double = 5, frame: Frame = .relative) { + super.init(type: .navigateToWaypoint, frame: frame, param1: holdTime, param2: acceptanceRadius, param4: yaw, latitude: latitude, longitude: longitude, altitude: altitude) } /// Constructor from generic MAVLink parameters. /// - /// - Parameter parameters: generic command parameters - convenience init(parameters: [Double]) throws { + /// - Parameters: + /// - frame: the reference frame of the coordinates + /// - parameters: generic command parameters + convenience init(frame: Frame = .relative, parameters: [Double]) throws { assert(parameters.count == 7) guard parameters.count == 7 else { throw MavlinkStandard.MavlinkCommand.ParseError @@ -97,7 +100,7 @@ extension MavlinkStandard { let holdTime = parameters[0] let acceptanceRadius = parameters[1] self.init(latitude: latitude, longitude: longitude, altitude: altitude, yaw: yaw, holdTime: holdTime, - acceptanceRadius: acceptanceRadius) + acceptanceRadius: acceptanceRadius, frame: frame) } } } diff --git a/GroundSdk/Mavlink/standard/OtherMavlinkCommand.swift b/GroundSdk/Mavlink/standard/OtherMavlinkCommand.swift index 6afccfb..a10a95b 100644 --- a/GroundSdk/Mavlink/standard/OtherMavlinkCommand.swift +++ b/GroundSdk/Mavlink/standard/OtherMavlinkCommand.swift @@ -53,6 +53,7 @@ extension MavlinkStandard { /// /// - Parameters: /// - rawType: the integer that describes the type of the MAVLink command. + /// - frame: the reference frame of the coordinates. /// - param1: the first parameter of the command. /// - param2: the second parameter of the command. /// - param3: the third parameter of the command. @@ -60,11 +61,10 @@ extension MavlinkStandard { /// - param5: the fifth parameter of the command. /// - param6: the sixth parameter of the command. /// - param7: the seventh parameter of the command. - public init(rawType: Int, param1: Double = .nan, param2: Double = .nan, + public init(rawType: Int, frame: Frame = .relative, param1: Double = .nan, param2: Double = .nan, param3: Double = .nan, param4: Double = .nan, param5: Double = .nan, param6: Double = .nan, param7: Double = .nan) { - super.init(type: .other, - rawType: rawType, + super.init(type: .other, rawType: rawType, frame: frame, parameters: [param1, param2, param3, param4, param5, param6, param7]) } @@ -72,16 +72,15 @@ extension MavlinkStandard { /// /// - Parameters: /// - rawType: the integer that describes the type of the MAVLink command. + /// - frame: the reference frame of the coordinates. /// - parameters: the parameters of the command. - public init(rawType: Int, parameters: [Double]) throws { + public init(rawType: Int, frame: Frame = .relative, parameters: [Double]) throws { assert(parameters.count == 7) guard parameters.count == 7 else { throw MavlinkStandard.MavlinkCommand.ParseError .incorrectNumberOfParameters("Expected 7 parameters but instead got \(parameters.count).") } - super.init(type: .other, - rawType: rawType, - parameters: parameters) + super.init(type: .other, rawType: rawType, frame: frame, parameters: parameters) } } } diff --git a/GroundSdk/Mavlink/standard/ReturnToLaunchCommand.swift b/GroundSdk/Mavlink/standard/ReturnToLaunchCommand.swift index e40d391..599bbec 100644 --- a/GroundSdk/Mavlink/standard/ReturnToLaunchCommand.swift +++ b/GroundSdk/Mavlink/standard/ReturnToLaunchCommand.swift @@ -37,8 +37,11 @@ extension MavlinkStandard { public final class ReturnToLaunchCommand: MavlinkStandard.MavlinkCommand { /// Constructor. - public init() { - super.init(type: .returnToLaunch) + /// + /// - Parameters: + /// - frame: the reference frame of the coordinates. + public init(frame: Frame = .command) { + super.init(type: .returnToLaunch, frame: frame) } } } diff --git a/GroundSdk/Mavlink/standard/SetRoiCommand.swift b/GroundSdk/Mavlink/standard/SetRoiCommand.swift index 2ec94b9..05b6faf 100644 --- a/GroundSdk/Mavlink/standard/SetRoiCommand.swift +++ b/GroundSdk/Mavlink/standard/SetRoiCommand.swift @@ -105,15 +105,18 @@ extension MavlinkStandard { /// functions as longitude. Roll is ignored by Anafi 2. /// - yawOrAltitude: when mode is `.waypointNext` functions as the yaw offset from next /// waypoint, when `.location` functions as altitude. + /// - frame: the reference frame of the coordinates. public init(mode: Mode, waypointIndex: Int, roiIndex: Int, pitchOrLatitude: Double, rollOrLongitude: Double, - yawOrAltitude: Double) { + yawOrAltitude: Double, + frame: Frame = .relative) { assert(0 <= roiIndex && roiIndex <= 255) assert(0 <= waypointIndex) super.init(type: .setRoi, + frame: frame, param1: Double(mode.rawValue), param2: Double(waypointIndex), param3: Double(roiIndex), @@ -124,8 +127,10 @@ extension MavlinkStandard { /// Constructor from generic MAVLink parameters. /// - /// - Parameter parameters: generic command parameters - convenience init(parameters: [Double]) throws { + /// - Parameters: + /// - frame: the reference frame of the coordinates + /// - parameters: generic command parameters + convenience init(frame: Frame = .relative, parameters: [Double]) throws { assert(parameters.count == 7) guard parameters.count == 7 else { throw MavlinkStandard.MavlinkCommand.ParseError @@ -154,7 +159,8 @@ extension MavlinkStandard { roiIndex: roiIndex, pitchOrLatitude: pitchOrLatitude, rollOrLongitude: rollOrLongitude, - yawOrAltitude: yawOrAltitude) + yawOrAltitude: yawOrAltitude, + frame: frame) } } } diff --git a/GroundSdk/Mavlink/standard/SetRoiLocationCommand.swift b/GroundSdk/Mavlink/standard/SetRoiLocationCommand.swift index 04ce62e..f418bce 100644 --- a/GroundSdk/Mavlink/standard/SetRoiLocationCommand.swift +++ b/GroundSdk/Mavlink/standard/SetRoiLocationCommand.swift @@ -57,8 +57,10 @@ extension MavlinkStandard { /// - latitude: Latitude of ROI location. /// - longitude: Longitude of ROI location. /// - altitude: Altitude of ROI location. - public init(latitude: Double, longitude: Double, altitude: Double) { + /// - frame: the reference frame of the coordinates. + public init(latitude: Double, longitude: Double, altitude: Double, frame: Frame = .relative) { super.init(type: .setRoiLocation, + frame: frame, latitude: latitude, longitude: longitude, altitude: altitude) @@ -66,8 +68,10 @@ extension MavlinkStandard { /// Constructor from generic MAVLink parameters. /// - /// - Parameter parameters: generic command parameters - convenience init(parameters: [Double]) throws { + /// - Parameters: + /// - frame: the reference frame of the coordinates + /// - parameters: generic command parameters + convenience init(frame: Frame = .relative, parameters: [Double]) throws { assert(parameters.count == 7) guard parameters.count == 7 else { throw MavlinkStandard.MavlinkCommand.ParseError @@ -76,7 +80,7 @@ extension MavlinkStandard { let latitude = parameters[4] let longitude = parameters[5] let altitude = parameters[6] - self.init(latitude: latitude, longitude: longitude, altitude: altitude) + self.init(latitude: latitude, longitude: longitude, altitude: altitude, frame: frame) } } } diff --git a/GroundSdk/Mavlink/standard/SetRoiNoneCommand.swift b/GroundSdk/Mavlink/standard/SetRoiNoneCommand.swift index 9f29042..11d88b0 100644 --- a/GroundSdk/Mavlink/standard/SetRoiNoneCommand.swift +++ b/GroundSdk/Mavlink/standard/SetRoiNoneCommand.swift @@ -37,8 +37,12 @@ extension MavlinkStandard { /// Issuing this command the drone will look towards the next waypoint. public final class SetRoiNoneCommand: MavlinkStandard.MavlinkCommand { - public init() { - super.init(type: .setRoiNone) + /// Constructor. + /// + /// - Parameters: + /// - frame: the reference frame of the coordinates. + public init(frame: Frame = .command) { + super.init(type: .setRoiNone, frame: frame) } } } diff --git a/GroundSdk/Mavlink/standard/SetStillCaptureModeCommand.swift b/GroundSdk/Mavlink/standard/SetStillCaptureModeCommand.swift index 5700acc..afaf89a 100644 --- a/GroundSdk/Mavlink/standard/SetStillCaptureModeCommand.swift +++ b/GroundSdk/Mavlink/standard/SetStillCaptureModeCommand.swift @@ -72,14 +72,17 @@ extension MavlinkStandard { /// /// - Parameters: /// - mode: still capture photo mode - public init(mode: PhotoMode) { - super.init(type: .setStillCaptureMode, param3: Double(mode.rawValue)) + /// - frame: the reference frame of the coordinates + public init(mode: PhotoMode, frame: Frame = .command) { + super.init(type: .setStillCaptureMode, frame: frame, param3: Double(mode.rawValue)) } /// Constructor from generic MAVLink parameters. /// - /// - Parameter parameters: generic command parameters - convenience init(parameters: [Double]) throws { + /// - Parameters: + /// - frame: the reference frame of the coordinates + /// - parameters: generic command parameters + convenience init(frame: Frame = .command, parameters: [Double]) throws { assert(parameters.count == 7) guard parameters.count == 7 else { throw MavlinkStandard.MavlinkCommand.ParseError @@ -90,7 +93,7 @@ extension MavlinkStandard { throw MavlinkStandard.MavlinkCommand.ParseError .invalidParameter("Parameter 3 (mode) was out of range.") } - self.init(mode: mode) + self.init(mode: mode, frame: frame) } } } diff --git a/GroundSdk/Mavlink/standard/SetViewModeCommand.swift b/GroundSdk/Mavlink/standard/SetViewModeCommand.swift index 25821a8..1eb6a05 100644 --- a/GroundSdk/Mavlink/standard/SetViewModeCommand.swift +++ b/GroundSdk/Mavlink/standard/SetViewModeCommand.swift @@ -55,6 +55,22 @@ extension MavlinkStandard { } } + /// Pitch view mode. + public enum PitchMode: Int, CustomStringConvertible { + /// Camera orientation is fixed between two waypoints. Orientation changes when the waypoint is reached. + case absolute + /// Camera orientation changes linearly between two waypoints. + case continuous + + /// Debug description. + public var description: String { + switch self { + case .absolute: return "absolute" + case .continuous: return "continuous" + } + } + } + /// View mode. public var mode: Mode { Mode(rawValue: Int(parameters[0]))! @@ -67,20 +83,29 @@ extension MavlinkStandard { Int(parameters[1]) } + /// Pich view mode + public var pitchMode: PitchMode { + PitchMode(rawValue: Int(parameters[2]))! + } + /// Constructor. /// /// - Parameters: /// - mode: view mode /// - roiIndex: index of the Region Of Interest if mode is `.roi` (if index is invalid, /// `.absolute` mode is used instead); value is ignored for any other mode - public init(mode: Mode, roiIndex: Int = 0) { - super.init(type: .setViewMode, param1: Double(mode.rawValue), param2: Double(roiIndex)) + /// - frame: the reference frame of the coordinates. + public init(mode: Mode, roiIndex: Int = 0, pitchMode: PitchMode = .absolute, frame: Frame = .command) { + super.init(type: .setViewMode, frame: frame, param1: Double(mode.rawValue), + param2: Double(roiIndex), param3: Double(pitchMode.rawValue)) } /// Constructor from generic MAVLink parameters. /// - /// - Parameter parameters: generic command parameters - convenience init(parameters: [Double]) throws { + /// - Parameters: + /// - frame: the reference frame of the coordinates + /// - parameters: generic command parameters + convenience init(frame: Frame = .command, parameters: [Double]) throws { assert(parameters.count == 7) guard parameters.count == 7 else { throw MavlinkStandard.MavlinkCommand.ParseError @@ -91,8 +116,13 @@ extension MavlinkStandard { throw MavlinkStandard.MavlinkCommand.ParseError .invalidParameter("Parameter 1 (mode) was out of range.") } + let rawPitchMode = parameters[2] + guard let pitchMode = PitchMode(rawValue: Int(rawPitchMode.isNaN ? 0 : rawPitchMode)) else { + throw MavlinkStandard.MavlinkCommand.ParseError + .invalidParameter("Parameter 3 (pitch mode) was out of range.") + } let roiIndex = parameters[1] - self.init(mode: mode, roiIndex: Int(roiIndex)) + self.init(mode: mode, roiIndex: Int(roiIndex), pitchMode: pitchMode, frame: frame) } } } diff --git a/GroundSdk/Mavlink/standard/StartPhotoCaptureCommand.swift b/GroundSdk/Mavlink/standard/StartPhotoCaptureCommand.swift index 176115f..77bea4b 100644 --- a/GroundSdk/Mavlink/standard/StartPhotoCaptureCommand.swift +++ b/GroundSdk/Mavlink/standard/StartPhotoCaptureCommand.swift @@ -62,21 +62,24 @@ extension MavlinkStandard { /// only valid for single-capture (count == 1), otherwise set to 0. /// Increment the capture ID for each capture command to prevent double /// captures when a command is re-transmitted. + /// - frame: the reference frame of the coordinates. /// - note: Implicitly starts a timelapse if an interval is specified with a count greater than 0. - public init(interval: Double, count: Int, sequenceNumber: Int) { + public init(interval: Double, count: Int, sequenceNumber: Int, frame: Frame = .command) { if count == 1 { assert(sequenceNumber >= 1) } else { assert(sequenceNumber == 0) } - super.init(type: .startPhotoCapture, param2: interval, param3: Double(count), + super.init(type: .startPhotoCapture, frame: frame, param2: interval, param3: Double(count), param4: Double(sequenceNumber)) } /// Constructor from generic MAVLink parameters. /// - /// - Parameter parameters: generic command parameters - convenience init(parameters: [Double]) throws { + /// - Parameters: + /// - frame: the reference frame of the coordinates + /// - parameters: generic command parameters + convenience init(frame: Frame = .command, parameters: [Double]) throws { assert(parameters.count == 7) guard parameters.count == 7 else { throw MavlinkStandard.MavlinkCommand.ParseError @@ -85,7 +88,8 @@ extension MavlinkStandard { let interval = parameters[1] let count = parameters[2] let sequenceNumber = parameters[3] - self.init(interval: interval, count: Int(count), sequenceNumber: Int(sequenceNumber)) + self.init(interval: interval, count: Int(count), sequenceNumber: Int(sequenceNumber), + frame: frame) } } } diff --git a/GroundSdk/Mavlink/standard/StartVideoCaptureCommand.swift b/GroundSdk/Mavlink/standard/StartVideoCaptureCommand.swift index ef47445..f157f08 100644 --- a/GroundSdk/Mavlink/standard/StartVideoCaptureCommand.swift +++ b/GroundSdk/Mavlink/standard/StartVideoCaptureCommand.swift @@ -35,8 +35,11 @@ extension MavlinkStandard { public final class StartVideoCaptureCommand: MavlinkStandard.MavlinkCommand { /// Constructor. - public init() { - super.init(type: .startVideoCapture) + /// + /// - Parameters: + /// - frame: the reference frame of the coordinates. + public init(frame: Frame = .command) { + super.init(type: .startVideoCapture, frame: frame) } } } diff --git a/GroundSdk/Mavlink/standard/StopPhotoCaptureCommand.swift b/GroundSdk/Mavlink/standard/StopPhotoCaptureCommand.swift index f455353..e98b539 100644 --- a/GroundSdk/Mavlink/standard/StopPhotoCaptureCommand.swift +++ b/GroundSdk/Mavlink/standard/StopPhotoCaptureCommand.swift @@ -35,8 +35,11 @@ extension MavlinkStandard { public final class StopPhotoCaptureCommand: MavlinkStandard.MavlinkCommand { /// Constructor. - public init() { - super.init(type: .stopPhotoCapture) + /// + /// - Parameters: + /// - frame: the reference frame of the coordinates. + public init(frame: Frame = .command) { + super.init(type: .stopPhotoCapture, frame: frame) } } } diff --git a/GroundSdk/Mavlink/standard/StopVideoCaptureCommand.swift b/GroundSdk/Mavlink/standard/StopVideoCaptureCommand.swift index 7004ffd..f462e6d 100644 --- a/GroundSdk/Mavlink/standard/StopVideoCaptureCommand.swift +++ b/GroundSdk/Mavlink/standard/StopVideoCaptureCommand.swift @@ -35,8 +35,11 @@ extension MavlinkStandard { public final class StopVideoCaptureCommand: MavlinkStandard.MavlinkCommand { /// Constructor. - public init() { - super.init(type: .stopVideoCapture) + /// + /// - Parameters: + /// - frame: the reference frame of the coordinates. + public init(frame: Frame = .command) { + super.init(type: .stopVideoCapture, frame: frame) } } } diff --git a/GroundSdk/Mavlink/standard/TakeOffCommand.swift b/GroundSdk/Mavlink/standard/TakeOffCommand.swift index 77869a6..0558a30 100644 --- a/GroundSdk/Mavlink/standard/TakeOffCommand.swift +++ b/GroundSdk/Mavlink/standard/TakeOffCommand.swift @@ -68,11 +68,14 @@ extension MavlinkStandard { /// - latitude: latitude of the implicitly added waypoint, in degrees. /// - longitude: longitude of the implicitly added waypoint, in degrees. /// - altitude: altitude of the implicitly added waypoint above take off point, in meters. + /// - frame: the reference frame of the coordinates. public init(yaw: Double = .nan, latitude: Double = 0.0, longitude: Double = 0.0, - altitude: Double = 0.0) { + altitude: Double = 0.0, + frame: Frame = .relative) { super.init(type: .takeOff, + frame: frame, param4: yaw, latitude: latitude, longitude: longitude, @@ -82,8 +85,9 @@ extension MavlinkStandard { /// Constructor from generic MAVLink parameters. /// /// - Parameters: - /// - parameters: generic command parameters. - convenience init(parameters: [Double]) throws { + /// - frame: the reference frame of the coordinates + /// - parameters: generic command parameters + convenience init(frame: Frame = .relative, parameters: [Double]) throws { assert(parameters.count == 7) guard parameters.count == 7 else { throw MavlinkStandard.MavlinkCommand.ParseError @@ -96,7 +100,8 @@ extension MavlinkStandard { self.init(yaw: yaw, latitude: latitude, longitude: longitude, - altitude: altitude) + altitude: altitude, + frame: frame) } } } diff --git a/GroundSdk/Stream/Overlayer.swift b/GroundSdk/Stream/Overlayer.swift index e5a0912..7f649e0 100644 --- a/GroundSdk/Stream/Overlayer.swift +++ b/GroundSdk/Stream/Overlayer.swift @@ -64,7 +64,7 @@ public protocol OverlayContext { /// Media info handle; pointer to const struct pdraw_media_info. var mediaInfoHandle: UnsafeRawPointer {get} - /// Frame metadata handle; pointer to const struct pdraw_media_info. + /// Frame metadata handle; pointer to const struct struct vmeta_frame. var frameMetadataHandle: UnsafeRawPointer? {get} /// Histogram. diff --git a/GroundSdk/Stream/StreamView.swift b/GroundSdk/Stream/StreamView.swift index 8121a32..486d862 100644 --- a/GroundSdk/Stream/StreamView.swift +++ b/GroundSdk/Stream/StreamView.swift @@ -215,7 +215,7 @@ open class StreamView: GLKView { /// Initializes OpenGL context. private func contextInit() { - context = EAGLContext.init(api: EAGLRenderingAPI.openGLES3)! + context = EAGLContext(api: EAGLRenderingAPI.openGLES3)! enableSetNeedsDisplay = true }