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 CameraList
struct CaptureInfo
struct CurrentSettingsUpdate
struct EulerAngle
struct Information
struct ModeUpdate
struct Option
struct Position
struct PossibleSettingOptionsUpdate
struct Quaternion
struct Setting
struct SettingOptions
struct Storage
struct StorageUpdate
struct VideoStreamInfo
struct VideoStreamSettings
struct VideoStreamUpdate
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(CameraList)> CameraListCallback | Callback type for subscribe_camera_list. |
Handle< CameraList > CameraListHandle | Handle type for subscribe_camera_list. |
std::function< void(ModeUpdate)> ModeCallback | Callback type for subscribe_mode. |
Handle< ModeUpdate > ModeHandle | Handle type for subscribe_mode. |
std::function< void(VideoStreamUpdate)> VideoStreamInfoCallback | Callback type for subscribe_video_stream_info. |
Handle< VideoStreamUpdate > 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(StorageUpdate)> StorageCallback | Callback type for subscribe_storage. |
Handle< StorageUpdate > StorageHandle | Handle type for subscribe_storage. |
std::function< void(CurrentSettingsUpdate)> CurrentSettingsCallback | Callback type for subscribe_current_settings. |
Handle< CurrentSettingsUpdate > CurrentSettingsHandle | Handle type for subscribe_current_settings. |
std::function< void(PossibleSettingOptionsUpdate)> PossibleSettingOptionsCallback | Callback type for subscribe_possible_setting_options. |
Handle< PossibleSettingOptionsUpdate > 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 | take_photo_async (int32_t component_id, const ResultCallback callback) | Take one photo. |
Result | take_photo (int32_t component_id)const | Take one photo. |
void | start_photo_interval_async (int32_t component_id, float interval_s, const ResultCallback callback) | Start photo timelapse with a given interval. |
Result | start_photo_interval (int32_t component_id, float interval_s)const | Start photo timelapse with a given interval. |
void | stop_photo_interval_async (int32_t component_id, const ResultCallback callback) | Stop a running photo timelapse. |
Result | stop_photo_interval (int32_t component_id)const | Stop a running photo timelapse. |
void | start_video_async (int32_t component_id, const ResultCallback callback) | Start a video recording. |
Result | start_video (int32_t component_id)const | Start a video recording. |
void | stop_video_async (int32_t component_id, const ResultCallback callback) | Stop a running video recording. |
Result | stop_video (int32_t component_id)const | Stop a running video recording. |
Result | start_video_streaming (int32_t component_id, int32_t stream_id)const | Start video streaming. |
Result | stop_video_streaming (int32_t component_id, int32_t stream_id)const | Stop current video streaming. |
void | set_mode_async (int32_t component_id, Mode mode, const ResultCallback callback) | Set camera mode. |
Result | set_mode (int32_t component_id, Mode mode)const | Set camera mode. |
void | list_photos_async (int32_t component_id, PhotosRange photos_range, const ListPhotosCallback callback) | List photos available on the camera. |
std::pair< Result, std::vector< Camera::CaptureInfo > > | list_photos (int32_t component_id, PhotosRange photos_range)const | List photos available on the camera. |
CameraListHandle | subscribe_camera_list (const CameraListCallback & callback) | Subscribe to list of cameras. |
void | unsubscribe_camera_list (CameraListHandle handle) | Unsubscribe from subscribe_camera_list. |
CameraList | camera_list () const | Poll for 'CameraList' (blocking). |
ModeHandle | subscribe_mode (const ModeCallback & callback) | Subscribe to camera mode updates. |
void | unsubscribe_mode (ModeHandle handle) | Unsubscribe from subscribe_mode. |
std::pair< Result, Camera::Mode > | get_mode (int32_t component_id)const | Get camera mode. |
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. |
std::pair< Result, Camera::VideoStreamInfo > | get_video_stream_info (int32_t component_id)const | Get video stream info. |
CaptureInfoHandle | subscribe_capture_info (const CaptureInfoCallback & callback) | Subscribe to capture info updates. |
void | unsubscribe_capture_info (CaptureInfoHandle handle) | Unsubscribe from subscribe_capture_info. |
StorageHandle | subscribe_storage (const StorageCallback & callback) | Subscribe to camera's storage status updates. |
void | unsubscribe_storage (StorageHandle handle) | Unsubscribe from subscribe_storage. |
std::pair< Result, Camera::Storage > | get_storage (int32_t component_id)const | Get camera's storage status. |
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. |
std::pair< Result, std::vector< Camera::Setting > > | get_current_settings (int32_t component_id)const | Get 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::pair< Result, std::vector< Camera::SettingOptions > > | get_possible_setting_options (int32_t component_id)const | Get possible setting options. |
void | set_setting_async (int32_t component_id, Setting setting, const ResultCallback callback) | Set a setting to some value. |
Result | set_setting (int32_t component_id, Setting setting)const | Set a setting to some value. |
void | get_setting_async (int32_t component_id, Setting setting, const GetSettingCallback callback) | Get a setting. |
std::pair< Result, Camera::Setting > | get_setting (int32_t component_id, Setting setting)const | Get a setting. |
void | format_storage_async (int32_t component_id, int32_t storage_id, const ResultCallback callback) | Format storage (e.g. SD card) in camera. |
Result | format_storage (int32_t component_id, int32_t storage_id)const | Format storage (e.g. SD card) in camera. |
void | reset_settings_async (int32_t component_id, const ResultCallback callback) | Reset all settings in camera. |
Result | reset_settings (int32_t component_id)const | Reset all settings in camera. |
void | zoom_in_start_async (int32_t component_id, const ResultCallback callback) | Start zooming in. |
Result | zoom_in_start (int32_t component_id)const | Start zooming in. |
void | zoom_out_start_async (int32_t component_id, const ResultCallback callback) | Start zooming out. |
Result | zoom_out_start (int32_t component_id)const | Start zooming out. |
void | zoom_stop_async (int32_t component_id, const ResultCallback callback) | Stop zooming. |
Result | zoom_stop (int32_t component_id)const | Stop zooming. |
void | zoom_range_async (int32_t component_id, float range, const ResultCallback callback) | Zoom to value as proportion of full camera range (percentage between 0.0 and 100.0). |
Result | zoom_range (int32_t component_id, float range)const | Zoom to value as proportion of full camera range (percentage between 0.0 and 100.0). |
void | track_point_async (int32_t component_id, float point_x, float point_y, float radius, const ResultCallback callback) | Track point. |
Result | track_point (int32_t component_id, float point_x, float point_y, float radius)const | Track point. |
void | track_rectangle_async (int32_t component_id, float top_left_x, float top_left_y, float bottom_right_x, float bottom_right_y, const ResultCallback callback) | Track rectangle. |
Result | track_rectangle (int32_t component_id, float top_left_x, float top_left_y, float bottom_right_x, float bottom_right_y)const | Track rectangle. |
void | track_stop_async (int32_t component_id, const ResultCallback callback) | Stop tracking. |
Result | track_stop (int32_t component_id)const | Stop tracking. |
void | focus_in_start_async (int32_t component_id, const ResultCallback callback) | Start focusing in. |
Result | focus_in_start (int32_t component_id)const | Start focusing in. |
void | focus_out_start_async (int32_t component_id, const ResultCallback callback) | Start focusing out. |
Result | focus_out_start (int32_t component_id)const | Start focusing out. |
void | focus_stop_async (int32_t component_id, const ResultCallback callback) | Stop focus. |
Result | focus_stop (int32_t component_id)const | Stop focus. |
void | focus_range_async (int32_t component_id, float range, const ResultCallback callback) | Focus with range value of full range (value between 0.0 and 100.0). |
Result | focus_range (int32_t component_id, float range)const | Focus with range value of full range (value between 0.0 and 100.0). |
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
- const Camera& other -
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 CameraListCallback ​
using mavsdk::Camera::CameraListCallback = std::function<void(CameraList)>
Callback type for subscribe_camera_list.
typedef CameraListHandle ​
using mavsdk::Camera::CameraListHandle = Handle<CameraList>
Handle type for subscribe_camera_list.
typedef ModeCallback ​
using mavsdk::Camera::ModeCallback = std::function<void(ModeUpdate)>
Callback type for subscribe_mode.
typedef ModeHandle ​
using mavsdk::Camera::ModeHandle = Handle<ModeUpdate>
Handle type for subscribe_mode.
typedef VideoStreamInfoCallback ​
using mavsdk::Camera::VideoStreamInfoCallback = std::function<void(VideoStreamUpdate)>
Callback type for subscribe_video_stream_info.
typedef VideoStreamInfoHandle ​
using mavsdk::Camera::VideoStreamInfoHandle = Handle<VideoStreamUpdate>
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 StorageCallback ​
using mavsdk::Camera::StorageCallback = std::function<void(StorageUpdate)>
Callback type for subscribe_storage.
typedef StorageHandle ​
using mavsdk::Camera::StorageHandle = Handle<StorageUpdate>
Handle type for subscribe_storage.
typedef CurrentSettingsCallback ​
using mavsdk::Camera::CurrentSettingsCallback = std::function<void(CurrentSettingsUpdate)>
Callback type for subscribe_current_settings.
typedef CurrentSettingsHandle ​
using mavsdk::Camera::CurrentSettingsHandle = Handle<CurrentSettingsUpdate>
Handle type for subscribe_current_settings.
typedef PossibleSettingOptionsCallback ​
using mavsdk::Camera::PossibleSettingOptionsCallback = std::function<void(PossibleSettingOptionsUpdate)>
Callback type for subscribe_possible_setting_options.
typedef PossibleSettingOptionsHandle ​
using mavsdk::Camera::PossibleSettingOptionsHandle = Handle<PossibleSettingOptionsUpdate>
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. |
Unavailable | Not available (yet). |
CameraIdInvalid | Camera with camera ID not found. |
ActionUnsupported | Camera action not supported. |
Member Function Documentation ​
take_photo_async() ​
void mavsdk::Camera::take_photo_async(int32_t component_id, const ResultCallback callback)
Take one photo.
This function is non-blocking. See 'take_photo' for the blocking counterpart.
Parameters
- int32_t component_id -
- const ResultCallback callback -
take_photo() ​
Result mavsdk::Camera::take_photo(int32_t component_id) const
Take one photo.
This function is blocking. See 'take_photo_async' for the non-blocking counterpart.
Parameters
- int32_t component_id -
Returns
 Result - Result of request.
start_photo_interval_async() ​
void mavsdk::Camera::start_photo_interval_async(int32_t component_id, 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
- int32_t component_id -
- float interval_s -
- const ResultCallback callback -
start_photo_interval() ​
Result mavsdk::Camera::start_photo_interval(int32_t component_id, 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
- int32_t component_id -
- float interval_s -
Returns
 Result - Result of request.
stop_photo_interval_async() ​
void mavsdk::Camera::stop_photo_interval_async(int32_t component_id, const ResultCallback callback)
Stop a running photo timelapse.
This function is non-blocking. See 'stop_photo_interval' for the blocking counterpart.
Parameters
- int32_t component_id -
- const ResultCallback callback -
stop_photo_interval() ​
Result mavsdk::Camera::stop_photo_interval(int32_t component_id) const
Stop a running photo timelapse.
This function is blocking. See 'stop_photo_interval_async' for the non-blocking counterpart.
Parameters
- int32_t component_id -
Returns
 Result - Result of request.
start_video_async() ​
void mavsdk::Camera::start_video_async(int32_t component_id, const ResultCallback callback)
Start a video recording.
This function is non-blocking. See 'start_video' for the blocking counterpart.
Parameters
- int32_t component_id -
- const ResultCallback callback -
start_video() ​
Result mavsdk::Camera::start_video(int32_t component_id) const
Start a video recording.
This function is blocking. See 'start_video_async' for the non-blocking counterpart.
Parameters
- int32_t component_id -
Returns
 Result - Result of request.
stop_video_async() ​
void mavsdk::Camera::stop_video_async(int32_t component_id, const ResultCallback callback)
Stop a running video recording.
This function is non-blocking. See 'stop_video' for the blocking counterpart.
Parameters
- int32_t component_id -
- const ResultCallback callback -
stop_video() ​
Result mavsdk::Camera::stop_video(int32_t component_id) const
Stop a running video recording.
This function is blocking. See 'stop_video_async' for the non-blocking counterpart.
Parameters
- int32_t component_id -
Returns
 Result - Result of request.
start_video_streaming() ​
Result mavsdk::Camera::start_video_streaming(int32_t component_id, int32_t stream_id) const
Start video streaming.
This function is blocking.
Parameters
- int32_t component_id -
- int32_t stream_id -
Returns
 Result - Result of request.
stop_video_streaming() ​
Result mavsdk::Camera::stop_video_streaming(int32_t component_id, int32_t stream_id) const
Stop current video streaming.
This function is blocking.
Parameters
- int32_t component_id -
- int32_t stream_id -
Returns
 Result - Result of request.
set_mode_async() ​
void mavsdk::Camera::set_mode_async(int32_t component_id, Mode mode, const ResultCallback callback)
Set camera mode.
This function is non-blocking. See 'set_mode' for the blocking counterpart.
Parameters
- int32_t component_id -
- Mode mode -
- const ResultCallback callback -
set_mode() ​
Result mavsdk::Camera::set_mode(int32_t component_id, Mode mode) const
Set camera mode.
This function is blocking. See 'set_mode_async' for the non-blocking counterpart.
Parameters
- int32_t component_id -
- Mode mode -
Returns
 Result - Result of request.
list_photos_async() ​
void mavsdk::Camera::list_photos_async(int32_t component_id, PhotosRange photos_range, const ListPhotosCallback callback)
List photos available on the camera.
Note that this might need to be called initially to set the PhotosRange accordingly. Once set to 'all' rather than 'since connection', it will try to request the previous images over time.
This function is non-blocking. See 'list_photos' for the blocking counterpart.
Parameters
- int32_t component_id -
- PhotosRange photos_range -
- const ListPhotosCallback callback -
list_photos() ​
std::pair< Result, std::vector< Camera::CaptureInfo > > mavsdk::Camera::list_photos(int32_t component_id, PhotosRange photos_range) const
List photos available on the camera.
Note that this might need to be called initially to set the PhotosRange accordingly. Once set to 'all' rather than 'since connection', it will try to request the previous images over time.
This function is blocking. See 'list_photos_async' for the non-blocking counterpart.
Parameters
- int32_t component_id -
- PhotosRange photos_range -
Returns
 std::pair< Result, std::vector< Camera::CaptureInfo > > - Result of request.
subscribe_camera_list() ​
CameraListHandle mavsdk::Camera::subscribe_camera_list(const CameraListCallback &callback)
Subscribe to list of cameras.
This allows to find out what cameras are connected to the system. Based on the camera ID, we can then address a specific camera.
Parameters
- const CameraListCallback& callback -
Returns
 CameraListHandle -
unsubscribe_camera_list() ​
void mavsdk::Camera::unsubscribe_camera_list(CameraListHandle handle)
Unsubscribe from subscribe_camera_list.
Parameters
- CameraListHandle handle -
camera_list() ​
CameraList mavsdk::Camera::camera_list() const
Poll for 'CameraList' (blocking).
Returns
 CameraList - One CameraList update.
subscribe_mode() ​
ModeHandle mavsdk::Camera::subscribe_mode(const ModeCallback &callback)
Subscribe to camera mode updates.
Parameters
- const ModeCallback& callback -
Returns
 ModeHandle -
unsubscribe_mode() ​
void mavsdk::Camera::unsubscribe_mode(ModeHandle handle)
Unsubscribe from subscribe_mode.
Parameters
- ModeHandle handle -
get_mode() ​
std::pair< Result, Camera::Mode > mavsdk::Camera::get_mode(int32_t component_id) const
Get camera mode.
This function is blocking.
Parameters
- int32_t component_id -
Returns
 std::pair< Result, Camera::Mode > - Result of request.
subscribe_video_stream_info() ​
VideoStreamInfoHandle mavsdk::Camera::subscribe_video_stream_info(const VideoStreamInfoCallback &callback)
Subscribe to video stream info updates.
Parameters
- const VideoStreamInfoCallback& callback -
Returns
unsubscribe_video_stream_info() ​
void mavsdk::Camera::unsubscribe_video_stream_info(VideoStreamInfoHandle handle)
Unsubscribe from subscribe_video_stream_info.
Parameters
- VideoStreamInfoHandle handle -
get_video_stream_info() ​
std::pair< Result, Camera::VideoStreamInfo > mavsdk::Camera::get_video_stream_info(int32_t component_id) const
Get video stream info.
This function is blocking.
Parameters
- int32_t component_id -
Returns
 std::pair< Result, Camera::VideoStreamInfo > - Result of request.
subscribe_capture_info() ​
CaptureInfoHandle mavsdk::Camera::subscribe_capture_info(const CaptureInfoCallback &callback)
Subscribe to capture info updates.
Parameters
- const CaptureInfoCallback& callback -
Returns
 CaptureInfoHandle -
unsubscribe_capture_info() ​
void mavsdk::Camera::unsubscribe_capture_info(CaptureInfoHandle handle)
Unsubscribe from subscribe_capture_info.
Parameters
- CaptureInfoHandle handle -
subscribe_storage() ​
StorageHandle mavsdk::Camera::subscribe_storage(const StorageCallback &callback)
Subscribe to camera's storage status updates.
Parameters
- const StorageCallback& callback -
Returns
 StorageHandle -
unsubscribe_storage() ​
void mavsdk::Camera::unsubscribe_storage(StorageHandle handle)
Unsubscribe from subscribe_storage.
Parameters
- StorageHandle handle -
get_storage() ​
std::pair< Result, Camera::Storage > mavsdk::Camera::get_storage(int32_t component_id) const
Get camera's storage status.
This function is blocking.
Parameters
- int32_t component_id -
Returns
 std::pair< Result, Camera::Storage > - Result of request.
subscribe_current_settings() ​
CurrentSettingsHandle mavsdk::Camera::subscribe_current_settings(const CurrentSettingsCallback &callback)
Get the list of current camera settings.
Parameters
- const CurrentSettingsCallback& callback -
Returns
unsubscribe_current_settings() ​
void mavsdk::Camera::unsubscribe_current_settings(CurrentSettingsHandle handle)
Unsubscribe from subscribe_current_settings.
Parameters
- CurrentSettingsHandle handle -
get_current_settings() ​
std::pair< Result, std::vector< Camera::Setting > > mavsdk::Camera::get_current_settings(int32_t component_id) const
Get current settings.
This function is blocking.
Parameters
- int32_t component_id -
Returns
 std::pair< Result, std::vector< Camera::Setting > > - Result of request.
subscribe_possible_setting_options() ​
PossibleSettingOptionsHandle mavsdk::Camera::subscribe_possible_setting_options(const PossibleSettingOptionsCallback &callback)
Get the list of settings that can be changed.
Parameters
- const PossibleSettingOptionsCallback& callback -
Returns
 PossibleSettingOptionsHandle -
unsubscribe_possible_setting_options() ​
void mavsdk::Camera::unsubscribe_possible_setting_options(PossibleSettingOptionsHandle handle)
Unsubscribe from subscribe_possible_setting_options.
Parameters
- PossibleSettingOptionsHandle handle -
get_possible_setting_options() ​
std::pair< Result, std::vector< Camera::SettingOptions > > mavsdk::Camera::get_possible_setting_options(int32_t component_id) const
Get possible setting options.
This function is blocking.
Parameters
- int32_t component_id -
Returns
 std::pair< Result, std::vector< Camera::SettingOptions > > - Result of request.
set_setting_async() ​
void mavsdk::Camera::set_setting_async(int32_t component_id, 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
- int32_t component_id -
- Setting setting -
- const ResultCallback callback -
set_setting() ​
Result mavsdk::Camera::set_setting(int32_t component_id, 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
- int32_t component_id -
- Setting setting -
Returns
 Result - Result of request.
get_setting_async() ​
void mavsdk::Camera::get_setting_async(int32_t component_id, 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
- int32_t component_id -
- Setting setting -
- const GetSettingCallback callback -
get_setting() ​
std::pair< Result, Camera::Setting > mavsdk::Camera::get_setting(int32_t component_id, 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
- int32_t component_id -
- Setting setting -
Returns
 std::pair< Result, Camera::Setting > - Result of request.
format_storage_async() ​
void mavsdk::Camera::format_storage_async(int32_t component_id, 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
- int32_t component_id -
- int32_t storage_id -
- const ResultCallback callback -
format_storage() ​
Result mavsdk::Camera::format_storage(int32_t component_id, 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 component_id -
- int32_t storage_id -
Returns
 Result - Result of request.
reset_settings_async() ​
void mavsdk::Camera::reset_settings_async(int32_t component_id, 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
- int32_t component_id -
- const ResultCallback callback -
reset_settings() ​
Result mavsdk::Camera::reset_settings(int32_t component_id) 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.
Parameters
- int32_t component_id -
Returns
 Result - Result of request.
zoom_in_start_async() ​
void mavsdk::Camera::zoom_in_start_async(int32_t component_id, const ResultCallback callback)
Start zooming in.
This function is non-blocking. See 'zoom_in_start' for the blocking counterpart.
Parameters
- int32_t component_id -
- const ResultCallback callback -
zoom_in_start() ​
Result mavsdk::Camera::zoom_in_start(int32_t component_id) const
Start zooming in.
This function is blocking. See 'zoom_in_start_async' for the non-blocking counterpart.
Parameters
- int32_t component_id -
Returns
 Result - Result of request.
zoom_out_start_async() ​
void mavsdk::Camera::zoom_out_start_async(int32_t component_id, const ResultCallback callback)
Start zooming out.
This function is non-blocking. See 'zoom_out_start' for the blocking counterpart.
Parameters
- int32_t component_id -
- const ResultCallback callback -
zoom_out_start() ​
Result mavsdk::Camera::zoom_out_start(int32_t component_id) const
Start zooming out.
This function is blocking. See 'zoom_out_start_async' for the non-blocking counterpart.
Parameters
- int32_t component_id -
Returns
 Result - Result of request.
zoom_stop_async() ​
void mavsdk::Camera::zoom_stop_async(int32_t component_id, const ResultCallback callback)
Stop zooming.
This function is non-blocking. See 'zoom_stop' for the blocking counterpart.
Parameters
- int32_t component_id -
- const ResultCallback callback -
zoom_stop() ​
Result mavsdk::Camera::zoom_stop(int32_t component_id) const
Stop zooming.
This function is blocking. See 'zoom_stop_async' for the non-blocking counterpart.
Parameters
- int32_t component_id -
Returns
 Result - Result of request.
zoom_range_async() ​
void mavsdk::Camera::zoom_range_async(int32_t component_id, float range, const ResultCallback callback)
Zoom to value as proportion of full camera range (percentage between 0.0 and 100.0).
This function is non-blocking. See 'zoom_range' for the blocking counterpart.
Parameters
- int32_t component_id -
- float range -
- const ResultCallback callback -
zoom_range() ​
Result mavsdk::Camera::zoom_range(int32_t component_id, float range) const
Zoom to value as proportion of full camera range (percentage between 0.0 and 100.0).
This function is blocking. See 'zoom_range_async' for the non-blocking counterpart.
Parameters
- int32_t component_id -
- float range -
Returns
 Result - Result of request.
track_point_async() ​
void mavsdk::Camera::track_point_async(int32_t component_id, float point_x, float point_y, float radius, const ResultCallback callback)
Track point.
This function is non-blocking. See 'track_point' for the blocking counterpart.
Parameters
- int32_t component_id -
- float point_x -
- float point_y -
- float radius -
- const ResultCallback callback -
track_point() ​
Result mavsdk::Camera::track_point(int32_t component_id, float point_x, float point_y, float radius) const
Track point.
This function is blocking. See 'track_point_async' for the non-blocking counterpart.
Parameters
- int32_t component_id -
- float point_x -
- float point_y -
- float radius -
Returns
 Result - Result of request.
track_rectangle_async() ​
void mavsdk::Camera::track_rectangle_async(int32_t component_id, float top_left_x, float top_left_y, float bottom_right_x, float bottom_right_y, const ResultCallback callback)
Track rectangle.
This function is non-blocking. See 'track_rectangle' for the blocking counterpart.
Parameters
- int32_t component_id -
- float top_left_x -
- float top_left_y -
- float bottom_right_x -
- float bottom_right_y -
- const ResultCallback callback -
track_rectangle() ​
Result mavsdk::Camera::track_rectangle(int32_t component_id, float top_left_x, float top_left_y, float bottom_right_x, float bottom_right_y) const
Track rectangle.
This function is blocking. See 'track_rectangle_async' for the non-blocking counterpart.
Parameters
- int32_t component_id -
- float top_left_x -
- float top_left_y -
- float bottom_right_x -
- float bottom_right_y -
Returns
 Result - Result of request.
track_stop_async() ​
void mavsdk::Camera::track_stop_async(int32_t component_id, const ResultCallback callback)
Stop tracking.
This function is non-blocking. See 'track_stop' for the blocking counterpart.
Parameters
- int32_t component_id -
- const ResultCallback callback -
track_stop() ​
Result mavsdk::Camera::track_stop(int32_t component_id) const
Stop tracking.
This function is blocking. See 'track_stop_async' for the non-blocking counterpart.
Parameters
- int32_t component_id -
Returns
 Result - Result of request.
focus_in_start_async() ​
void mavsdk::Camera::focus_in_start_async(int32_t component_id, const ResultCallback callback)
Start focusing in.
This function is non-blocking. See 'focus_in_start' for the blocking counterpart.
Parameters
- int32_t component_id -
- const ResultCallback callback -
focus_in_start() ​
Result mavsdk::Camera::focus_in_start(int32_t component_id) const
Start focusing in.
This function is blocking. See 'focus_in_start_async' for the non-blocking counterpart.
Parameters
- int32_t component_id -
Returns
 Result - Result of request.
focus_out_start_async() ​
void mavsdk::Camera::focus_out_start_async(int32_t component_id, const ResultCallback callback)
Start focusing out.
This function is non-blocking. See 'focus_out_start' for the blocking counterpart.
Parameters
- int32_t component_id -
- const ResultCallback callback -
focus_out_start() ​
Result mavsdk::Camera::focus_out_start(int32_t component_id) const
Start focusing out.
This function is blocking. See 'focus_out_start_async' for the non-blocking counterpart.
Parameters
- int32_t component_id -
Returns
 Result - Result of request.
focus_stop_async() ​
void mavsdk::Camera::focus_stop_async(int32_t component_id, const ResultCallback callback)
Stop focus.
This function is non-blocking. See 'focus_stop' for the blocking counterpart.
Parameters
- int32_t component_id -
- const ResultCallback callback -
focus_stop() ​
Result mavsdk::Camera::focus_stop(int32_t component_id) const
Stop focus.
This function is blocking. See 'focus_stop_async' for the non-blocking counterpart.
Parameters
- int32_t component_id -
Returns
 Result - Result of request.
focus_range_async() ​
void mavsdk::Camera::focus_range_async(int32_t component_id, float range, const ResultCallback callback)
Focus with range value of full range (value between 0.0 and 100.0).
This function is non-blocking. See 'focus_range' for the blocking counterpart.
Parameters
- int32_t component_id -
- float range -
- const ResultCallback callback -
focus_range() ​
Result mavsdk::Camera::focus_range(int32_t component_id, float range) const
Focus with range value of full range (value between 0.0 and 100.0).
This function is blocking. See 'focus_range_async' for the non-blocking counterpart.
Parameters
- int32_t component_id -
- float range -
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 & -