Offboard

public class Offboard

* Control a drone with position, velocity, attitude or motor commands.

The module is called offboard because the commands can be sent from external sources as opposed to onboard control right inside the autopilot “board”.

Client code must specify a setpoint before starting offboard mode. Mavsdk automatically sends setpoints at 20Hz (PX4 Offboard mode requires that setpoints are minimally sent at 2Hz).

  • Initializes a new Offboard 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 RuntimeOffboardError : Error
  • Undocumented

    See more

    Declaration

    Swift

    public struct OffboardError : Error
  • Type for attitude body angles in NED reference frame (roll, pitch, yaw and thrust)

    See more

    Declaration

    Swift

    public struct Attitude : Equatable
  • Eight controls that will be given to the group. Each control is a normalized (-1..+1) command value, which will be mapped and scaled through the mixer.

    See more

    Declaration

    Swift

    public struct ActuatorControlGroup : Equatable
  • Type for actuator control.

    Control members should be normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction.

    One group support eight controls.

    Up to 16 actuator controls can be set. To ignore an output group, set all it conrols to NaN. If one or more controls in group is not NaN, then all NaN controls will sent as zero. The first 8 actuator controls internally map to control group 0, the latter 8 actuator controls map to control group 1. Depending on what controls are set (instead of NaN) 1 or 2 MAVLink messages are actually sent.

    In PX4 v1.9.0 Only first four Control Groups are supported (https://github.com/PX4/Firmware/blob/v1.9.0/src/modules/mavlink/mavlink_receiver.cpp#L980).

    See more

    Declaration

    Swift

    public struct ActuatorControl : Equatable
  • Type for attitude rate commands in body coordinates (roll, pitch, yaw angular rate and thrust)

    See more

    Declaration

    Swift

    public struct AttitudeRate : Equatable
  • Type for position commands in NED (North East Down) coordinates and yaw.

    See more

    Declaration

    Swift

    public struct PositionNedYaw : Equatable
  • Type for velocity commands in body coordinates.

    See more

    Declaration

    Swift

    public struct VelocityBodyYawspeed : Equatable
  • Type for velocity commands in NED (North East Down) coordinates and yaw.

    See more

    Declaration

    Swift

    public struct VelocityNedYaw : Equatable
  • Result type.

    See more

    Declaration

    Swift

    public struct OffboardResult : Equatable
  • Start offboard control.

    Declaration

    Swift

    public func start() -> Completable
  • Stop offboard control.

    The vehicle will be put into Hold mode: https://docs.px4.io/en/flight_modes/hold.html

    Declaration

    Swift

    public func stop() -> Completable
  • Check if offboard control is active.

    True means that the vehicle is in offboard mode and we are actively sending setpoints.

    Declaration

    Swift

    public func isActive() -> Single<Bool>
  • Set the attitude in terms of roll, pitch and yaw in degrees with thrust.

    Declaration

    Swift

    public func setAttitude(attitude: Attitude) -> Completable

    Parameters

    attitude

    Attitude roll, pitch and yaw along with thrust

  • Set direct actuator control values to groups #0 and #1.

    First 8 controls will go to control group 0, the following 8 controls to control group 1 (if actuator_control.num_controls more than 8).

    Declaration

    Swift

    public func setActuatorControl(actuatorControl: ActuatorControl) -> Completable

    Parameters

    actuatorControl

    Actuator control values

  • Set the attitude rate in terms of pitch, roll and yaw angular rate along with thrust.

    Declaration

    Swift

    public func setAttitudeRate(attitudeRate: AttitudeRate) -> Completable

    Parameters

    attitudeRate

    Attitude rate roll, pitch and yaw angular rate along with thrust

  • Set the position in NED coordinates and yaw.

    Declaration

    Swift

    public func setPositionNed(positionNedYaw: PositionNedYaw) -> Completable

    Parameters

    positionNedYaw

    Position and yaw

  • Set the velocity in body coordinates and yaw angular rate. Not available for fixed-wing aircraft.

    Declaration

    Swift

    public func setVelocityBody(velocityBodyYawspeed: VelocityBodyYawspeed) -> Completable

    Parameters

    velocityBodyYawspeed

    Velocity and yaw angular rate

  • Set the velocity in NED coordinates and yaw. Not available for fixed-wing aircraft.

    Declaration

    Swift

    public func setVelocityNed(velocityNedYaw: VelocityNedYaw) -> Completable

    Parameters

    velocityNedYaw

    Velocity and yaw

  • Set the position in NED coordinates, with the velocity to be used as feed-forward.

    Declaration

    Swift

    public func setPositionVelocityNed(positionNedYaw: PositionNedYaw, velocityNedYaw: VelocityNedYaw) -> Completable

    Parameters

    positionNedYaw

    Position and yaw

    velocityNedYaw

    Velocity and yaw