Gimbal¶
-
class
mavsdk.gimbal.
ControlMode
(value)¶ Bases:
enum.Enum
Control mode
- 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
-
NONE
= 0¶
-
PRIMARY
= 1¶
-
SECONDARY
= 2¶
-
class
mavsdk.gimbal.
ControlStatus
(control_mode, sysid_primary_control, compid_primary_control, sysid_secondary_control, compid_secondary_control)¶ Bases:
object
Control status
- Parameters
control_mode (ControlMode) – Control mode (none, primary or secondary)
sysid_primary_control (int32_t) – Sysid of the component that has primary control over the gimbal (0 if no one is in control)
compid_primary_control (int32_t) – Compid of the component that has primary control over the gimbal (0 if no one is in control)
sysid_secondary_control (int32_t) – Sysid of the component that has secondary control over the gimbal (0 if no one is in control)
compid_secondary_control (int32_t) – Compid of the component that has secondary control over the gimbal (0 if no one is in control)
-
class
mavsdk.gimbal.
Gimbal
(async_plugin_manager)¶ Bases:
mavsdk._base.AsyncBase
Provide control over a gimbal.
Generated by dcsdkgen - MAVSDK Gimbal API
-
control
()¶ 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).
- Yields
control_status (ControlStatus) – Control status
-
name
= 'Gimbal'¶
-
async
release_control
()¶ Release control.
Release control, such that other components can control the gimbal.
- Raises
GimbalError – If the request fails. The error contains the reason for the failure.
-
async
set_mode
(gimbal_mode)¶ 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.
- Parameters
gimbal_mode (GimbalMode) – The mode to be set.
- Raises
GimbalError – If the request fails. The error contains the reason for the failure.
-
async
set_pitch_and_yaw
(pitch_deg, yaw_deg)¶ 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.
- Parameters
pitch_deg (float) – Pitch angle in degrees (negative points down)
yaw_deg (float) – Yaw angle in degrees (positive is clock-wise, range: -180 to 180 or 0 to 360)
- Raises
GimbalError – If the request fails. The error contains the reason for the failure.
-
async
set_pitch_rate_and_yaw_rate
(pitch_rate_deg_s, yaw_rate_deg_s)¶ 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.
- Parameters
pitch_rate_deg_s (float) – Angular rate around pitch axis in degrees/second (negative downward)
yaw_rate_deg_s (float) – Angular rate around yaw axis in degrees/second (positive is clock-wise)
- Raises
GimbalError – If the request fails. The error contains the reason for the failure.
-
async
set_roi_location
(latitude_deg, longitude_deg, 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
latitude_deg (double) – Latitude in degrees
longitude_deg (double) – Longitude in degrees
altitude_m (float) – Altitude in metres (AMSL)
- Raises
GimbalError – If the request fails. The error contains the reason for the failure.
-
async
take_control
(control_mode)¶ 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.
- Parameters
control_mode (ControlMode) – Control mode (primary or secondary)
- Raises
GimbalError – If the request fails. The error contains the reason for the failure.
-
-
exception
mavsdk.gimbal.
GimbalError
(result, origin, *params)¶ Bases:
Exception
Raised when a GimbalResult is a fail code
-
class
mavsdk.gimbal.
GimbalMode
(value)¶ Bases:
enum.Enum
Gimbal mode type.
- YAW_FOLLOW
Yaw follow will point the gimbal to the vehicle heading
- YAW_LOCK
Yaw lock will fix the gimbal poiting to an absolute direction
-
YAW_FOLLOW
= 0¶
-
YAW_LOCK
= 1¶
-
class
mavsdk.gimbal.
GimbalResult
(result, result_str)¶ Bases:
object
Result type.
- Parameters
result (Result) – Result enum value
result_str (std::string) – Human-readable English string describing the result
-
class
Result
(value)¶ Bases:
enum.Enum
Possible results returned for gimbal commands.
- UNKNOWN
Unknown result
- SUCCESS
Command was accepted
- ERROR
Error occurred sending the command
- TIMEOUT
Command timed out
- UNSUPPORTED
Functionality not supported
-
ERROR
= 2¶
-
SUCCESS
= 1¶
-
TIMEOUT
= 3¶
-
UNKNOWN
= 0¶
-
UNSUPPORTED
= 4¶