Skip to content

Commit 00bc7fc

Browse files
committed
examples: improve gimbal example
This adds a few more demo steps, as well as takes and releases control.
1 parent b62effb commit 00bc7fc

File tree

1 file changed

+48
-17
lines changed

1 file changed

+48
-17
lines changed

examples/gimbal.py

Lines changed: 48 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22

33
import asyncio
44
from mavsdk import System
5-
from mavsdk.gimbal import GimbalMode
5+
from mavsdk.gimbal import GimbalMode, ControlMode
66

77
async def run():
88
# Init the drone
@@ -12,41 +12,72 @@ async def run():
1212
# Start printing gimbal position updates
1313
asyncio.ensure_future(print_gimbal_position(drone))
1414

15-
# Arm and takeoff the drone
16-
await drone.action.arm()
17-
await drone.action.takeoff()
15+
print("Taking control of gimbal")
16+
await drone.gimbal.take_control(ControlMode.PRIMARY)
1817

1918
# Set the gimbal to YAW_LOCK (= 1) mode (see docs for the difference)
2019
# Other valid values: YAW_FOLLOW (= 0)
2120
# YAW_LOCK will fix the gimbal pointing to an absolute direction,
2221
# whereas YAW_FOLLOW will point relative to vehicle heading.
2322
print("Setting gimbal mode")
24-
await drone.gimbal.set_mode(GimbalMode.YAW_LOCK)
25-
await asyncio.sleep(5)
23+
await drone.gimbal.set_mode(GimbalMode.YAW_FOLLOW)
2624

27-
# Move the gimbal to point at pitch -40 degrees, yaw 30 degrees
28-
print("Setting pitch & yaw")
29-
await drone.gimbal.set_pitch_and_yaw(-40, 30)
30-
await asyncio.sleep(10)
25+
print("Look forward first")
26+
await drone.gimbal.set_pitch_and_yaw(0, 0)
27+
await asyncio.sleep(1)
3128

29+
print("Look down")
30+
await drone.gimbal.set_pitch_and_yaw(-90, 0)
31+
await asyncio.sleep(2)
32+
33+
print("Back to horizontal")
34+
await drone.gimbal.set_pitch_and_yaw(0, 0)
35+
await asyncio.sleep(2)
36+
37+
print("Slowly look up")
38+
await drone.gimbal.set_pitch_rate_and_yaw_rate(10, 0)
39+
await asyncio.sleep(3)
40+
41+
print("Back to horizontal")
42+
await drone.gimbal.set_pitch_and_yaw(0, 0)
43+
await asyncio.sleep(2)
44+
45+
print("Look right")
46+
await drone.gimbal.set_pitch_and_yaw(0, 90)
47+
await asyncio.sleep(2)
48+
49+
print("Look forward again")
50+
await drone.gimbal.set_pitch_and_yaw(0, 0)
51+
await asyncio.sleep(2)
52+
53+
print("Slowly look to the left")
54+
await drone.gimbal.set_pitch_rate_and_yaw_rate(0, -20)
55+
await asyncio.sleep(3)
56+
57+
print("Look forward again")
58+
await drone.gimbal.set_pitch_and_yaw(0, 0)
59+
await asyncio.sleep(2)
3260

3361
# Set the gimbal to track a region of interest (lat, lon, altitude)
3462
# Units are degrees and meters MSL respectively
35-
print("Setting RoI")
36-
await drone.gimbal.set_roi_location(28.452386, -13.867138, 28.5)
37-
await asyncio.sleep(10)
63+
print("Look at a ROI (region of interest)")
64+
await drone.gimbal.set_roi_location(47.39743832, 8.5463316, 488)
65+
await asyncio.sleep(3)
3866

39-
await drone.action.land()
40-
await asyncio.sleep(5)
67+
print("Look forward again")
68+
await drone.gimbal.set_pitch_and_yaw(0, 0)
69+
await asyncio.sleep(2)
4170

71+
print("Release control of gimbal again")
72+
await drone.gimbal.release_control()
4273

4374

4475
async def print_gimbal_position(drone):
4576
# Report gimbal position updates asynchronously
4677
# Note that we are getting gimbal position updates in
4778
# euler angles; we can also get them as quaternions
48-
async for position in drone.telemetry.camera_attitude_euler():
49-
print(position)
79+
async for angle in drone.telemetry.camera_attitude_euler():
80+
print(f"Gimbal pitch: {angle.pitch_deg}, yaw: {angle.yaw_deg}")
5081

5182

5283
if __name__ == "__main__":

0 commit comments

Comments
 (0)