mavsdk::Gimbal Class Reference
#include: gimbal.h
Provide control over a gimbal.
Data Structures
struct ControlStatus
Public Types
Type | Description |
---|---|
enum GimbalMode | Gimbal mode type. |
enum ControlMode | Control mode. |
enum Result | Possible results returned for gimbal commands. |
std::function< void(Result)> ResultCallback | Callback type for asynchronous Gimbal calls. |
std::function< void(ControlStatus)> ControlCallback | Callback type for subscribe_control. |
Handle< ControlStatus > ControlHandle | Handle type for subscribe_control. |
Public Member Functions
Type | Name | Description |
---|---|---|
Gimbal (System & system) | Constructor. Creates the plugin for a specific System. | |
Gimbal (std::shared_ptr< System > system) | Constructor. Creates the plugin for a specific System. | |
~Gimbal () override | Destructor (internal use only). | |
Gimbal (const Gimbal & other) | Copy constructor. | |
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_pitch_rate_and_yaw_rate_async (float pitch_rate_deg_s, float yaw_rate_deg_s, const ResultCallback callback) | Set gimbal angular rates around pitch and yaw axes. |
Result | set_pitch_rate_and_yaw_rate (float pitch_rate_deg_s, float yaw_rate_deg_s)const | Set gimbal angular rates around pitch and yaw axes. |
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). |
void | take_control_async (ControlMode control_mode, const ResultCallback callback) | Take control. |
Result | take_control (ControlMode control_mode)const | Take control. |
void | release_control_async (const ResultCallback callback) | Release control. |
Result | release_control () const | Release control. |
ControlHandle | subscribe_control (const ControlCallback & callback) | Subscribe to control status updates. |
void | unsubscribe_control (ControlHandle handle) | Unsubscribe from subscribe_control. |
ControlStatus | control () const | Poll for 'ControlStatus' (blocking). |
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 = Gimbal(system);
Parameters
- System& system - The specific system associated with this plugin.
Gimbal()
mavsdk::Gimbal::Gimbal(std::shared_ptr< System > system)
Constructor. Creates the plugin for a specific System.
The plugin is typically created as shown below:
auto gimbal = Gimbal(system);
Parameters
- std::shared_ptr< System > system - The specific system associated with this plugin.
~Gimbal()
mavsdk::Gimbal::~Gimbal() override
Destructor (internal use only).
Gimbal()
mavsdk::Gimbal::Gimbal(const Gimbal &other)
Copy constructor.
Parameters
- const Gimbal& other -
Member Typdef Documentation
typedef ResultCallback
using mavsdk::Gimbal::ResultCallback = std::function<void(Result)>
Callback type for asynchronous Gimbal calls.
typedef ControlCallback
using mavsdk::Gimbal::ControlCallback = std::function<void(ControlStatus)>
Callback type for subscribe_control.
typedef ControlHandle
using mavsdk::Gimbal::ControlHandle = Handle<ControlStatus>
Handle type for subscribe_control.
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 pointing to an absolute direction. |
enum ControlMode
Control mode.
Value | Description |
---|---|
None |
Indicates that the component does not have control over the gimbal. |
Primary |
To take primary control over the gimbal. |
Secondary |
To take secondary control over the gimbal. |
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. |
Unsupported |
Functionality not supported. |
NoSystem |
No system connected. |
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_pitch_rate_and_yaw_rate_async()
void mavsdk::Gimbal::set_pitch_rate_and_yaw_rate_async(float pitch_rate_deg_s, float yaw_rate_deg_s, const ResultCallback callback)
Set gimbal angular rates around pitch and yaw axes.
This sets the desired angular rates around pitch and yaw axes of a gimbal. Will return when the command is accepted, however, it might take the gimbal longer to actually reach the angular rate.
This function is non-blocking. See 'set_pitch_rate_and_yaw_rate' for the blocking counterpart.
Parameters
- float pitch_rate_deg_s -
- float yaw_rate_deg_s -
- const ResultCallback callback -
set_pitch_rate_and_yaw_rate()
Result mavsdk::Gimbal::set_pitch_rate_and_yaw_rate(float pitch_rate_deg_s, float yaw_rate_deg_s) const
Set gimbal angular rates around pitch and yaw axes.
This sets the desired angular rates around pitch and yaw axes of a gimbal. Will return when the command is accepted, however, it might take the gimbal longer to actually reach the angular rate.
This function is blocking. See 'set_pitch_rate_and_yaw_rate_async' for the non-blocking counterpart.
Parameters
- float pitch_rate_deg_s -
- float yaw_rate_deg_s -
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.
take_control_async()
void mavsdk::Gimbal::take_control_async(ControlMode control_mode, const ResultCallback callback)
Take control.
There can be only two components in control of a gimbal at any given time. One with "primary" control, and one with "secondary" control. The way the secondary control is implemented is not specified and hence depends on the vehicle.
Components are expected to be cooperative, which means that they can override each other and should therefore do it carefully.
This function is non-blocking. See 'take_control' for the blocking counterpart.
Parameters
- ControlMode control_mode -
- const ResultCallback callback -
take_control()
Result mavsdk::Gimbal::take_control(ControlMode control_mode) const
Take control.
There can be only two components in control of a gimbal at any given time. One with "primary" control, and one with "secondary" control. The way the secondary control is implemented is not specified and hence depends on the vehicle.
Components are expected to be cooperative, which means that they can override each other and should therefore do it carefully.
This function is blocking. See 'take_control_async' for the non-blocking counterpart.
Parameters
- ControlMode control_mode -
Returns
Result - Result of request.
release_control_async()
void mavsdk::Gimbal::release_control_async(const ResultCallback callback)
Release control.
Release control, such that other components can control the gimbal.
This function is non-blocking. See 'release_control' for the blocking counterpart.
Parameters
- const ResultCallback callback -
release_control()
Result mavsdk::Gimbal::release_control() const
Release control.
Release control, such that other components can control the gimbal.
This function is blocking. See 'release_control_async' for the non-blocking counterpart.
Returns
Result - Result of request.
subscribe_control()
ControlHandle mavsdk::Gimbal::subscribe_control(const ControlCallback &callback)
Subscribe to control status updates.
This allows a component to know if it has primary, secondary or no control over the gimbal. Also, it gives the system and component ids of the other components in control (if any).
Parameters
- const ControlCallback& callback -
Returns
unsubscribe_control()
void mavsdk::Gimbal::unsubscribe_control(ControlHandle handle)
Unsubscribe from subscribe_control.
Parameters
- ControlHandle handle -
control()
ControlStatus mavsdk::Gimbal::control() const
Poll for 'ControlStatus' (blocking).
Returns
ControlStatus - One ControlStatus update.
operator=()
const Gimbal& mavsdk::Gimbal::operator=(const Gimbal &)=delete
Equality operator (object is not copyable).
Parameters
- const Gimbal& -
Returns
const Gimbal & -