Gimbal¶
- class mavsdk.gimbal.AngularVelocityBody(roll_rad_s, pitch_rad_s, yaw_rad_s)¶
Bases:
object
Gimbal angular rate type
- Parameters:
roll_rad_s (float) – Roll angular velocity
pitch_rad_s (float) – Pitch angular velocity
yaw_rad_s (float) – Yaw angular velocity
- class mavsdk.gimbal.Attitude(gimbal_id, euler_angle_forward, quaternion_forward, euler_angle_north, quaternion_north, angular_velocity, timestamp_us)¶
Bases:
object
Gimbal attitude type
- Parameters:
gimbal_id (int32_t) – Gimbal ID
euler_angle_forward (EulerAngle) – Euler angle relative to forward
quaternion_forward (Quaternion) – Quaternion relative to forward
euler_angle_north (EulerAngle) – Euler angle relative to North
quaternion_north (Quaternion) – Quaternion relative to North
angular_velocity (AngularVelocityBody) – The angular rate
timestamp_us (uint64_t) – Timestamp in microseconds
- class mavsdk.gimbal.ControlMode(value)¶
Bases:
Enum
Control mode
Values¶
- 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(gimbal_id, control_mode, sysid_primary_control, compid_primary_control, sysid_secondary_control, compid_secondary_control)¶
Bases:
object
Control status
- Parameters:
gimbal_id (int32_t) – Gimbal ID
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.EulerAngle(roll_deg, pitch_deg, yaw_deg)¶
Bases:
object
Euler angle type.
All rotations and axis systems follow the right-hand rule. The Euler angles are converted using the 3-1-2 sequence instead of standard 3-2-1 in order to avoid the gimbal lock at 90 degrees down.
For more info see https://en.wikipedia.org/wiki/Euler_angles
- Parameters:
roll_deg (float) – Roll angle in degrees, positive is banking to the right
pitch_deg (float) – Pitch angle in degrees, positive is pitching nose up
yaw_deg (float) – Yaw angle in degrees, positive is clock-wise seen from above
- class mavsdk.gimbal.Gimbal(async_plugin_manager)¶
Bases:
AsyncBase
Provide control over a gimbal.
Generated by dcsdkgen - MAVSDK Gimbal API
- async attitude()¶
Subscribe to attitude updates.
This gets you the gimbal’s attitude and angular rate.
- Yields:
attitude (Attitude) – The attitude
- async control_status()¶
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
- async get_attitude(gimbal_id)¶
Get attitude for specific gimbal.
- Parameters:
gimbal_id (int32_t) – Gimbal ID
- Returns:
attitude – The attitude
- Return type:
- Raises:
GimbalError – If the request fails. The error contains the reason for the failure.
- async get_control_status(gimbal_id)¶
Get control status for specific gimbal.
- Parameters:
gimbal_id (int32_t) – Gimbal ID
- Returns:
control_status – Control status
- Return type:
- Raises:
GimbalError – If the request fails. The error contains the reason for the failure.
- async gimbal_list()¶
Subscribe to list of gimbals.
This allows to find out what gimbals are connected to the system. Based on the gimbal ID, we can then address a specific gimbal.
- Yields:
gimbal_list (GimbalList) – Gimbal list
- name = 'Gimbal'¶
- async release_control(gimbal_id)¶
Release control.
Release control, such that other components can control the gimbal.
- Parameters:
gimbal_id (int32_t) – Gimbal id to address (0 for all gimbals)
- Raises:
GimbalError – If the request fails. The error contains the reason for the failure.
- async set_angles(gimbal_id, roll_deg, pitch_deg, yaw_deg, gimbal_mode, send_mode)¶
Set gimbal roll, pitch and yaw angles.
This sets the desired roll, 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.
Note that the roll angle needs to be set to 0 when send_mode is Once.
- Parameters:
gimbal_id (int32_t) – Gimbal id to address (0 for all gimbals)
roll_deg (float) – Roll angle in degrees (negative down on the right)
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)
gimbal_mode (GimbalMode) – Gimbal mode to use
send_mode (SendMode) – Send mode of command/setpoint
- Raises:
GimbalError – If the request fails. The error contains the reason for the failure.
- async set_angular_rates(gimbal_id, roll_rate_deg_s, pitch_rate_deg_s, yaw_rate_deg_s, gimbal_mode, send_mode)¶
Set gimbal angular rates.
This sets the desired angular rates around roll, 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.
Note that the roll angle needs to be set to 0 when send_mode is Once.
- Parameters:
gimbal_id (int32_t) – Gimbal id to address (0 for all gimbals)
roll_rate_deg_s (float) – Angular rate around roll axis in degrees/second (negative down on the right)
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)
gimbal_mode (GimbalMode) – Gimbal mode to use
send_mode (SendMode) – Send mode of command/setpoint
- Raises:
GimbalError – If the request fails. The error contains the reason for the failure.
- async set_roi_location(gimbal_id, 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:
gimbal_id (int32_t) – Gimbal id to address (0 for all gimbals)
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(gimbal_id, 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:
gimbal_id (int32_t) – Gimbal id to address (0 for all gimbals)
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.GimbalItem(gimbal_id, vendor_name, model_name, custom_name, gimbal_manager_component_id, gimbal_device_id)¶
Bases:
object
Gimbal list item
- Parameters:
gimbal_id (int32_t) – ID to address it, starting at 1 (0 means all gimbals)
vendor_name (std::string) – Vendor name
model_name (std::string) – Model name
custom_name (std::string) – Custom name name
gimbal_manager_component_id (int32_t) – MAVLink component of gimbal manager, for debugging purposes
gimbal_device_id (int32_t) – MAVLink component of gimbal device
- class mavsdk.gimbal.GimbalList(gimbals)¶
Bases:
object
Gimbal list
- Parameters:
gimbals ([GimbalItem]) – Gimbal items.
- class mavsdk.gimbal.GimbalMode(value)¶
Bases:
Enum
Gimbal mode type.
Values¶
- YAW_FOLLOW
Yaw follow will point the gimbal to the vehicle heading
- YAW_LOCK
Yaw lock will fix the gimbal pointing 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
Possible results returned for gimbal commands.
Values¶
- UNKNOWN
Unknown result
- SUCCESS
Command was accepted
- ERROR
Error occurred sending the command
- TIMEOUT
Command timed out
- UNSUPPORTED
Functionality not supported
- NO_SYSTEM
No system connected
- INVALID_ARGUMENT
Invalid argument
- ERROR = 2¶
- INVALID_ARGUMENT = 6¶
- NO_SYSTEM = 5¶
- SUCCESS = 1¶
- TIMEOUT = 3¶
- UNKNOWN = 0¶
- UNSUPPORTED = 4¶
- class mavsdk.gimbal.Quaternion(w, x, y, z)¶
Bases:
object
Quaternion type.
All rotations and axis systems follow the right-hand rule. The Hamilton quaternion product definition is used. A zero-rotation quaternion is represented by (1,0,0,0). The quaternion could also be written as w + xi + yj + zk.
For more info see: https://en.wikipedia.org/wiki/Quaternion
- Parameters:
w (float) – Quaternion entry 0, also denoted as a
x (float) – Quaternion entry 1, also denoted as b
y (float) – Quaternion entry 2, also denoted as c
z (float) – Quaternion entry 3, also denoted as d