mavsdk::Camera Class Reference

#include: camera.h


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.

Data Structures

struct CaptureInfo

struct EulerAngle

struct Information

struct Option

struct Position

struct Quaternion

struct Setting

struct SettingOptions

struct Status

struct VideoStreamInfo

struct VideoStreamSettings

Public Types

Type Description
enum Mode Camera mode type.
enum PhotosRange Photos range type.
enum Result Possible results returned for camera commands.
std::function< void(Result)> ResultCallback Callback type for asynchronous Camera calls.
std::function< void(Result, std::vector< CaptureInfo >)> ListPhotosCallback Callback type for list_photos_async.
std::function< void(Mode)> ModeCallback Callback type for subscribe_mode.
Handle< Mode > ModeHandle Handle type for subscribe_mode.
std::function< void(Information)> InformationCallback Callback type for subscribe_information.
Handle< Information > InformationHandle Handle type for subscribe_information.
std::function< void(VideoStreamInfo)> VideoStreamInfoCallback Callback type for subscribe_video_stream_info.
Handle< VideoStreamInfo > VideoStreamInfoHandle Handle type for subscribe_video_stream_info.
std::function< void(CaptureInfo)> CaptureInfoCallback Callback type for subscribe_capture_info.
Handle< CaptureInfo > CaptureInfoHandle Handle type for subscribe_capture_info.
std::function< void(Status)> StatusCallback Callback type for subscribe_status.
Handle< Status > StatusHandle Handle type for subscribe_status.
std::function< void(std::vector< Setting >)> CurrentSettingsCallback Callback type for subscribe_current_settings.
Handle< std::vector< Setting > > CurrentSettingsHandle Handle type for subscribe_current_settings.
std::function< void(std::vector< SettingOptions >)> PossibleSettingOptionsCallback Callback type for subscribe_possible_setting_options.
Handle< std::vector< SettingOptions > > PossibleSettingOptionsHandle Handle type for subscribe_possible_setting_options.
std::function< void(Result, Setting)> GetSettingCallback Callback type for get_setting_async.

Public Member Functions

Type Name Description
  Camera (System & system) Constructor. Creates the plugin for a specific System.
  Camera (std::shared_ptr< System > system) Constructor. Creates the plugin for a specific System.
  ~Camera () override Destructor (internal use only).
  Camera (const Camera & other) Copy constructor.
void prepare_async (const ResultCallback callback) Prepare the camera plugin (e.g. download the camera definition, etc).
Result prepare () const Prepare the camera plugin (e.g. download the camera definition, etc).
void take_photo_async (const ResultCallback callback) Take one photo.
Result take_photo () const Take one photo.
void start_photo_interval_async (float interval_s, const ResultCallback callback) Start photo timelapse with a given interval.
Result start_photo_interval (float interval_s)const Start photo timelapse with a given interval.
void stop_photo_interval_async (const ResultCallback callback) Stop a running photo timelapse.
Result stop_photo_interval () const Stop a running photo timelapse.
void start_video_async (const ResultCallback callback) Start a video recording.
Result start_video () const Start a video recording.
void stop_video_async (const ResultCallback callback) Stop a running video recording.
Result stop_video () const Stop a running video recording.
Result start_video_streaming (int32_t stream_id)const Start video streaming.
Result stop_video_streaming (int32_t stream_id)const Stop current video streaming.
void set_mode_async (Mode mode, const ResultCallback callback) Set camera mode.
Result set_mode (Mode mode)const Set camera mode.
void list_photos_async (PhotosRange photos_range, const ListPhotosCallback callback) List photos available on the camera.
std::pair< Result, std::vector< Camera::CaptureInfo > > list_photos (PhotosRange photos_range)const List photos available on the camera.
ModeHandle subscribe_mode (const ModeCallback & callback) Subscribe to camera mode updates.
void unsubscribe_mode (ModeHandle handle) Unsubscribe from subscribe_mode.
Mode mode () const Poll for 'Mode' (blocking).
InformationHandle subscribe_information (const InformationCallback & callback) Subscribe to camera information updates.
void unsubscribe_information (InformationHandle handle) Unsubscribe from subscribe_information.
Information information () const Poll for 'Information' (blocking).
VideoStreamInfoHandle subscribe_video_stream_info (const VideoStreamInfoCallback & callback) Subscribe to video stream info updates.
void unsubscribe_video_stream_info (VideoStreamInfoHandle handle) Unsubscribe from subscribe_video_stream_info.
VideoStreamInfo video_stream_info () const Poll for 'VideoStreamInfo' (blocking).
CaptureInfoHandle subscribe_capture_info (const CaptureInfoCallback & callback) Subscribe to capture info updates.
void unsubscribe_capture_info (CaptureInfoHandle handle) Unsubscribe from subscribe_capture_info.
StatusHandle subscribe_status (const StatusCallback & callback) Subscribe to camera status updates.
void unsubscribe_status (StatusHandle handle) Unsubscribe from subscribe_status.
Status status () const Poll for 'Status' (blocking).
CurrentSettingsHandle subscribe_current_settings (const CurrentSettingsCallback & callback) Get the list of current camera settings.
void unsubscribe_current_settings (CurrentSettingsHandle handle) Unsubscribe from subscribe_current_settings.
PossibleSettingOptionsHandle subscribe_possible_setting_options (const PossibleSettingOptionsCallback & callback) Get the list of settings that can be changed.
void unsubscribe_possible_setting_options (PossibleSettingOptionsHandle handle) Unsubscribe from subscribe_possible_setting_options.
std::vector< SettingOptions > possible_setting_options () const Poll for 'std::vector' (blocking).
void set_setting_async (Setting setting, const ResultCallback callback) Set a setting to some value.
Result set_setting (Setting setting)const Set a setting to some value.
void get_setting_async (Setting setting, const GetSettingCallback callback) Get a setting.
std::pair< Result, Camera::Setting > get_setting (Setting setting)const Get a setting.
void format_storage_async (int32_t storage_id, const ResultCallback callback) Format storage (e.g. SD card) in camera.
Result format_storage (int32_t storage_id)const Format storage (e.g. SD card) in camera.
Result select_camera (int32_t camera_id)const Select current camera .
void reset_settings_async (const ResultCallback callback) Reset all settings in camera.
Result reset_settings () const Reset all settings in camera.
const Camera & operator= (const Camera &)=delete Equality operator (object is not copyable).

Constructor & Destructor Documentation

Camera()

mavsdk::Camera::Camera(System &system)

Constructor. Creates the plugin for a specific System.

The plugin is typically created as shown below:

auto camera = Camera(system);

Parameters

  • System& system - The specific system associated with this plugin.

Camera()

mavsdk::Camera::Camera(std::shared_ptr< System > system)

Constructor. Creates the plugin for a specific System.

The plugin is typically created as shown below:

auto camera = Camera(system);

Parameters

  • std::shared_ptr< System > system - The specific system associated with this plugin.

~Camera()

mavsdk::Camera::~Camera() override

Destructor (internal use only).

Camera()

mavsdk::Camera::Camera(const Camera &other)

Copy constructor.

Parameters

Member Typdef Documentation

typedef ResultCallback

using mavsdk::Camera::ResultCallback =  std::function<void(Result)>

Callback type for asynchronous Camera calls.

typedef ListPhotosCallback

using mavsdk::Camera::ListPhotosCallback =  std::function<void(Result, std::vector<CaptureInfo>)>

Callback type for list_photos_async.

typedef ModeCallback

using mavsdk::Camera::ModeCallback =  std::function<void(Mode)>

Callback type for subscribe_mode.

typedef ModeHandle

using mavsdk::Camera::ModeHandle =  Handle<Mode>

Handle type for subscribe_mode.

typedef InformationCallback

using mavsdk::Camera::InformationCallback =  std::function<void(Information)>

Callback type for subscribe_information.

typedef InformationHandle

using mavsdk::Camera::InformationHandle =  Handle<Information>

Handle type for subscribe_information.

typedef VideoStreamInfoCallback

using mavsdk::Camera::VideoStreamInfoCallback =  std::function<void(VideoStreamInfo)>

Callback type for subscribe_video_stream_info.

typedef VideoStreamInfoHandle

using mavsdk::Camera::VideoStreamInfoHandle =  Handle<VideoStreamInfo>

Handle type for subscribe_video_stream_info.

typedef CaptureInfoCallback

using mavsdk::Camera::CaptureInfoCallback =  std::function<void(CaptureInfo)>

Callback type for subscribe_capture_info.

typedef CaptureInfoHandle

using mavsdk::Camera::CaptureInfoHandle =  Handle<CaptureInfo>

Handle type for subscribe_capture_info.

typedef StatusCallback

using mavsdk::Camera::StatusCallback =  std::function<void(Status)>

Callback type for subscribe_status.

typedef StatusHandle

using mavsdk::Camera::StatusHandle =  Handle<Status>

Handle type for subscribe_status.

typedef CurrentSettingsCallback

using mavsdk::Camera::CurrentSettingsCallback =  std::function<void(std::vector<Setting>)>

Callback type for subscribe_current_settings.

typedef CurrentSettingsHandle

using mavsdk::Camera::CurrentSettingsHandle =  Handle<std::vector<Setting> >

Handle type for subscribe_current_settings.

typedef PossibleSettingOptionsCallback

using mavsdk::Camera::PossibleSettingOptionsCallback =  std::function<void(std::vector<SettingOptions>)>

Callback type for subscribe_possible_setting_options.

typedef PossibleSettingOptionsHandle

using mavsdk::Camera::PossibleSettingOptionsHandle =  Handle<std::vector<SettingOptions> >

Handle type for subscribe_possible_setting_options.

typedef GetSettingCallback

using mavsdk::Camera::GetSettingCallback =  std::function<void(Result, Setting)>

Callback type for get_setting_async.

Member Enumeration Documentation

enum Mode

Camera mode type.

Value Description
Unknown Unknown.
Photo Photo mode.
Video Video mode.

enum PhotosRange

Photos range type.

Value Description
All All the photos present on the camera.
SinceConnection Photos taken since MAVSDK got connected.

enum Result

Possible results returned for camera commands.

Value Description
Unknown Unknown result.
Success Command executed successfully.
InProgress 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.
WrongArgument Command has wrong argument(s).
NoSystem No system connected.
ProtocolUnsupported Definition file protocol not supported.

Member Function Documentation

prepare_async()

void mavsdk::Camera::prepare_async(const ResultCallback callback)

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

This function is non-blocking. See 'prepare' for the blocking counterpart.

Parameters

prepare()

Result mavsdk::Camera::prepare() const

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

This function is blocking. See 'prepare_async' for the non-blocking counterpart.

Returns

Result - Result of request.

take_photo_async()

void mavsdk::Camera::take_photo_async(const ResultCallback callback)

Take one photo.

This function is non-blocking. See 'take_photo' for the blocking counterpart.

Parameters

take_photo()

Result mavsdk::Camera::take_photo() const

Take one photo.

This function is blocking. See 'take_photo_async' for the non-blocking counterpart.

Returns

Result - Result of request.

start_photo_interval_async()

void mavsdk::Camera::start_photo_interval_async(float interval_s, const ResultCallback callback)

Start photo timelapse with a given interval.

This function is non-blocking. See 'start_photo_interval' for the blocking counterpart.

Parameters

start_photo_interval()

Result mavsdk::Camera::start_photo_interval(float interval_s) const

Start photo timelapse with a given interval.

This function is blocking. See 'start_photo_interval_async' for the non-blocking counterpart.

Parameters

  • float interval_s -

Returns

Result - Result of request.

stop_photo_interval_async()

void mavsdk::Camera::stop_photo_interval_async(const ResultCallback callback)

Stop a running photo timelapse.

This function is non-blocking. See 'stop_photo_interval' for the blocking counterpart.

Parameters

stop_photo_interval()

Result mavsdk::Camera::stop_photo_interval() const

Stop a running photo timelapse.

This function is blocking. See 'stop_photo_interval_async' for the non-blocking counterpart.

Returns

Result - Result of request.

start_video_async()

void mavsdk::Camera::start_video_async(const ResultCallback callback)

Start a video recording.

This function is non-blocking. See 'start_video' for the blocking counterpart.

Parameters

start_video()

Result mavsdk::Camera::start_video() const

Start a video recording.

This function is blocking. See 'start_video_async' for the non-blocking counterpart.

Returns

Result - Result of request.

stop_video_async()

void mavsdk::Camera::stop_video_async(const ResultCallback callback)

Stop a running video recording.

This function is non-blocking. See 'stop_video' for the blocking counterpart.

Parameters

stop_video()

Result mavsdk::Camera::stop_video() const

Stop a running video recording.

This function is blocking. See 'stop_video_async' for the non-blocking counterpart.

Returns

Result - Result of request.

start_video_streaming()

Result mavsdk::Camera::start_video_streaming(int32_t stream_id) const

Start video streaming.

This function is blocking.

Parameters

  • int32_t stream_id -

Returns

Result - Result of request.

stop_video_streaming()

Result mavsdk::Camera::stop_video_streaming(int32_t stream_id) const

Stop current video streaming.

This function is blocking.

Parameters

  • int32_t stream_id -

Returns

Result - Result of request.

set_mode_async()

void mavsdk::Camera::set_mode_async(Mode mode, const ResultCallback callback)

Set camera mode.

This function is non-blocking. See 'set_mode' for the blocking counterpart.

Parameters

set_mode()

Result mavsdk::Camera::set_mode(Mode mode) const

Set camera mode.

This function is blocking. See 'set_mode_async' for the non-blocking counterpart.

Parameters

Returns

Result - Result of request.

list_photos_async()

void mavsdk::Camera::list_photos_async(PhotosRange photos_range, const ListPhotosCallback callback)

List photos available on the camera.

This function is non-blocking. See 'list_photos' for the blocking counterpart.

Parameters

list_photos()

std::pair<Result, std::vector<Camera::CaptureInfo> > mavsdk::Camera::list_photos(PhotosRange photos_range) const

List photos available on the camera.

This function is blocking. See 'list_photos_async' for the non-blocking counterpart.

Parameters

Returns

 std::pair< Result, std::vector< Camera::CaptureInfo > > - Result of request.

subscribe_mode()

ModeHandle mavsdk::Camera::subscribe_mode(const ModeCallback &callback)

Subscribe to camera mode updates.

Parameters

Returns

ModeHandle -

unsubscribe_mode()

void mavsdk::Camera::unsubscribe_mode(ModeHandle handle)

Unsubscribe from subscribe_mode.

Parameters

mode()

Mode mavsdk::Camera::mode() const

Poll for 'Mode' (blocking).

Returns

Mode - One Mode update.

subscribe_information()

InformationHandle mavsdk::Camera::subscribe_information(const InformationCallback &callback)

Subscribe to camera information updates.

Parameters

Returns

InformationHandle -

unsubscribe_information()

void mavsdk::Camera::unsubscribe_information(InformationHandle handle)

Unsubscribe from subscribe_information.

Parameters

information()

Information mavsdk::Camera::information() const

Poll for 'Information' (blocking).

Returns

Information - One Information update.

subscribe_video_stream_info()

VideoStreamInfoHandle mavsdk::Camera::subscribe_video_stream_info(const VideoStreamInfoCallback &callback)

Subscribe to video stream info updates.

Parameters

Returns

VideoStreamInfoHandle -

unsubscribe_video_stream_info()

void mavsdk::Camera::unsubscribe_video_stream_info(VideoStreamInfoHandle handle)

Unsubscribe from subscribe_video_stream_info.

Parameters

video_stream_info()

VideoStreamInfo mavsdk::Camera::video_stream_info() const

Poll for 'VideoStreamInfo' (blocking).

Returns

VideoStreamInfo - One VideoStreamInfo update.

subscribe_capture_info()

CaptureInfoHandle mavsdk::Camera::subscribe_capture_info(const CaptureInfoCallback &callback)

Subscribe to capture info updates.

Parameters

Returns

CaptureInfoHandle -

unsubscribe_capture_info()

void mavsdk::Camera::unsubscribe_capture_info(CaptureInfoHandle handle)

Unsubscribe from subscribe_capture_info.

Parameters

subscribe_status()

StatusHandle mavsdk::Camera::subscribe_status(const StatusCallback &callback)

Subscribe to camera status updates.

Parameters

Returns

StatusHandle -

unsubscribe_status()

void mavsdk::Camera::unsubscribe_status(StatusHandle handle)

Unsubscribe from subscribe_status.

Parameters

status()

Status mavsdk::Camera::status() const

Poll for 'Status' (blocking).

Returns

Status - One Status update.

subscribe_current_settings()

CurrentSettingsHandle mavsdk::Camera::subscribe_current_settings(const CurrentSettingsCallback &callback)

Get the list of current camera settings.

Parameters

Returns

CurrentSettingsHandle -

unsubscribe_current_settings()

void mavsdk::Camera::unsubscribe_current_settings(CurrentSettingsHandle handle)

Unsubscribe from subscribe_current_settings.

Parameters

subscribe_possible_setting_options()

PossibleSettingOptionsHandle mavsdk::Camera::subscribe_possible_setting_options(const PossibleSettingOptionsCallback &callback)

Get the list of settings that can be changed.

Parameters

Returns

PossibleSettingOptionsHandle -

unsubscribe_possible_setting_options()

void mavsdk::Camera::unsubscribe_possible_setting_options(PossibleSettingOptionsHandle handle)

Unsubscribe from subscribe_possible_setting_options.

Parameters

possible_setting_options()

std::vector<SettingOptions> mavsdk::Camera::possible_setting_options() const

Poll for 'std::vector' (blocking).

Returns

 std::vector< SettingOptions > - One std::vector update.

set_setting_async()

void mavsdk::Camera::set_setting_async(Setting setting, const ResultCallback callback)

Set a setting to some value.

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

This function is non-blocking. See 'set_setting' for the blocking counterpart.

Parameters

set_setting()

Result mavsdk::Camera::set_setting(Setting setting) const

Set a setting to some value.

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

This function is blocking. See 'set_setting_async' for the non-blocking counterpart.

Parameters

Returns

Result - Result of request.

get_setting_async()

void mavsdk::Camera::get_setting_async(Setting setting, const GetSettingCallback callback)

Get a setting.

Only setting_id of setting needs to be set.

This function is non-blocking. See 'get_setting' for the blocking counterpart.

Parameters

get_setting()

std::pair<Result, Camera::Setting> mavsdk::Camera::get_setting(Setting setting) const

Get a setting.

Only setting_id of setting needs to be set.

This function is blocking. See 'get_setting_async' for the non-blocking counterpart.

Parameters

Returns

 std::pair< Result, Camera::Setting > - Result of request.

format_storage_async()

void mavsdk::Camera::format_storage_async(int32_t storage_id, const ResultCallback callback)

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

This will delete all content of the camera storage!

This function is non-blocking. See 'format_storage' for the blocking counterpart.

Parameters

format_storage()

Result mavsdk::Camera::format_storage(int32_t storage_id) const

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

This will delete all content of the camera storage!

This function is blocking. See 'format_storage_async' for the non-blocking counterpart.

Parameters

  • int32_t storage_id -

Returns

Result - Result of request.

select_camera()

Result mavsdk::Camera::select_camera(int32_t camera_id) const

Select current camera .

Bind the plugin instance to a specific camera_id

This function is blocking.

Parameters

  • int32_t camera_id -

Returns

Result - Result of request.

reset_settings_async()

void mavsdk::Camera::reset_settings_async(const ResultCallback callback)

Reset all settings in camera.

This will reset all camera settings to default value

This function is non-blocking. See 'reset_settings' for the blocking counterpart.

Parameters

reset_settings()

Result mavsdk::Camera::reset_settings() const

Reset all settings in camera.

This will reset all camera settings to default value

This function is blocking. See 'reset_settings_async' for the non-blocking counterpart.

Returns

Result - Result of request.

operator=()

const Camera& mavsdk::Camera::operator=(const Camera &)=delete

Equality operator (object is not copyable).

Parameters

Returns

 const Camera & -

© MAVSDK Development Team 2017-2023. License: CC BY 4.0            Updated: 2023-12-27 03:10:20

results matching ""

    No results matching ""