mavsdk::Camera Class Reference
#include: camera.h
The Camera class 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
.
Synchronous and asynchronous variants of the camera methods are supplied.
Data Structures
struct CaptureInfo
struct Information
struct Option
struct Setting
struct SettingOptions
struct Status
struct VideoStreamInfo
struct VideoStreamSettings
Public Types
Type | Description |
---|---|
enum Result | Possible results returned for camera commands. |
enum Mode | Camera mode type. |
std::function< void(Result)> result_callback_t | Callback type for asynchronous Camera calls. |
std::function< void(Result, const Mode &)> mode_callback_t | Callback type for asynchronous camera mode calls. |
std::function< void(Mode)> subscribe_mode_callback_t | Callback type for camera mode subscription. |
std::function< void(Result, VideoStreamInfo)> get_video_stream_info_callback_t | Callback type for asynchronous video stream info call. |
std::function< void(VideoStreamInfo)> subscribe_video_stream_info_callback_t | Callback type for video stream info. |
std::function< void(CaptureInfo)> capture_info_callback_t | Callback type for capture info updates. |
std::function< void(Result, Status)> get_status_callback_t | Callback type to get status. |
std::function< void(Status)> subscribe_status_callback_t | Callback type to subscribe to status updates. |
std::function< void(Result, const Option &)> get_option_callback_t | Callback type to get an option. |
std::function< void(const std::vector< Setting >)> subscribe_current_settings_callback_t | Callback type to get the currently selected settings. |
std::function< void(const std::vector< SettingOptions >)> subscribe_possible_setting_options_callback_t | Callback type to get possible setting options. |
Public Member Functions
Type | Name | Description |
---|---|---|
Camera (System & system) | Constructor. Creates the plugin for a specific System. | |
~Camera () | Destructor (internal use only). | |
Camera (const Camera &)=delete | Copy constructor (object is not copyable). | |
Result | select_camera (unsigned id) | Select camera to interact with. |
Result | take_photo () | Take photo (synchronous). |
Result | start_photo_interval (float interval_s) | Start photo interval (synchronous). |
Result | stop_photo_interval () | Stop photo interval (synchronous). |
Result | start_video () | Start video capture (synchronous). |
Result | stop_video () | Stop video capture (synchronous). |
void | take_photo_async (const result_callback_t & callback) | Take photo (asynchronous). |
void | start_photo_interval_async (float interval_s, const result_callback_t & callback) | Start photo interval (asynchronous). |
void | stop_photo_interval_async (const result_callback_t & callback) | Stop photo interval (asynchronous). |
void | start_video_async (const result_callback_t & callback) | Start video capture (asynchronous). |
void | stop_video_async (const result_callback_t & callback) | Stop video capture (asynchronous). |
Information | get_information () | Get general camera information. |
Result | set_mode (const Mode mode) | Setter for camera mode (synchronous). |
void | set_mode_async (const Mode mode, const mode_callback_t & callback) | Setter for camera mode (asynchronous). |
void | get_mode_async (const mode_callback_t & callback) | Getter for camera mode (asynchronous). |
void | subscribe_mode (const subscribe_mode_callback_t callback) | Async subscription for camera mode updates (asynchronous). |
Result | get_video_stream_info (VideoStreamInfo & info) | Get video stream information (synchronous). |
void | get_video_stream_info_async (const get_video_stream_info_callback_t callback) | Get video stream information (asynchronous). |
void | subscribe_video_stream_info (const subscribe_video_stream_info_callback_t callback) | Async subscription for video stream info updates (asynchronous). |
Result | start_video_streaming () | Starts video streaming (synchronous). |
Result | stop_video_streaming () | Stop the current video streaming (synchronous). |
void | subscribe_capture_info (capture_info_callback_t callback) | Subscribe to capture info updates (asynchronous). |
void | get_status_async (get_status_callback_t callback) | Get camera status (asynchronous). |
void | subscribe_status (const subscribe_status_callback_t callback) | Subscribe to status updates (asynchronous). |
bool | get_possible_setting_options (std::vector< std::string > & settings) | Get settings that can be changed. |
bool | get_possible_options (const std::string & setting_id, std::vector< Camera::Option > & options) | Get possible options for a setting that can be selected. |
bool | is_setting_range (const std::string & setting_id) | Query if setting is a range setting. |
Camera::Result | get_option (const std::string & setting_id, Option & option) | Get an option of a setting (synchronous). |
void | get_option_async (const std::string & setting_id, const get_option_callback_t & callback) | Get an option of a setting (asynchronous). |
void | set_option_async (const result_callback_t & callback, const std::string & setting_id, const Camera::Option & option) | Set an option of a setting (asynchronous). |
void | subscribe_current_settings (const subscribe_current_settings_callback_t & callback) | Subscribe to currently selected settings (asynchronous). |
void | subscribe_possible_setting_options (const subscribe_possible_setting_options_callback_t & callback) | Subscribe to all possible setting options (asynchronous). |
void | format_storage_async (result_callback_t callback) | Format storage (e.g. SD card) in camera (asynchronous). |
Result | format_storage () | Format storage (e.g. SD card) in camera (synchronous). |
const Camera & | operator= (const Camera &)=delete | Equality operator (object is not copyable). |
Static Public Member Functions
Type | Name | Description |
---|---|---|
std::string | result_str (Result result) | Returns a human-readable English string for Camera::Result. |
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 = std::make_shared<Camera>(system);
Parameters
- System& system - The specific system associated with this plugin.
~Camera()
mavsdk::Camera::~Camera()
Destructor (internal use only).
Camera()
mavsdk::Camera::Camera(const Camera &)=delete
Copy constructor (object is not copyable).
Parameters
- const Camera& -
Member Typdef Documentation
typedef result_callback_t
typedef std::function<void(Result)> mavsdk::Camera::result_callback_t
Callback type for asynchronous Camera calls.
typedef mode_callback_t
typedef std::function<void(Result, const Mode&)> mavsdk::Camera::mode_callback_t
Callback type for asynchronous camera mode calls.
typedef subscribe_mode_callback_t
typedef std::function<void(Mode)> mavsdk::Camera::subscribe_mode_callback_t
Callback type for camera mode subscription.
typedef get_video_stream_info_callback_t
typedef std::function<void(Result, VideoStreamInfo)> mavsdk::Camera::get_video_stream_info_callback_t
Callback type for asynchronous video stream info call.
typedef subscribe_video_stream_info_callback_t
typedef std::function<void(VideoStreamInfo)> mavsdk::Camera::subscribe_video_stream_info_callback_t
Callback type for video stream info.
typedef capture_info_callback_t
typedef std::function<void(CaptureInfo)> mavsdk::Camera::capture_info_callback_t
Callback type for capture info updates.
typedef get_status_callback_t
typedef std::function<void(Result, Status)> mavsdk::Camera::get_status_callback_t
Callback type to get status.
typedef subscribe_status_callback_t
typedef std::function<void(Status)> mavsdk::Camera::subscribe_status_callback_t
Callback type to subscribe to status updates.
typedef get_option_callback_t
typedef std::function<void(Result, const Option&)> mavsdk::Camera::get_option_callback_t
Callback type to get an option.
typedef subscribe_current_settings_callback_t
typedef std::function<void(const std::vector<Setting>)> mavsdk::Camera::subscribe_current_settings_callback_t
Callback type to get the currently selected settings.
typedef subscribe_possible_setting_options_callback_t
typedef std::function<void(const std::vector<SettingOptions>)> mavsdk::Camera::subscribe_possible_setting_options_callback_t
Callback type to get possible setting options.
Member Enumeration Documentation
enum Result
Possible results returned for camera commands.
Value | Description |
---|---|
UNKNOWN |
The result is unknown. |
SUCCESS |
Camera command executed successfully. |
IN_PROGRESS |
Camera command is in progress. |
BUSY |
Camera is busy and rejected command. |
DENIED |
Camera has denied the command. |
ERROR |
An error has occurred while executing the command. |
TIMEOUT |
Camera has not responded in time and the command has timed out. |
WRONG_ARGUMENT |
The command has wrong arguments. |
enum Mode
Camera mode type.
Value | Description |
---|---|
PHOTO |
Photo mode. |
VIDEO |
Video mode. |
UNKNOWN |
Unknown mode. |
Member Function Documentation
select_camera()
Result mavsdk::Camera::select_camera(unsigned id)
Select camera to interact with.
It is recommended to instantiate multiple camera plugins to deal with multiple cameras and to select the camera once right after creating the plugin.
Parameters
- unsigned id - The camera ID from 0 to 5.
Returns
Result - Result of request.
take_photo()
Result mavsdk::Camera::take_photo()
Take photo (synchronous).
This takes one photo.
Returns
Result - Result of request.
start_photo_interval()
Result mavsdk::Camera::start_photo_interval(float interval_s)
Start photo interval (synchronous).
Starts a photo timelapse with a given interval.
Parameters
- float interval_s - The interval between photos in seconds.
Returns
Result - Result of request.
See Also:
stop_photo_interval()
Result mavsdk::Camera::stop_photo_interval()
Stop photo interval (synchronous).
Stops a photo timelapse, previously started with start_photo_interval().
Returns
Result - Result of request.
start_video()
Result mavsdk::Camera::start_video()
Start video capture (synchronous).
This starts a video recording.
Returns
Result - Result of request.
stop_video()
Result mavsdk::Camera::stop_video()
Stop video capture (synchronous).
This stops a video recording, previously started with start_video().
Returns
Result - Result of request.
take_photo_async()
void mavsdk::Camera::take_photo_async(const result_callback_t &callback)
Take photo (asynchronous).
This takes one photo.
Parameters
- const result_callback_t& callback - Function to call with result of request.
start_photo_interval_async()
void mavsdk::Camera::start_photo_interval_async(float interval_s, const result_callback_t &callback)
Start photo interval (asynchronous).
Starts a photo timelapse with a given interval.
Parameters
- float interval_s - The interval between photos in seconds.
- const result_callback_t& callback - Function to call with result of request.
See Also:
stop_photo_interval_async()
void mavsdk::Camera::stop_photo_interval_async(const result_callback_t &callback)
Stop photo interval (asynchronous).
Stops a photo timelapse, previously started with start_photo_interval_async().
Parameters
- const result_callback_t& callback - Function to call with result of request.
start_video_async()
void mavsdk::Camera::start_video_async(const result_callback_t &callback)
Start video capture (asynchronous).
This starts a video recording.
Parameters
- const result_callback_t& callback - Function to call with result of request.
stop_video_async()
void mavsdk::Camera::stop_video_async(const result_callback_t &callback)
Stop video capture (asynchronous).
This stops a video recording, previously started with start_video_async().
Parameters
- const result_callback_t& callback - Function to call with result of request.
get_information()
Information mavsdk::Camera::get_information()
Get general camera information.
Returns
Information - The camera information struct.
set_mode()
Result mavsdk::Camera::set_mode(const Mode mode)
Setter for camera mode (synchronous).
Parameters
Returns
Result - SUCCESS if mode is set, error otherwise.
set_mode_async()
void mavsdk::Camera::set_mode_async(const Mode mode, const mode_callback_t &callback)
Setter for camera mode (asynchronous).
Parameters
- const Mode mode - Camera mode to set.
- const mode_callback_t& callback - Function to call with result of request.
get_mode_async()
void mavsdk::Camera::get_mode_async(const mode_callback_t &callback)
Getter for camera mode (asynchronous).
Parameters
- const mode_callback_t& callback - Function to call with result of request.
subscribe_mode()
void mavsdk::Camera::subscribe_mode(const subscribe_mode_callback_t callback)
Async subscription for camera mode updates (asynchronous).
Parameters
- const subscribe_mode_callback_t callback - Function to call with camera mode updates.
get_video_stream_info()
Result mavsdk::Camera::get_video_stream_info(VideoStreamInfo &info)
Get video stream information (synchronous).
Application may use media player like VLC and feed uri
to play the ongoing video streaming.
Parameters
- VideoStreamInfo& info - Video stream information will be filled.
Returns
Result - SUCCESS if video stream info is received, error otherwise.
get_video_stream_info_async()
void mavsdk::Camera::get_video_stream_info_async(const get_video_stream_info_callback_t callback)
Get video stream information (asynchronous).
Parameters
- const get_video_stream_info_callback_t callback - Function to call with video stream info.
subscribe_video_stream_info()
void mavsdk::Camera::subscribe_video_stream_info(const subscribe_video_stream_info_callback_t callback)
Async subscription for video stream info updates (asynchronous).
Parameters
- const subscribe_video_stream_info_callback_t callback - Function to call with video stream updates.
start_video_streaming()
Result mavsdk::Camera::start_video_streaming()
Starts video streaming (synchronous).
Sends a request to start video streaming.
Returns
Result - SUCCESS if video streaming is started, error otherwise.
See Also:
stop_video_streaming()
Result mavsdk::Camera::stop_video_streaming()
Stop the current video streaming (synchronous).
Sends a request to stop ongoing video streaming.
Returns
Result - SUCCESS if video streaming is stopped, error otherwise.
See Also:
subscribe_capture_info()
void mavsdk::Camera::subscribe_capture_info(capture_info_callback_t callback)
Subscribe to capture info updates (asynchronous).
Parameters
- capture_info_callback_t callback - Function to call with updates.
get_status_async()
void mavsdk::Camera::get_status_async(get_status_callback_t callback)
Get camera status (asynchronous).
Parameters
- get_status_callback_t callback - Function to call with camera status.
subscribe_status()
void mavsdk::Camera::subscribe_status(const subscribe_status_callback_t callback)
Subscribe to status updates (asynchronous).
Parameters
- const subscribe_status_callback_t callback - Function to call with status update.
get_possible_setting_options()
bool mavsdk::Camera::get_possible_setting_options(std::vector< std::string > &settings)
Get settings that can be changed.
Parameters
- std::vector< std::string >& settings - List of settings that can be changed.
Returns
bool - true request was successful.
get_possible_options()
bool mavsdk::Camera::get_possible_options(const std::string &setting_id, std::vector< Camera::Option > &options)
Get possible options for a setting that can be selected.
Parameters
- const std::string& setting_id - Name of setting (machine readable).
- std::vector< Camera::Option >& options - List of Option objects to select from.
Returns
bool - true if request was successful.
is_setting_range()
bool mavsdk::Camera::is_setting_range(const std::string &setting_id)
Query if setting is a range setting.
A range setting is not given by possible options but rather by [min, max] or [min, max, interval].
Parameters
- const std::string& setting_id - Name of setting (machine readable).
Returns
bool - true if it is a range setting.
get_option()
Camera::Result mavsdk::Camera::get_option(const std::string &setting_id, Option &option)
Get an option of a setting (synchronous).
Parameters
- const std::string& setting_id - The machine readable name of the setting.
- Option& option - A reference to the option to set.
Returns
Camera::Result - Result of request.
get_option_async()
void mavsdk::Camera::get_option_async(const std::string &setting_id, const get_option_callback_t &callback)
Get an option of a setting (asynchronous).
Parameters
- const std::string& setting_id - The machine readable name of the setting.
- const get_option_callback_t& callback - The callback to get the result and selected option.
set_option_async()
void mavsdk::Camera::set_option_async(const result_callback_t &callback, const std::string &setting_id, const Camera::Option &option)
Set an option of a setting (asynchronous).
Parameters
- const result_callback_t& callback - The callback to get the result.
- const std::string& setting_id - The machine readable name of the setting.
- const Camera::Option& option - The machine readable name of the option value.
subscribe_current_settings()
void mavsdk::Camera::subscribe_current_settings(const subscribe_current_settings_callback_t &callback)
Subscribe to currently selected settings (asynchronous).
Parameters
- const subscribe_current_settings_callback_t& callback - Function to call when current options have been updated.
subscribe_possible_setting_options()
void mavsdk::Camera::subscribe_possible_setting_options(const subscribe_possible_setting_options_callback_t &callback)
Subscribe to all possible setting options (asynchronous).
Parameters
- const subscribe_possible_setting_options_callback_t& callback - Function to call when possible options have been updated.
format_storage_async()
void mavsdk::Camera::format_storage_async(result_callback_t callback)
Format storage (e.g. SD card) in camera (asynchronous).
This will delete all content of the camera storage (e.g. SD card).
Parameters
- result_callback_t callback - Callback to get result.
format_storage()
Result mavsdk::Camera::format_storage()
Format storage (e.g. SD card) in camera (synchronous).
This will delete all content of the camera storage (e.g. SD card).
Returns
Result - result of request.
operator=()
const Camera& mavsdk::Camera::operator=(const Camera &)=delete
Equality operator (object is not copyable).
Parameters
- const Camera& -
Returns
const Camera & -
result_str()
static std::string mavsdk::Camera::result_str(Result result)
Returns a human-readable English string for Camera::Result.
Parameters
- Result result - The enum value for which a human readable string is required.
Returns
std::string - Human readable string for the Camera::Result.