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 Result Possible results returned for camera commands.
std::function< void(Result)> ResultCallback Callback type for asynchronous Camera calls.
std::function< void(Mode)> ModeCallback Callback type for subscribe_mode.
std::function< void(Information)> InformationCallback Callback type for subscribe_information.
std::function< void(VideoStreamInfo)> VideoStreamInfoCallback Callback type for subscribe_video_stream_info.
std::function< void(CaptureInfo)> CaptureInfoCallback Callback type for subscribe_capture_info.
std::function< void(Status)> StatusCallback Callback type for subscribe_status.
std::function< void(std::vector< Setting >)> CurrentSettingsCallback Callback type for subscribe_current_settings.
std::function< void(std::vector< SettingOptions >)> PossibleSettingOptionsCallback Callback 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 () Destructor (internal use only).
  Camera (const Camera & other) Copy constructor.
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 () const Start video streaming.
Result stop_video_streaming () 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 subscribe_mode (ModeCallback callback) Subscribe to camera mode updates.
Mode mode () const Poll for 'Mode' (blocking).
void subscribe_information (InformationCallback callback) Subscribe to camera information updates.
Information information () const Poll for 'Information' (blocking).
void subscribe_video_stream_info (VideoStreamInfoCallback callback) Subscribe to video stream info updates.
VideoStreamInfo video_stream_info () const Poll for 'VideoStreamInfo' (blocking).
void subscribe_capture_info (CaptureInfoCallback callback) Subscribe to capture info updates.
void subscribe_status (StatusCallback callback) Subscribe to camera status updates.
Status status () const Poll for 'Status' (blocking).
void subscribe_current_settings (CurrentSettingsCallback callback) Get the list of current camera settings.
void subscribe_possible_setting_options (PossibleSettingOptionsCallback callback) Get the list of settings that can be changed.
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 (const ResultCallback callback) Format storage (e.g. SD card) in camera.
Result format_storage () const Format storage (e.g. SD card) 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()

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 ModeCallback

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

Callback type for subscribe_mode.

typedef InformationCallback

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

Callback type for subscribe_information.

typedef VideoStreamInfoCallback

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

Callback type for subscribe_video_stream_info.

typedef CaptureInfoCallback

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

Callback type for subscribe_capture_info.

typedef StatusCallback

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

Callback type for subscribe_status.

typedef CurrentSettingsCallback

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

Callback 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 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 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 occured while executing the command.
Timeout Command timed out.
WrongArgument Command has wrong argument(s).

Member Function Documentation

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() const

Start video streaming.

This function is blocking.

Returns

Result - Result of request.

stop_video_streaming()

Result mavsdk::Camera::stop_video_streaming() const

Stop current video streaming.

This function is blocking.

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.

subscribe_mode()

void mavsdk::Camera::subscribe_mode(ModeCallback callback)

Subscribe to camera mode updates.

Parameters

mode()

Mode mavsdk::Camera::mode() const

Poll for 'Mode' (blocking).

Returns

Mode - One Mode update.

subscribe_information()

void mavsdk::Camera::subscribe_information(InformationCallback callback)

Subscribe to camera information updates.

Parameters

information()

Information mavsdk::Camera::information() const

Poll for 'Information' (blocking).

Returns

Information - One Information update.

subscribe_video_stream_info()

void mavsdk::Camera::subscribe_video_stream_info(VideoStreamInfoCallback callback)

Subscribe to video stream info updates.

Parameters

video_stream_info()

VideoStreamInfo mavsdk::Camera::video_stream_info() const

Poll for 'VideoStreamInfo' (blocking).

Returns

VideoStreamInfo - One VideoStreamInfo update.

subscribe_capture_info()

void mavsdk::Camera::subscribe_capture_info(CaptureInfoCallback callback)

Subscribe to capture info updates.

Parameters

subscribe_status()

void mavsdk::Camera::subscribe_status(StatusCallback callback)

Subscribe to camera status updates.

Parameters

status()

Status mavsdk::Camera::status() const

Poll for 'Status' (blocking).

Returns

Status - One Status update.

subscribe_current_settings()

void mavsdk::Camera::subscribe_current_settings(CurrentSettingsCallback callback)

Get the list of current camera settings.

Parameters

subscribe_possible_setting_options()

void mavsdk::Camera::subscribe_possible_setting_options(PossibleSettingOptionsCallback callback)

Get the list of settings that can be changed.

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(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() 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.

Returns

Result - Result of request.

operator=()

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

Equality operator (object is not copyable).

Parameters

Returns

 const Camera & -

© Dronecode 2017-2020. License: CC BY 4.0            Updated: 2021-02-08 13:41:53

results matching ""

    No results matching ""