mavsdk::Gimbal Class Reference
#include: gimbal.h
Provide control over a gimbal.
Public Types
Type | Description |
---|---|
enum GimbalMode | Gimbal mode type. |
enum Result | Possible results returned for gimbal commands. |
std::function< void(Result)> ResultCallback | 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). | |
void | set_pitch_and_yaw_async (float pitch_deg, float yaw_deg, const ResultCallback callback) | Set gimbal pitch and yaw angles. |
Result | set_pitch_and_yaw (float pitch_deg, float yaw_deg)const | Set gimbal pitch and yaw angles. |
void | set_mode_async (GimbalMode gimbal_mode, const ResultCallback callback) | Set gimbal mode. |
Result | set_mode (GimbalMode gimbal_mode)const | Set gimbal mode. |
void | set_roi_location_async (double latitude_deg, double longitude_deg, float altitude_m, const ResultCallback callback) | Set gimbal region of interest (ROI). |
Result | set_roi_location (double latitude_deg, double longitude_deg, float altitude_m)const | Set gimbal region of interest (ROI). |
const Gimbal & | operator= (const Gimbal &)=delete | Equality operator (object is not copyable). |
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
- const Gimbal& -
Member Typdef Documentation
typedef ResultCallback
using mavsdk::Gimbal::ResultCallback = std::function<void(Result)>
Callback type for asynchronous Gimbal calls.
Member Enumeration Documentation
enum GimbalMode
Gimbal mode type.
Value | Description |
---|---|
YawFollow |
Yaw follow will point the gimbal to the vehicle heading. |
YawLock |
Yaw lock will fix the gimbal poiting to an absolute direction. |
enum Result
Possible results returned for gimbal commands.
Value | Description |
---|---|
Unknown |
Unknown result. |
Success |
Command was accepted. |
Error |
Error occurred sending the command. |
Timeout |
Command timed out. |
Member Function Documentation
set_pitch_and_yaw_async()
void mavsdk::Gimbal::set_pitch_and_yaw_async(float pitch_deg, float yaw_deg, const ResultCallback callback)
Set gimbal pitch and yaw angles.
This sets the desired pitch and yaw angles of a gimbal. Will return when the command is accepted, however, it might take the gimbal longer to actually be set to the new angles.
This function is non-blocking. See 'set_pitch_and_yaw' for the blocking counterpart.
Parameters
- float pitch_deg -
- float yaw_deg -
- const ResultCallback callback -
set_pitch_and_yaw()
Result mavsdk::Gimbal::set_pitch_and_yaw(float pitch_deg, float yaw_deg) const
Set gimbal pitch and yaw angles.
This sets the desired pitch and yaw angles of a gimbal. Will return when the command is accepted, however, it might take the gimbal longer to actually be set to the new angles.
This function is blocking. See 'set_pitch_and_yaw_async' for the non-blocking counterpart.
Parameters
- float pitch_deg -
- float yaw_deg -
Returns
Result - Result of request.
set_mode_async()
void mavsdk::Gimbal::set_mode_async(GimbalMode gimbal_mode, const ResultCallback callback)
Set gimbal mode.
This sets the desired yaw mode of a gimbal. Will return when the command is accepted. However, it might take the gimbal longer to actually be set to the new angles.
This function is non-blocking. See 'set_mode' for the blocking counterpart.
Parameters
- GimbalMode gimbal_mode -
- const ResultCallback callback -
set_mode()
Result mavsdk::Gimbal::set_mode(GimbalMode gimbal_mode) const
Set gimbal mode.
This sets the desired yaw mode of a gimbal. Will return when the command is accepted. However, it might take the gimbal longer to actually be set to the new angles.
This function is blocking. See 'set_mode_async' for the non-blocking counterpart.
Parameters
- GimbalMode gimbal_mode -
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, const ResultCallback callback)
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.
This function is non-blocking. See 'set_roi_location' for the blocking counterpart.
Parameters
- double latitude_deg -
- double longitude_deg -
- float altitude_m -
- const ResultCallback callback -
set_roi_location()
Result mavsdk::Gimbal::set_roi_location(double latitude_deg, double longitude_deg, float altitude_m) const
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.
This function is blocking. See 'set_roi_location_async' for the non-blocking counterpart.
Parameters
- double latitude_deg -
- double longitude_deg -
- float altitude_m -
Returns
Result - Result of request.
operator=()
const Gimbal& mavsdk::Gimbal::operator=(const Gimbal &)=delete
Equality operator (object is not copyable).
Parameters
- const Gimbal& -
Returns
const Gimbal & -