ManualControl

public class ManualControl

Enable manual control using e.g. a joystick or gamepad.

  • Initializes a new ManualControl 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 to

    port

    The port of the MavsdkServer instance to connect to

    scheduler

    The scheduler to be used by Observables

  • Undocumented

    See more

    Declaration

    Swift

    public struct RuntimeManualControlError : Error
  • Undocumented

    See more

    Declaration

    Swift

    public struct ManualControlError : Error
  • Result type.

    See more

    Declaration

    Swift

    public struct ManualControlResult : Equatable
  • Start position control using e.g. joystick input.

    Requires manual control input to be sent regularly already. Requires a valid position using e.g. GPS, external vision, or optical flow.

    Declaration

    Swift

    public func startPositionControl() -> Completable
  • Start altitude control

    Requires manual control input to be sent regularly already. Does not require a valid position e.g. GPS.

    Declaration

    Swift

    public func startAltitudeControl() -> Completable
  • Set manual control input

    The manual control input needs to be sent at a rate high enough to prevent triggering of RC loss, a good minimum rate is 10 Hz.

    Declaration

    Swift

    public func setManualControlInput(x: Float, y: Float, z: Float, r: Float) -> Completable

    Parameters

    x

    value between -1. to 1. negative -> backwards, positive -> forwards

    y

    value between -1. to 1. negative -> left, positive -> right

    z

    value between -1. to 1. negative -> down, positive -> up (usually for now, for multicopter 0 to 1 is expected)

    r

    value between -1. to 1. negative -> turn anti-clockwise (towards the left), positive -> turn clockwise (towards the right)