Telemetry
public class Telemetry
Allow users to get vehicle telemetry and state information (e.g. battery, GPS, RC connection, flight mode etc.) and set telemetry update rates.
-
Initializes a new
Telemetryplugin.Normally never created manually, but used from the
Dronehelper class instead.Declaration
Swift
public convenience init(address: String = "localhost", port: Int32 = 50051, scheduler: SchedulerType = ConcurrentDispatchQueueScheduler(qos: .background))Parameters
addressThe address of the
MavsdkServerinstance to connect toportThe port of the
MavsdkServerinstance to connect toschedulerThe scheduler to be used by
Observables -
Undocumented
See moreDeclaration
Swift
public struct RuntimeTelemetryError : Error -
Undocumented
See moreDeclaration
Swift
public struct TelemetryError : Error -
GPS fix type.
See moreDeclaration
Swift
public enum FixType : Equatable -
Flight modes.
For more information about flight modes, check out https://docs.px4.io/master/en/config/flight_mode.html.
See moreDeclaration
Swift
public enum FlightMode : Equatable -
Status types.
See moreDeclaration
Swift
public enum StatusTextType : Equatable -
Landed State enumeration.
See moreDeclaration
Swift
public enum LandedState : Equatable -
Position type in global coordinates.
See moreDeclaration
Swift
public struct Position : Equatable -
Quaternion type.
All rotations and axis systems follow the right-hand rule. The Hamilton quaternion product definition is used. A zero-rotation quaternion is represented by (1,0,0,0). The quaternion could also be written as w + xi + yj + zk.
For more info see: https://en.wikipedia.org/wiki/Quaternion
See moreDeclaration
Swift
public struct Quaternion : Equatable -
Euler angle type.
All rotations and axis systems follow the right-hand rule. The Euler angles follow the convention of a 3-2-1 intrinsic Tait-Bryan rotation sequence.
For more info see https://en.wikipedia.org/wiki/Euler_angles
See moreDeclaration
Swift
public struct EulerAngle : Equatable -
Angular velocity type.
See moreDeclaration
Swift
public struct AngularVelocityBody : Equatable -
GPS information type.
See moreDeclaration
Swift
public struct GpsInfo : Equatable -
Battery type.
See moreDeclaration
Swift
public struct Battery : Equatable -
Health type.
See moreDeclaration
Swift
public struct Health : Equatable -
Remote control status type.
See moreDeclaration
Swift
public struct RcStatus : Equatable -
StatusText information type.
See moreDeclaration
Swift
public struct StatusText : Equatable -
Actuator control target type.
See moreDeclaration
Swift
public struct ActuatorControlTarget : Equatable -
Actuator output status type.
See moreDeclaration
Swift
public struct ActuatorOutputStatus : Equatable -
Covariance type.
Row-major representation of a 6x6 cross-covariance matrix upper right triangle. Set first to NaN if unknown.
See moreDeclaration
Swift
public struct Covariance : Equatable -
Velocity type, represented in the Body (X Y Z) frame and in metres/second.
See moreDeclaration
Swift
public struct VelocityBody : Equatable -
Position type, represented in the Body (X Y Z) frame
See moreDeclaration
Swift
public struct PositionBody : Equatable -
Odometry message type.
See moreDeclaration
Swift
public struct Odometry : Equatable -
DistanceSensor message type.
See moreDeclaration
Swift
public struct DistanceSensor : Equatable -
PositionNed message type.
See moreDeclaration
Swift
public struct PositionNed : Equatable -
VelocityNed message type.
See moreDeclaration
Swift
public struct VelocityNed : Equatable -
PositionVelocityNed message type.
See moreDeclaration
Swift
public struct PositionVelocityNed : Equatable -
GroundTruth message type.
See moreDeclaration
Swift
public struct GroundTruth : Equatable -
FixedwingMetrics message type.
See moreDeclaration
Swift
public struct FixedwingMetrics : Equatable -
AccelerationFrd message type.
See moreDeclaration
Swift
public struct AccelerationFrd : Equatable -
AngularVelocityFrd message type.
See moreDeclaration
Swift
public struct AngularVelocityFrd : Equatable -
MagneticFieldFrd message type.
See moreDeclaration
Swift
public struct MagneticFieldFrd : Equatable -
Imu message type.
See moreDeclaration
Swift
public struct Imu : Equatable -
Gps global origin type.
See moreDeclaration
Swift
public struct GpsGlobalOrigin : Equatable -
Result type.
See moreDeclaration
Swift
public struct TelemetryResult : Equatable -
Subscribe to ‘position’ updates.
Declaration
Swift
public lazy var position: Observable<Position> { get set } -
Subscribe to ‘home position’ updates.
Declaration
Swift
public lazy var home: Observable<Position> { get set } -
Subscribe to in-air updates.
Declaration
Swift
public lazy var inAir: Observable<Bool> { get set } -
Subscribe to landed state updates
Declaration
Swift
public lazy var landedState: Observable<LandedState> { get set } -
Subscribe to armed updates.
Declaration
Swift
public lazy var armed: Observable<Bool> { get set } -
Subscribe to ‘attitude’ updates (quaternion).
Declaration
Swift
public lazy var attitudeQuaternion: Observable<Quaternion> { get set } -
Subscribe to ‘attitude’ updates (Euler).
Declaration
Swift
public lazy var attitudeEuler: Observable<EulerAngle> { get set } -
Subscribe to ‘attitude’ updates (angular velocity)
Declaration
Swift
public lazy var attitudeAngularVelocityBody: Observable<AngularVelocityBody> { get set } -
Subscribe to ‘camera attitude’ updates (quaternion).
Declaration
Swift
public lazy var cameraAttitudeQuaternion: Observable<Quaternion> { get set } -
Subscribe to ‘camera attitude’ updates (Euler).
Declaration
Swift
public lazy var cameraAttitudeEuler: Observable<EulerAngle> { get set } -
Subscribe to ‘ground speed’ updates (NED).
Declaration
Swift
public lazy var velocityNed: Observable<VelocityNed> { get set } -
Subscribe to ‘GPS info’ updates.
Declaration
Swift
public lazy var gpsInfo: Observable<GpsInfo> { get set } -
Subscribe to ‘battery’ updates.
Declaration
Swift
public lazy var battery: Observable<Battery> { get set } -
Subscribe to ‘flight mode’ updates.
Declaration
Swift
public lazy var flightMode: Observable<FlightMode> { get set } -
Subscribe to ‘health’ updates.
Declaration
Swift
public lazy var health: Observable<Health> { get set } -
Subscribe to ‘RC status’ updates.
Declaration
Swift
public lazy var rcStatus: Observable<RcStatus> { get set } -
Subscribe to ‘status text’ updates.
Declaration
Swift
public lazy var statusText: Observable<StatusText> { get set } -
Subscribe to ‘actuator control target’ updates.
Declaration
Swift
public lazy var actuatorControlTarget: Observable<ActuatorControlTarget> { get set } -
Subscribe to ‘actuator output status’ updates.
Declaration
Swift
public lazy var actuatorOutputStatus: Observable<ActuatorOutputStatus> { get set } -
Subscribe to ‘odometry’ updates.
Declaration
Swift
public lazy var odometry: Observable<Odometry> { get set } -
Subscribe to ‘position velocity’ updates.
Declaration
Swift
public lazy var positionVelocityNed: Observable<PositionVelocityNed> { get set } -
Subscribe to ‘ground truth’ updates.
Declaration
Swift
public lazy var groundTruth: Observable<GroundTruth> { get set } -
Subscribe to ‘fixedwing metrics’ updates.
Declaration
Swift
public lazy var fixedwingMetrics: Observable<FixedwingMetrics> { get set } -
Subscribe to ‘IMU’ updates.
Declaration
Swift
public lazy var imu: Observable<Imu> { get set } -
Subscribe to ‘HealthAllOk’ updates.
Declaration
Swift
public lazy var healthAllOk: Observable<Bool> { get set } -
Subscribe to ‘unix epoch time’ updates.
Declaration
Swift
public lazy var unixEpochTime: Observable<UInt64> { get set } -
Subscribe to ‘Distance Sensor’ updates.
Declaration
Swift
public lazy var distanceSensor: Observable<DistanceSensor> { get set } -
Set rate to ‘position’ updates.
Declaration
Swift
public func setRatePosition(rateHz: Double) -> CompletableParameters
rateHzThe requested rate (in Hertz)
-
Set rate to ‘home position’ updates.
Declaration
Swift
public func setRateHome(rateHz: Double) -> CompletableParameters
rateHzThe requested rate (in Hertz)
-
Set rate to in-air updates.
Declaration
Swift
public func setRateInAir(rateHz: Double) -> CompletableParameters
rateHzThe requested rate (in Hertz)
-
Set rate to landed state updates
Declaration
Swift
public func setRateLandedState(rateHz: Double) -> CompletableParameters
rateHzThe requested rate (in Hertz)
-
Set rate to ‘attitude’ updates.
Declaration
Swift
public func setRateAttitude(rateHz: Double) -> CompletableParameters
rateHzThe requested rate (in Hertz)
-
Set rate of camera attitude updates.
Declaration
Swift
public func setRateCameraAttitude(rateHz: Double) -> CompletableParameters
rateHzThe requested rate (in Hertz)
-
Set rate to ‘ground speed’ updates (NED).
Declaration
Swift
public func setRateVelocityNed(rateHz: Double) -> CompletableParameters
rateHzThe requested rate (in Hertz)
-
Set rate to ‘GPS info’ updates.
Declaration
Swift
public func setRateGpsInfo(rateHz: Double) -> CompletableParameters
rateHzThe requested rate (in Hertz)
-
Set rate to ‘battery’ updates.
Declaration
Swift
public func setRateBattery(rateHz: Double) -> CompletableParameters
rateHzThe requested rate (in Hertz)
-
Set rate to ‘RC status’ updates.
Declaration
Swift
public func setRateRcStatus(rateHz: Double) -> CompletableParameters
rateHzThe requested rate (in Hertz)
-
Set rate to ‘actuator control target’ updates.
Declaration
Swift
public func setRateActuatorControlTarget(rateHz: Double) -> CompletableParameters
rateHzThe requested rate (in Hertz)
-
Set rate to ‘actuator output status’ updates.
Declaration
Swift
public func setRateActuatorOutputStatus(rateHz: Double) -> CompletableParameters
rateHzThe requested rate (in Hertz)
-
Set rate to ‘odometry’ updates.
Declaration
Swift
public func setRateOdometry(rateHz: Double) -> CompletableParameters
rateHzThe requested rate (in Hertz)
-
Set rate to ‘position velocity’ updates.
Declaration
Swift
public func setRatePositionVelocityNed(rateHz: Double) -> CompletableParameters
rateHzThe requested rate (in Hertz)
-
Set rate to ‘ground truth’ updates.
Declaration
Swift
public func setRateGroundTruth(rateHz: Double) -> CompletableParameters
rateHzThe requested rate (in Hertz)
-
Set rate to ‘fixedwing metrics’ updates.
Declaration
Swift
public func setRateFixedwingMetrics(rateHz: Double) -> CompletableParameters
rateHzThe requested rate (in Hertz)
-
Set rate to ‘IMU’ updates.
Declaration
Swift
public func setRateImu(rateHz: Double) -> CompletableParameters
rateHzThe requested rate (in Hertz)
-
Set rate to ‘unix epoch time’ updates.
Declaration
Swift
public func setRateUnixEpochTime(rateHz: Double) -> CompletableParameters
rateHzThe requested rate (in Hertz)
-
Set rate to ‘Distance Sensor’ updates.
Declaration
Swift
public func setRateDistanceSensor(rateHz: Double) -> CompletableParameters
rateHzThe requested rate (in Hertz)
-
Get the GPS location of where the estimator has been initialized.
Declaration
Swift
public func getGpsGlobalOrigin() -> Single<GpsGlobalOrigin>
View on GitHub
Install in Dash
Telemetry Class Reference