Camera

class mavsdk.camera.Camera(async_plugin_manager)

Bases: AsyncBase

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.

Generated by dcsdkgen - MAVSDK Camera API

async capture_info()

Subscribe to capture info updates.

Yields:

capture_info (CaptureInfo) – Capture info

async current_settings()

Get the list of current camera settings.

Yields:

current_settings ([Setting]) – List of current settings

async focus_in_start()

Start focusing in.

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async focus_out_start()

Start focusing out.

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async focus_range(range)

Focus with range value of full range (value between 0.0 and 100.0).

Parameters:

range (float) – Range must be between 0.0 - 100.0

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async focus_stop()

Stop focus.

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async format_storage(storage_id)

Format storage (e.g. SD card) in camera.

This will delete all content of the camera storage!

Parameters:

storage_id (int32_t) – Storage identify to be format

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async get_setting(setting)

Get a setting.

Only setting_id of setting needs to be set.

Parameters:

setting (Setting) – Requested setting

Returns:

setting – Setting

Return type:

Setting

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async information()

Subscribe to camera information updates.

Yields:

information (Information) – Camera information

async list_photos(photos_range)

List photos available on the camera.

Parameters:

photos_range (PhotosRange) – Which photos should be listed (all or since connection)

Returns:

capture_infos – List of capture infos (representing the photos)

Return type:

[CaptureInfo]

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async mode()

Subscribe to camera mode updates.

Yields:

mode (Mode) – Camera mode

name = 'Camera'
async possible_setting_options()

Get the list of settings that can be changed.

Yields:

setting_options ([SettingOptions]) – List of settings that can be changed

async prepare()

Prepare the camera plugin (e.g. download the camera definition, etc).

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async reset_settings()

Reset all settings in camera.

This will reset all camera settings to default value

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async select_camera(camera_id)

Select current camera .

Bind the plugin instance to a specific camera_id

Parameters:

camera_id (int32_t) – Id of camera to be selected

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async set_mode(mode)

Set camera mode.

Parameters:

mode (Mode) – Camera mode to set

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async set_setting(setting)

Set a setting to some value.

Only setting_id of setting and option_id of option needs to be set.

Parameters:

setting (Setting) – Desired setting

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async start_photo_interval(interval_s)

Start photo timelapse with a given interval.

Parameters:

interval_s (float) – Interval between photos (in seconds)

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async start_video()

Start a video recording.

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async start_video_streaming(stream_id)

Start video streaming.

Parameters:

stream_id (int32_t) – video stream id

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async status()

Subscribe to camera status updates.

Yields:

camera_status (Status) – Camera status

async stop_photo_interval()

Stop a running photo timelapse.

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async stop_video()

Stop a running video recording.

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async stop_video_streaming(stream_id)

Stop current video streaming.

Parameters:

stream_id (int32_t) – video stream id

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async take_photo()

Take one photo.

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async track_point(point_x, point_y, radius)

Track point.

Parameters:
  • point_x (float) – Point in X axis (0..1, 0 is left, 1 is right)

  • point_y (float) – Point in Y axis (0..1, 0 is top, 1 is bottom)

  • radius (float) – Radius (0 is one pixel, 1 is full image width)

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async track_rectangle(top_left_x, top_left_y, bottom_right_x, bottom_right_y)

Track rectangle.

Parameters:
  • top_left_x (float) – Top left corner of rectangle x value (normalized 0..1, 0 is left, 1 is right)

  • top_left_y (float) – Top left corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom)

  • bottom_right_x (float) – Bottom right corner of rectangle x value (normalized 0..1, 0 is left, 1 is right)

  • bottom_right_y (float) – Bottom right corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom)

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async track_stop()

Stop tracking.

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async video_stream_info()

Subscribe to video stream info updates.

Yields:

video_stream_info (VideoStreamInfo) – Video stream info

async zoom_in_start()

Start zooming in.

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async zoom_out_start()

Start zooming out.

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async zoom_range(range)

Zoom to value as proportion of full camera range (percentage between 0.0 and 100.0).

Parameters:

range (float) – Range must be between 0.0 and 100.0

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

async zoom_stop()

Stop zooming.

Raises:

CameraError – If the request fails. The error contains the reason for the failure.

exception mavsdk.camera.CameraError(result, origin, *params)

Bases: Exception

Raised when a CameraResult is a fail code

class mavsdk.camera.CameraResult(result, result_str)

Bases: object

Result type.

Parameters:
  • result (Result) – Result enum value

  • result_str (std::string) – Human-readable English string describing the result

class Result(value)

Bases: Enum

Possible results returned for camera commands

Values

UNKNOWN

Unknown result

SUCCESS

Command executed successfully

IN_PROGRESS

Command in progress

BUSY

Camera is busy and rejected command

DENIED

Camera denied the command

ERROR

An error has occurred while executing the command

TIMEOUT

Command timed out

WRONG_ARGUMENT

Command has wrong argument(s)

NO_SYSTEM

No system connected

PROTOCOL_UNSUPPORTED

Definition file protocol not supported

BUSY = 3
DENIED = 4
ERROR = 5
IN_PROGRESS = 2
NO_SYSTEM = 8
PROTOCOL_UNSUPPORTED = 9
SUCCESS = 1
TIMEOUT = 6
UNKNOWN = 0
WRONG_ARGUMENT = 7
class mavsdk.camera.CaptureInfo(position, attitude_quaternion, attitude_euler_angle, time_utc_us, is_success, index, file_url)

Bases: object

Information about a picture just captured.

Parameters:
  • position (Position) – Location where the picture was taken

  • attitude_quaternion (Quaternion) – Attitude of the camera when the picture was taken (quaternion)

  • attitude_euler_angle (EulerAngle) – Attitude of the camera when the picture was taken (euler angle)

  • time_utc_us (uint64_t) – Timestamp in UTC (since UNIX epoch) in microseconds

  • is_success (bool) – True if the capture was successful

  • index (int32_t) – Zero-based index of this image since vehicle was armed

  • file_url (std::string) – Download URL of this image

class mavsdk.camera.EulerAngle(roll_deg, pitch_deg, yaw_deg)

Bases: object

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

Parameters:
  • roll_deg (float) – Roll angle in degrees, positive is banking to the right

  • pitch_deg (float) – Pitch angle in degrees, positive is pitching nose up

  • yaw_deg (float) – Yaw angle in degrees, positive is clock-wise seen from above

class mavsdk.camera.Information(vendor_name, model_name, focal_length_mm, horizontal_sensor_size_mm, vertical_sensor_size_mm, horizontal_resolution_px, vertical_resolution_px)

Bases: object

Type to represent a camera information.

Parameters:
  • vendor_name (std::string) – Name of the camera vendor

  • model_name (std::string) – Name of the camera model

  • focal_length_mm (float) – Focal length

  • horizontal_sensor_size_mm (float) – Horizontal sensor size

  • vertical_sensor_size_mm (float) – Vertical sensor size

  • horizontal_resolution_px (uint32_t) – Horizontal image resolution in pixels

  • vertical_resolution_px (uint32_t) – Vertical image resolution in pixels

class mavsdk.camera.Mode(value)

Bases: Enum

Camera mode type.

Values

UNKNOWN

Unknown

PHOTO

Photo mode

VIDEO

Video mode

PHOTO = 1
UNKNOWN = 0
VIDEO = 2
class mavsdk.camera.Option(option_id, option_description)

Bases: object

Type to represent a setting option.

Parameters:
  • option_id (std::string) – Name of the option (machine readable)

  • option_description (std::string) – Description of the option (human readable)

class mavsdk.camera.PhotosRange(value)

Bases: Enum

Photos range type.

Values

ALL

All the photos present on the camera

SINCE_CONNECTION

Photos taken since MAVSDK got connected

ALL = 0
SINCE_CONNECTION = 1
class mavsdk.camera.Position(latitude_deg, longitude_deg, absolute_altitude_m, relative_altitude_m)

Bases: object

Position type in global coordinates.

Parameters:
  • latitude_deg (double) – Latitude in degrees (range: -90 to +90)

  • longitude_deg (double) – Longitude in degrees (range: -180 to +180)

  • absolute_altitude_m (float) – Altitude AMSL (above mean sea level) in metres

  • relative_altitude_m (float) – Altitude relative to takeoff altitude in metres

class mavsdk.camera.Quaternion(w, x, y, z)

Bases: object

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

Parameters:
  • w (float) – Quaternion entry 0, also denoted as a

  • x (float) – Quaternion entry 1, also denoted as b

  • y (float) – Quaternion entry 2, also denoted as c

  • z (float) – Quaternion entry 3, also denoted as d

class mavsdk.camera.Setting(setting_id, setting_description, option, is_range)

Bases: object

Type to represent a setting with a selected option.

Parameters:
  • setting_id (std::string) – Name of a setting (machine readable)

  • setting_description (std::string) – Description of the setting (human readable). This field is meant to be read from the drone, ignore it when setting.

  • option (Option) – Selected option

  • is_range (bool) – If option is given as a range. This field is meant to be read from the drone, ignore it when setting.

class mavsdk.camera.SettingOptions(setting_id, setting_description, options, is_range)

Bases: object

Type to represent a setting with a list of options to choose from.

Parameters:
  • setting_id (std::string) – Name of the setting (machine readable)

  • setting_description (std::string) – Description of the setting (human readable)

  • options ([Option]) – List of options or if range [min, max] or [min, max, interval]

  • is_range (bool) – If option is given as a range

class mavsdk.camera.Status(video_on, photo_interval_on, used_storage_mib, available_storage_mib, total_storage_mib, recording_time_s, media_folder_name, storage_status, storage_id, storage_type)

Bases: object

Information about the camera status.

Parameters:
  • video_on (bool) – Whether video recording is currently in process

  • photo_interval_on (bool) – Whether a photo interval is currently in process

  • used_storage_mib (float) – Used storage (in MiB)

  • available_storage_mib (float) – Available storage (in MiB)

  • total_storage_mib (float) – Total storage (in MiB)

  • recording_time_s (float) – Elapsed time since starting the video recording (in seconds)

  • media_folder_name (std::string) – Current folder name where media are saved

  • storage_status (StorageStatus) – Storage status

  • storage_id (uint32_t) – Storage ID starting at 1

  • storage_type (StorageType) – Storage type

class StorageStatus(value)

Bases: Enum

Storage status type.

Values

NOT_AVAILABLE

Status not available

UNFORMATTED

Storage is not formatted (i.e. has no recognized file system)

FORMATTED

Storage is formatted (i.e. has recognized a file system)

NOT_SUPPORTED

Storage status is not supported

FORMATTED = 2
NOT_AVAILABLE = 0
NOT_SUPPORTED = 3
UNFORMATTED = 1
class StorageType(value)

Bases: Enum

Storage type.

Values

UNKNOWN

Storage type unknown

USB_STICK

Storage type USB stick

SD

Storage type SD card

MICROSD

Storage type MicroSD card

HD

Storage type HD mass storage

OTHER

Storage type other, not listed

HD = 4
MICROSD = 3
OTHER = 5
SD = 2
UNKNOWN = 0
USB_STICK = 1
class mavsdk.camera.VideoStreamInfo(settings, status, spectrum)

Bases: object

Information about the video stream.

Parameters:
class VideoStreamSpectrum(value)

Bases: Enum

Video stream light spectrum type

Values

UNKNOWN

Unknown

VISIBLE_LIGHT

Visible light

INFRARED

Infrared

INFRARED = 2
UNKNOWN = 0
VISIBLE_LIGHT = 1
class VideoStreamStatus(value)

Bases: Enum

Video stream status type.

Values

NOT_RUNNING

Video stream is not running

IN_PROGRESS

Video stream is running

IN_PROGRESS = 1
NOT_RUNNING = 0
class mavsdk.camera.VideoStreamSettings(frame_rate_hz, horizontal_resolution_pix, vertical_resolution_pix, bit_rate_b_s, rotation_deg, uri, horizontal_fov_deg)

Bases: object

Type for video stream settings.

Parameters:
  • frame_rate_hz (float) – Frames per second

  • horizontal_resolution_pix (uint32_t) – Horizontal resolution (in pixels)

  • vertical_resolution_pix (uint32_t) – Vertical resolution (in pixels)

  • bit_rate_b_s (uint32_t) – Bit rate (in bits per second)

  • rotation_deg (uint32_t) – Video image rotation (clockwise, 0-359 degrees)

  • uri (std::string) – Video stream URI

  • horizontal_fov_deg (float) – Horizontal fov in degrees