Camera
public class Camera
Can be used to manage cameras that implement the MAVLink Camera Protocol: https://mavlink.io/en/protocol/camera.html.
Currently only a single camera is supported.
When multiple cameras are supported the plugin will need to be
instantiated separately for every camera and the camera selected using
select_camera
.
-
Initializes a new
Camera
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 RuntimeCameraError : Error
-
Undocumented
See moreDeclaration
Swift
public struct CameraError : Error
-
Camera mode type.
See moreDeclaration
Swift
public enum Mode : Equatable
-
Result type.
See moreDeclaration
Swift
public struct CameraResult : 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
-
Information about a picture just captured.
See moreDeclaration
Swift
public struct CaptureInfo : Equatable
-
Type for video stream settings.
See moreDeclaration
Swift
public struct VideoStreamSettings : Equatable
-
Information about the video stream.
See moreDeclaration
Swift
public struct VideoStreamInfo : Equatable
-
Information about the camera status.
See moreDeclaration
Swift
public struct Status : Equatable
-
Type to represent a setting option.
See moreDeclaration
Swift
public struct Option : Equatable
-
Type to represent a setting with a selected option.
See moreDeclaration
Swift
public struct Setting : Equatable
-
Type to represent a setting with a list of options to choose from.
See moreDeclaration
Swift
public struct SettingOptions : Equatable
-
Type to represent a camera information.
See moreDeclaration
Swift
public struct Information : Equatable
-
Take one photo.
Declaration
Swift
public func takePhoto() -> Completable
-
Start photo timelapse with a given interval.
Declaration
Swift
public func startPhotoInterval(intervalS: Float) -> Completable
Parameters
intervalS
Interval between photos (in seconds)
-
Stop a running photo timelapse.
Declaration
Swift
public func stopPhotoInterval() -> Completable
-
Start a video recording.
Declaration
Swift
public func startVideo() -> Completable
-
Stop a running video recording.
Declaration
Swift
public func stopVideo() -> Completable
-
Start video streaming.
Declaration
Swift
public func startVideoStreaming() -> Completable
-
Stop current video streaming.
Declaration
Swift
public func stopVideoStreaming() -> Completable
-
Set camera mode.
Declaration
Swift
public func setMode(mode: Mode) -> Completable
Parameters
mode
Camera mode to set
-
Subscribe to camera mode updates.
Declaration
Swift
public lazy var mode: Observable<Mode> { get set }
-
Subscribe to camera information updates.
Declaration
Swift
public lazy var information: Observable<Information> { get set }
-
Subscribe to video stream info updates.
Declaration
Swift
public lazy var videoStreamInfo: Observable<VideoStreamInfo> { get set }
-
Subscribe to capture info updates.
Declaration
Swift
public lazy var captureInfo: Observable<CaptureInfo> { get set }
-
Subscribe to camera status updates.
Declaration
Swift
public lazy var status: Observable<Status> { get set }
-
Get the list of current camera settings.
Declaration
Swift
public lazy var currentSettings: Observable<[Setting]> { get set }
-
Get the list of settings that can be changed.
Declaration
Swift
public lazy var possibleSettingOptions: Observable<[SettingOptions]> { get set }
-
Set a setting to some value.
Only setting_id of setting and option_id of option needs to be set.
Declaration
Swift
public func setSetting(setting: Setting) -> Completable
Parameters
setting
Desired setting
-
Get a setting.
Only setting_id of setting needs to be set.
Parameters
setting
Requested setting
-
Format storage (e.g. SD card) in camera.
This will delete all content of the camera storage!
Declaration
Swift
public func formatStorage() -> Completable