mavsdk::Gimbal Class Reference

#include: gimbal.h


The Gimbal class provides control over a gimbal.

Synchronous and asynchronous variants of the gimbal methods are supplied.

Public Types

Type Description
enum Result Possible results returned for gimbal commands.
enum GimbalMode Gimbal mode type.
std::function< void(Result)> result_callback_t Callback type for asynchronous Gimbal calls.

Public Member Functions

Type Name Description
  Gimbal (System & system) Constructor. Creates the plugin for a specific System.
  ~Gimbal () Destructor (internal use only).
  Gimbal (const Gimbal &)=delete Copy constructor (object is not copyable).
Result set_pitch_and_yaw (float pitch_deg, float yaw_deg) Set gimbal pitch and yaw angles (synchronous).
void set_pitch_and_yaw_async (float pitch_deg, float yaw_deg, result_callback_t callback) Set gimbal pitch and yaw angles (asynchronous).
Result set_gimbal_mode (const Gimbal::GimbalMode gimbal_mode) Set gimbal mode (synchronous).
void set_gimbal_mode_async (const Gimbal::GimbalMode gimbal_mode, result_callback_t callback) Set gimbal mode (asynchronous).
Result set_roi_location (double latitude_deg, double longitude_deg, float altitude_m) Set gimbal region of interest (ROI).
void set_roi_location_async (double latitude_deg, double longitude_deg, float altitude_m, result_callback_t callback) Set gimbal region of interest (ROI) (asynchronous).
const Gimbal & operator= (const Gimbal &)=delete Equality operator (object is not copyable).

Static Public Member Functions

Type Name Description
const char * result_str (Result result) Returns a human-readable English string for Gimbal::Result.

Constructor & Destructor Documentation

Gimbal()

mavsdk::Gimbal::Gimbal(System &system)

Constructor. Creates the plugin for a specific System.

The plugin is typically created as shown below:

auto gimbal = std::make_shared<Gimbal>(system);

Parameters

  • System& system - The specific system associated with this plugin.

~Gimbal()

mavsdk::Gimbal::~Gimbal()

Destructor (internal use only).

Gimbal()

mavsdk::Gimbal::Gimbal(const Gimbal &)=delete

Copy constructor (object is not copyable).

Parameters

Member Typdef Documentation

typedef result_callback_t

typedef std::function<void(Result)> mavsdk::Gimbal::result_callback_t

Callback type for asynchronous Gimbal calls.

Member Enumeration Documentation

enum Result

Possible results returned for gimbal commands.

Value Description
SUCCESS Success. The gimbal command was accepted.
ERROR Error. An error occured sending the command.
TIMEOUT Timeout. A timeout occured sending the command.
UNKNOWN Unspecified error.

enum GimbalMode

Gimbal mode type.

Value Description
YAW_FOLLOW Yaw follow mode.
YAW_LOCK Yaw lock mode.

Member Function Documentation

set_pitch_and_yaw()

Result mavsdk::Gimbal::set_pitch_and_yaw(float pitch_deg, float yaw_deg)

Set gimbal pitch and yaw angles (synchronous).

This sets the desired pitch and yaw angles of a gimbal. The function will return when the command is accepted, however, it might take the gimbal longer to actually be set to the new angles.

Parameters

  • float pitch_deg - The pitch angle in degrees. Negative to point down.
  • float yaw_deg - The yaw angle in degrees. Positive for clock-wise, range -180..180 or 0..360. The yaw angle is relative to vehicle heading if the GimbalMode is YAW_FOLLOW and relative to absolute North if the GimbalMode is YAW_LOCK.

Returns

Result - Result of request.

set_pitch_and_yaw_async()

void mavsdk::Gimbal::set_pitch_and_yaw_async(float pitch_deg, float yaw_deg, result_callback_t callback)

Set gimbal pitch and yaw angles (asynchronous).

This sets the desired pitch and yaw angles of a gimbal. The callback will be called when the command is accepted, however, it might take the gimbal longer to actually be set to the new angles.

Parameters

  • float pitch_deg - The pitch angle in degrees. Negative to point down.
  • float yaw_deg - The yaw angle in degrees. Positive for clock-wise, range -180..180 or 0..360. The yaw angle is relative to vehicle heading if the GimbalMode is YAW_FOLLOW and relative to absolute North if the GimbalMode is YAW_LOCK.
  • result_callback_t callback - Function to call with result of request.

set_gimbal_mode()

Result mavsdk::Gimbal::set_gimbal_mode(const Gimbal::GimbalMode gimbal_mode)

Set gimbal mode (synchronous).

This sets the desired yaw mode of a gimbal. The function will return when the command is accepted, however, it might take the gimbal longer to actually be set to the new angles.

Parameters

  • const Gimbal::GimbalMode gimbal_mode - The mode to be set. Either yaw lock or yaw follow. Yaw lock will fix the gimbal poiting to an absolute direction. Yaw follow will point the gimbal to the vehicle heading.

Returns

Result - Result of request.

set_gimbal_mode_async()

void mavsdk::Gimbal::set_gimbal_mode_async(const Gimbal::GimbalMode gimbal_mode, result_callback_t callback)

Set gimbal mode (asynchronous).

This sets the desired yaw mode of a gimbal. The function will return when the command is accepted, however, it might take the gimbal longer to actually be set to the new angles.

Parameters

  • const Gimbal::GimbalMode gimbal_mode - The mode to be set. Either yaw lock or yaw follow. Yaw lock will fix the gimbal poiting to an absolute direction. Yaw follow will point the gimbal to the vehicle heading.
  • result_callback_t callback - Function to call with result of request.

set_roi_location()

Result mavsdk::Gimbal::set_roi_location(double latitude_deg, double longitude_deg, float altitude_m)

Set gimbal region of interest (ROI).

This sets a region of interest that the gimbal will point to. The gimbal will continue to point to the specified region until it receives a new command. The function will return when the command is accepted, however, it might take the gimbal longer to actually rotate to the ROI.

Parameters

  • double latitude_deg - Latitude in degrees.
  • double longitude_deg - Longitude in degrees.
  • float altitude_m - Altitude in meters (ASML).

Returns

Result - Result of request.

set_roi_location_async()

void mavsdk::Gimbal::set_roi_location_async(double latitude_deg, double longitude_deg, float altitude_m, result_callback_t callback)

Set gimbal region of interest (ROI) (asynchronous).

This sets a region of interest that the gimbal will point to. The gimbal will continue to point to the specified region until it receives a new command. The callback will be called when the command is accepted, however, it might take the gimbal longer to actually be set to the new angles.

Parameters

  • double latitude_deg - Latitude in degrees.
  • double longitude_deg - Longitude in degrees.
  • float altitude_m - Altitude in meters (ASML).
  • result_callback_t callback - Function to call with result of request.

operator=()

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

Equality operator (object is not copyable).

Parameters

Returns

 const Gimbal & -

result_str()

static const char* mavsdk::Gimbal::result_str(Result result)

Returns a human-readable English string for Gimbal::Result.

Parameters

  • Result result - The enum value for which a human readable string is required.

Returns

 const char * - Human readable string for the Gimbal::Result.

© Dronecode 2017-2019. License: CC BY 4.0            Updated: 2019-11-05 22:27:07

results matching ""

    No results matching ""