mavsdk::CameraServer Class Reference

#include: camera_server.h


Provides handling of camera trigger commands.

Data Structures

struct CaptureInfo

struct CaptureStatus

struct Information

struct Position

struct Quaternion

struct StorageInformation

struct VideoStreaming

Public Types

Type Description
enum CameraFeedback Possible feedback results for camera respond command.
enum Mode Camera mode type.
enum Result Possible results returned for action requests.
std::function< void(Result)> ResultCallback Callback type for asynchronous CameraServer calls.
std::function< void(int32_t)> TakePhotoCallback Callback type for subscribe_take_photo.
Handle< int32_t > TakePhotoHandle Handle type for subscribe_take_photo.
std::function< void(int32_t)> StartVideoCallback Callback type for subscribe_start_video.
Handle< int32_t > StartVideoHandle Handle type for subscribe_start_video.
std::function< void(int32_t)> StopVideoCallback Callback type for subscribe_stop_video.
Handle< int32_t > StopVideoHandle Handle type for subscribe_stop_video.
std::function< void(int32_t)> StartVideoStreamingCallback Callback type for subscribe_start_video_streaming.
Handle< int32_t > StartVideoStreamingHandle Handle type for subscribe_start_video_streaming.
std::function< void(int32_t)> StopVideoStreamingCallback Callback type for subscribe_stop_video_streaming.
Handle< int32_t > StopVideoStreamingHandle Handle type for subscribe_stop_video_streaming.
std::function< void(Mode)> SetModeCallback Callback type for subscribe_set_mode.
Handle< Mode > SetModeHandle Handle type for subscribe_set_mode.
std::function< void(int32_t)> StorageInformationCallback Callback type for subscribe_storage_information.
Handle< int32_t > StorageInformationHandle Handle type for subscribe_storage_information.
std::function< void(int32_t)> CaptureStatusCallback Callback type for subscribe_capture_status.
Handle< int32_t > CaptureStatusHandle Handle type for subscribe_capture_status.
std::function< void(int32_t)> FormatStorageCallback Callback type for subscribe_format_storage.
Handle< int32_t > FormatStorageHandle Handle type for subscribe_format_storage.
std::function< void(int32_t)> ResetSettingsCallback Callback type for subscribe_reset_settings.
Handle< int32_t > ResetSettingsHandle Handle type for subscribe_reset_settings.

Public Member Functions

Type Name Description
  CameraServer (std::shared_ptr< ServerComponent > server_component) Constructor. Creates the plugin for a ServerComponent instance.
  ~CameraServer () override Destructor (internal use only).
  CameraServer (const CameraServer & other) Copy constructor.
Result set_information (Information information)const Sets the camera information. This must be called as soon as the camera server is created.
Result set_video_streaming (VideoStreaming video_streaming)const Sets video streaming settings.
Result set_in_progress (bool in_progress)const Sets image capture in progress status flags. This should be set to true when the camera is busy taking a photo and false when it is done.
TakePhotoHandle subscribe_take_photo (const TakePhotoCallback & callback) Subscribe to image capture requests. Each request received should respond to using RespondTakePhoto.
void unsubscribe_take_photo (TakePhotoHandle handle) Unsubscribe from subscribe_take_photo.
Result respond_take_photo (CameraFeedback take_photo_feedback, CaptureInfo capture_info)const Respond to an image capture request from SubscribeTakePhoto.
StartVideoHandle subscribe_start_video (const StartVideoCallback & callback) Subscribe to start video requests. Each request received should respond to using RespondStartVideo.
void unsubscribe_start_video (StartVideoHandle handle) Unsubscribe from subscribe_start_video.
Result respond_start_video (CameraFeedback start_video_feedback)const Subscribe to stop video requests. Each request received should respond using StopVideoResponse.
StopVideoHandle subscribe_stop_video (const StopVideoCallback & callback) Subscribe to stop video requests. Each request received should response to using RespondStopVideo.
void unsubscribe_stop_video (StopVideoHandle handle) Unsubscribe from subscribe_stop_video.
Result respond_stop_video (CameraFeedback stop_video_feedback)const Respond to stop video request from SubscribeStopVideo.
StartVideoStreamingHandle subscribe_start_video_streaming (const StartVideoStreamingCallback & callback) Subscribe to start video streaming requests. Each request received should response to using RespondStartVideoStreaming.
void unsubscribe_start_video_streaming (StartVideoStreamingHandle handle) Unsubscribe from subscribe_start_video_streaming.
Result respond_start_video_streaming (CameraFeedback start_video_streaming_feedback)const Respond to start video streaming from SubscribeStartVideoStreaming.
StopVideoStreamingHandle subscribe_stop_video_streaming (const StopVideoStreamingCallback & callback) Subscribe to stop video streaming requests. Each request received should response to using RespondStopVideoStreaming.
void unsubscribe_stop_video_streaming (StopVideoStreamingHandle handle) Unsubscribe from subscribe_stop_video_streaming.
Result respond_stop_video_streaming (CameraFeedback stop_video_streaming_feedback)const Respond to stop video streaming from SubscribeStopVideoStreaming.
SetModeHandle subscribe_set_mode (const SetModeCallback & callback) Subscribe to set camera mode requests. Each request received should response to using RespondSetMode.
void unsubscribe_set_mode (SetModeHandle handle) Unsubscribe from subscribe_set_mode.
Result respond_set_mode (CameraFeedback set_mode_feedback)const Respond to set camera mode from SubscribeSetMode.
StorageInformationHandle subscribe_storage_information (const StorageInformationCallback & callback) Subscribe to camera storage information requests. Each request received should response to using RespondStorageInformation.
void unsubscribe_storage_information (StorageInformationHandle handle) Unsubscribe from subscribe_storage_information.
Result respond_storage_information (CameraFeedback storage_information_feedback, StorageInformation storage_information)const Respond to camera storage information from SubscribeStorageInformation.
CaptureStatusHandle subscribe_capture_status (const CaptureStatusCallback & callback) Subscribe to camera capture status requests. Each request received should response to using RespondCaptureStatus.
void unsubscribe_capture_status (CaptureStatusHandle handle) Unsubscribe from subscribe_capture_status.
Result respond_capture_status (CameraFeedback capture_status_feedback, CaptureStatus capture_status)const Respond to camera capture status from SubscribeCaptureStatus.
FormatStorageHandle subscribe_format_storage (const FormatStorageCallback & callback) Subscribe to format storage requests. Each request received should response to using RespondFormatStorage.
void unsubscribe_format_storage (FormatStorageHandle handle) Unsubscribe from subscribe_format_storage.
Result respond_format_storage (CameraFeedback format_storage_feedback)const Respond to format storage from SubscribeFormatStorage.
ResetSettingsHandle subscribe_reset_settings (const ResetSettingsCallback & callback) Subscribe to reset settings requests. Each request received should response to using RespondResetSettings.
void unsubscribe_reset_settings (ResetSettingsHandle handle) Unsubscribe from subscribe_reset_settings.
Result respond_reset_settings (CameraFeedback reset_settings_feedback)const Respond to reset settings from SubscribeResetSettings.
const CameraServer & operator= (const CameraServer &)=delete Equality operator (object is not copyable).

Constructor & Destructor Documentation

CameraServer()

mavsdk::CameraServer::CameraServer(std::shared_ptr< ServerComponent > server_component)

Constructor. Creates the plugin for a ServerComponent instance.

The plugin is typically created as shown below:

auto camera_server = CameraServer(server_component);

Parameters

~CameraServer()

mavsdk::CameraServer::~CameraServer() override

Destructor (internal use only).

CameraServer()

mavsdk::CameraServer::CameraServer(const CameraServer &other)

Copy constructor.

Parameters

Member Typdef Documentation

typedef ResultCallback

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

Callback type for asynchronous CameraServer calls.

typedef TakePhotoCallback

using mavsdk::CameraServer::TakePhotoCallback =  std::function<void(int32_t)>

Callback type for subscribe_take_photo.

typedef TakePhotoHandle

using mavsdk::CameraServer::TakePhotoHandle =  Handle<int32_t>

Handle type for subscribe_take_photo.

typedef StartVideoCallback

using mavsdk::CameraServer::StartVideoCallback =  std::function<void(int32_t)>

Callback type for subscribe_start_video.

typedef StartVideoHandle

using mavsdk::CameraServer::StartVideoHandle =  Handle<int32_t>

Handle type for subscribe_start_video.

typedef StopVideoCallback

using mavsdk::CameraServer::StopVideoCallback =  std::function<void(int32_t)>

Callback type for subscribe_stop_video.

typedef StopVideoHandle

using mavsdk::CameraServer::StopVideoHandle =  Handle<int32_t>

Handle type for subscribe_stop_video.

typedef StartVideoStreamingCallback

using mavsdk::CameraServer::StartVideoStreamingCallback =  std::function<void(int32_t)>

Callback type for subscribe_start_video_streaming.

typedef StartVideoStreamingHandle

using mavsdk::CameraServer::StartVideoStreamingHandle =  Handle<int32_t>

Handle type for subscribe_start_video_streaming.

typedef StopVideoStreamingCallback

using mavsdk::CameraServer::StopVideoStreamingCallback =  std::function<void(int32_t)>

Callback type for subscribe_stop_video_streaming.

typedef StopVideoStreamingHandle

using mavsdk::CameraServer::StopVideoStreamingHandle =  Handle<int32_t>

Handle type for subscribe_stop_video_streaming.

typedef SetModeCallback

using mavsdk::CameraServer::SetModeCallback =  std::function<void(Mode)>

Callback type for subscribe_set_mode.

typedef SetModeHandle

using mavsdk::CameraServer::SetModeHandle =  Handle<Mode>

Handle type for subscribe_set_mode.

typedef StorageInformationCallback

using mavsdk::CameraServer::StorageInformationCallback =  std::function<void(int32_t)>

Callback type for subscribe_storage_information.

typedef StorageInformationHandle

using mavsdk::CameraServer::StorageInformationHandle =  Handle<int32_t>

Handle type for subscribe_storage_information.

typedef CaptureStatusCallback

using mavsdk::CameraServer::CaptureStatusCallback =  std::function<void(int32_t)>

Callback type for subscribe_capture_status.

typedef CaptureStatusHandle

using mavsdk::CameraServer::CaptureStatusHandle =  Handle<int32_t>

Handle type for subscribe_capture_status.

typedef FormatStorageCallback

using mavsdk::CameraServer::FormatStorageCallback =  std::function<void(int32_t)>

Callback type for subscribe_format_storage.

typedef FormatStorageHandle

using mavsdk::CameraServer::FormatStorageHandle =  Handle<int32_t>

Handle type for subscribe_format_storage.

typedef ResetSettingsCallback

using mavsdk::CameraServer::ResetSettingsCallback =  std::function<void(int32_t)>

Callback type for subscribe_reset_settings.

typedef ResetSettingsHandle

using mavsdk::CameraServer::ResetSettingsHandle =  Handle<int32_t>

Handle type for subscribe_reset_settings.

Member Enumeration Documentation

enum CameraFeedback

Possible feedback results for camera respond command.

Value Description
Unknown Unknown.
Ok Ok.
Busy Busy.
Failed Failed.

enum Mode

Camera mode type.

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

enum Result

Possible results returned for action requests.

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.

Member Function Documentation

set_information()

Result mavsdk::CameraServer::set_information(Information information) const

Sets the camera information. This must be called as soon as the camera server is created.

This function is blocking.

Parameters

Returns

Result - Result of request.

set_video_streaming()

Result mavsdk::CameraServer::set_video_streaming(VideoStreaming video_streaming) const

Sets video streaming settings.

This function is blocking.

Parameters

Returns

Result - Result of request.

set_in_progress()

Result mavsdk::CameraServer::set_in_progress(bool in_progress) const

Sets image capture in progress status flags. This should be set to true when the camera is busy taking a photo and false when it is done.

This function is blocking.

Parameters

  • bool in_progress -

Returns

Result - Result of request.

subscribe_take_photo()

TakePhotoHandle mavsdk::CameraServer::subscribe_take_photo(const TakePhotoCallback &callback)

Subscribe to image capture requests. Each request received should respond to using RespondTakePhoto.

Parameters

Returns

TakePhotoHandle -

unsubscribe_take_photo()

void mavsdk::CameraServer::unsubscribe_take_photo(TakePhotoHandle handle)

Unsubscribe from subscribe_take_photo.

Parameters

respond_take_photo()

Result mavsdk::CameraServer::respond_take_photo(CameraFeedback take_photo_feedback, CaptureInfo capture_info) const

Respond to an image capture request from SubscribeTakePhoto.

This function is blocking.

Parameters

Returns

Result - Result of request.

subscribe_start_video()

StartVideoHandle mavsdk::CameraServer::subscribe_start_video(const StartVideoCallback &callback)

Subscribe to start video requests. Each request received should respond to using RespondStartVideo.

Parameters

Returns

StartVideoHandle -

unsubscribe_start_video()

void mavsdk::CameraServer::unsubscribe_start_video(StartVideoHandle handle)

Unsubscribe from subscribe_start_video.

Parameters

respond_start_video()

Result mavsdk::CameraServer::respond_start_video(CameraFeedback start_video_feedback) const

Subscribe to stop video requests. Each request received should respond using StopVideoResponse.

This function is blocking.

Parameters

Returns

Result - Result of request.

subscribe_stop_video()

StopVideoHandle mavsdk::CameraServer::subscribe_stop_video(const StopVideoCallback &callback)

Subscribe to stop video requests. Each request received should response to using RespondStopVideo.

Parameters

Returns

StopVideoHandle -

unsubscribe_stop_video()

void mavsdk::CameraServer::unsubscribe_stop_video(StopVideoHandle handle)

Unsubscribe from subscribe_stop_video.

Parameters

respond_stop_video()

Result mavsdk::CameraServer::respond_stop_video(CameraFeedback stop_video_feedback) const

Respond to stop video request from SubscribeStopVideo.

This function is blocking.

Parameters

Returns

Result - Result of request.

subscribe_start_video_streaming()

StartVideoStreamingHandle mavsdk::CameraServer::subscribe_start_video_streaming(const StartVideoStreamingCallback &callback)

Subscribe to start video streaming requests. Each request received should response to using RespondStartVideoStreaming.

Parameters

Returns

StartVideoStreamingHandle -

unsubscribe_start_video_streaming()

void mavsdk::CameraServer::unsubscribe_start_video_streaming(StartVideoStreamingHandle handle)

Unsubscribe from subscribe_start_video_streaming.

Parameters

respond_start_video_streaming()

Result mavsdk::CameraServer::respond_start_video_streaming(CameraFeedback start_video_streaming_feedback) const

Respond to start video streaming from SubscribeStartVideoStreaming.

This function is blocking.

Parameters

Returns

Result - Result of request.

subscribe_stop_video_streaming()

StopVideoStreamingHandle mavsdk::CameraServer::subscribe_stop_video_streaming(const StopVideoStreamingCallback &callback)

Subscribe to stop video streaming requests. Each request received should response to using RespondStopVideoStreaming.

Parameters

Returns

StopVideoStreamingHandle -

unsubscribe_stop_video_streaming()

void mavsdk::CameraServer::unsubscribe_stop_video_streaming(StopVideoStreamingHandle handle)

Unsubscribe from subscribe_stop_video_streaming.

Parameters

respond_stop_video_streaming()

Result mavsdk::CameraServer::respond_stop_video_streaming(CameraFeedback stop_video_streaming_feedback) const

Respond to stop video streaming from SubscribeStopVideoStreaming.

This function is blocking.

Parameters

Returns

Result - Result of request.

subscribe_set_mode()

SetModeHandle mavsdk::CameraServer::subscribe_set_mode(const SetModeCallback &callback)

Subscribe to set camera mode requests. Each request received should response to using RespondSetMode.

Parameters

Returns

SetModeHandle -

unsubscribe_set_mode()

void mavsdk::CameraServer::unsubscribe_set_mode(SetModeHandle handle)

Unsubscribe from subscribe_set_mode.

Parameters

respond_set_mode()

Result mavsdk::CameraServer::respond_set_mode(CameraFeedback set_mode_feedback) const

Respond to set camera mode from SubscribeSetMode.

This function is blocking.

Parameters

Returns

Result - Result of request.

subscribe_storage_information()

StorageInformationHandle mavsdk::CameraServer::subscribe_storage_information(const StorageInformationCallback &callback)

Subscribe to camera storage information requests. Each request received should response to using RespondStorageInformation.

Parameters

Returns

StorageInformationHandle -

unsubscribe_storage_information()

void mavsdk::CameraServer::unsubscribe_storage_information(StorageInformationHandle handle)

Unsubscribe from subscribe_storage_information.

Parameters

respond_storage_information()

Result mavsdk::CameraServer::respond_storage_information(CameraFeedback storage_information_feedback, StorageInformation storage_information) const

Respond to camera storage information from SubscribeStorageInformation.

This function is blocking.

Parameters

Returns

Result - Result of request.

subscribe_capture_status()

CaptureStatusHandle mavsdk::CameraServer::subscribe_capture_status(const CaptureStatusCallback &callback)

Subscribe to camera capture status requests. Each request received should response to using RespondCaptureStatus.

Parameters

Returns

CaptureStatusHandle -

unsubscribe_capture_status()

void mavsdk::CameraServer::unsubscribe_capture_status(CaptureStatusHandle handle)

Unsubscribe from subscribe_capture_status.

Parameters

respond_capture_status()

Result mavsdk::CameraServer::respond_capture_status(CameraFeedback capture_status_feedback, CaptureStatus capture_status) const

Respond to camera capture status from SubscribeCaptureStatus.

This function is blocking.

Parameters

Returns

Result - Result of request.

subscribe_format_storage()

FormatStorageHandle mavsdk::CameraServer::subscribe_format_storage(const FormatStorageCallback &callback)

Subscribe to format storage requests. Each request received should response to using RespondFormatStorage.

Parameters

Returns

FormatStorageHandle -

unsubscribe_format_storage()

void mavsdk::CameraServer::unsubscribe_format_storage(FormatStorageHandle handle)

Unsubscribe from subscribe_format_storage.

Parameters

respond_format_storage()

Result mavsdk::CameraServer::respond_format_storage(CameraFeedback format_storage_feedback) const

Respond to format storage from SubscribeFormatStorage.

This function is blocking.

Parameters

Returns

Result - Result of request.

subscribe_reset_settings()

ResetSettingsHandle mavsdk::CameraServer::subscribe_reset_settings(const ResetSettingsCallback &callback)

Subscribe to reset settings requests. Each request received should response to using RespondResetSettings.

Parameters

Returns

ResetSettingsHandle -

unsubscribe_reset_settings()

void mavsdk::CameraServer::unsubscribe_reset_settings(ResetSettingsHandle handle)

Unsubscribe from subscribe_reset_settings.

Parameters

respond_reset_settings()

Result mavsdk::CameraServer::respond_reset_settings(CameraFeedback reset_settings_feedback) const

Respond to reset settings from SubscribeResetSettings.

This function is blocking.

Parameters

Returns

Result - Result of request.

operator=()

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

Equality operator (object is not copyable).

Parameters

Returns

 const CameraServer & -

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

results matching ""

    No results matching ""