TelemetryServer
public class TelemetryServer
Allow users to provide vehicle telemetry and state information (e.g. battery, GPS, RC connection, flight mode etc.) and set telemetry update rates.
-
Initializes a new
TelemetryServer
plugin.Normally never created manually, but used from the
Drone
helper class instead.Declaration
Swift
public convenience init(address: String = "localhost", port: Int32 = 50051, scheduler: SchedulerType = ConcurrentDispatchQueueScheduler(qos: .background))
Parameters
address
The address of the
MavsdkServer
instance to connect toport
The port of the
MavsdkServer
instance to connect toscheduler
The scheduler to be used by
Observable
s -
Undocumented
See moreDeclaration
Swift
public struct RuntimeTelemetryServerError : Error
-
Undocumented
See moreDeclaration
Swift
public struct TelemetryServerError : Error
-
GPS fix type.
See moreDeclaration
Swift
public enum FixType : Equatable
-
Maps to MAV_VTOL_STATE
See moreDeclaration
Swift
public enum VtolState : 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
-
Heading type used for global position
See moreDeclaration
Swift
public struct Heading : 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
-
Raw GPS information type.
Warning: this is an advanced type! If you want the location of the drone, use the position instead. This message exposes the raw values of the GNSS sensor.
See moreDeclaration
Swift
public struct RawGps : Equatable
-
Battery type.
See moreDeclaration
Swift
public struct Battery : 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
-
Scaled Pressure message type.
See moreDeclaration
Swift
public struct ScaledPressure : 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
-
Result type.
See moreDeclaration
Swift
public struct TelemetryServerResult : Equatable
-
Publish to ‘position’ updates.
Declaration
Swift
public func publishPosition(position: Position, velocityNed: VelocityNed, heading: Heading) -> Completable
Parameters
position
The next position
velocityNed
The next velocity (NED)
heading
Heading (yaw) in degrees
-
Publish to ‘home position’ updates.
Declaration
Swift
public func publishHome(home: Position) -> Completable
Parameters
home
The next home position
-
Publish ‘sys status’ updates.
Declaration
Swift
public func publishSysStatus(battery: Battery, rcReceiverStatus: Bool, gyroStatus: Bool, accelStatus: Bool, magStatus: Bool, gpsStatus: Bool) -> Completable
Parameters
battery
The next ‘battery’ state
rcReceiverStatus
rc receiver status
gyroStatus
accelStatus
magStatus
gpsStatus
-
Publish ‘extended sys state’ updates.
Declaration
Swift
public func publishExtendedSysState(vtolState: VtolState, landedState: LandedState) -> Completable
Parameters
vtolState
landedState
-
Publish to ‘Raw GPS’ updates.
Parameters
rawGps
The next ‘Raw GPS’ state. Warning: this is an advanced feature, use
Position
updates to get the location of the drone!gpsInfo
The next ‘GPS info’ state
-
Publish to ‘battery’ updates.
Declaration
Swift
public func publishBattery(battery: Battery) -> Completable
Parameters
battery
The next ‘battery’ state
-
Publish to ‘status text’ updates.
Declaration
Swift
public func publishStatusText(statusText: StatusText) -> Completable
Parameters
statusText
The next ‘status text’
-
Publish to ‘odometry’ updates.
Declaration
Swift
public func publishOdometry(odometry: Odometry) -> Completable
Parameters
odometry
The next odometry status
-
Publish to ‘position velocity’ updates.
Declaration
Swift
public func publishPositionVelocityNed(positionVelocityNed: PositionVelocityNed) -> Completable
Parameters
positionVelocityNed
The next position and velocity status
-
Publish to ‘ground truth’ updates.
Declaration
Swift
public func publishGroundTruth(groundTruth: GroundTruth) -> Completable
Parameters
groundTruth
Ground truth position information available in simulation
-
Publish to ‘IMU’ updates (in SI units in NED body frame).
Declaration
Swift
public func publishImu(imu: Imu) -> Completable
Parameters
imu
The next IMU status
-
Publish to ‘Scaled IMU’ updates.
Declaration
Swift
public func publishScaledImu(imu: Imu) -> Completable
Parameters
imu
The next scaled IMU status
-
Publish to ‘Raw IMU’ updates.
Declaration
Swift
public func publishRawImu(imu: Imu) -> Completable
Parameters
imu
The next raw IMU status
-
Publish to ‘unix epoch time’ updates.
Declaration
Swift
public func publishUnixEpochTime(timeUs: UInt64) -> Completable
Parameters
timeUs
The next ‘unix epoch time’ status