mavsdk::CameraServer Class Reference

#include: camera_server.h


Provides handling of camera trigger commands.

Data Structures

struct CaptureInfo

struct Information

struct Position

struct Quaternion

Public Types

Type Description
enum TakePhotoFeedback Possible results when taking a photo.
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.

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_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.
void subscribe_take_photo (TakePhotoCallback callback) Subscribe to image capture requests. Each request received should respond to using RespondTakePhoto.
Result respond_take_photo (TakePhotoFeedback take_photo_feedback, CaptureInfo capture_info)const Respond to an image capture request from SubscribeTakePhoto.
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

  • std::shared_ptr< ServerComponent > server_component - The ServerComponent instance associated with this server plugin.

~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.

Member Enumeration Documentation

enum TakePhotoFeedback

Possible results when taking a photo.

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

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

void mavsdk::CameraServer::subscribe_take_photo(TakePhotoCallback callback)

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

Parameters

respond_take_photo()

Result mavsdk::CameraServer::respond_take_photo(TakePhotoFeedback 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.

operator=()

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

Equality operator (object is not copyable).

Parameters

Returns

 const CameraServer & -

© Dronecode 2017-2020. License: CC BY 4.0            Updated: 2022-05-26 20:06:59

results matching ""

    No results matching ""