2
2
3
3
import asyncio
4
4
from mavsdk import System
5
- from mavsdk .gimbal import GimbalMode
5
+ from mavsdk .gimbal import GimbalMode , ControlMode
6
6
7
7
async def run ():
8
8
# Init the drone
@@ -12,41 +12,72 @@ async def run():
12
12
# Start printing gimbal position updates
13
13
asyncio .ensure_future (print_gimbal_position (drone ))
14
14
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 )
18
17
19
18
# Set the gimbal to YAW_LOCK (= 1) mode (see docs for the difference)
20
19
# Other valid values: YAW_FOLLOW (= 0)
21
20
# YAW_LOCK will fix the gimbal pointing to an absolute direction,
22
21
# whereas YAW_FOLLOW will point relative to vehicle heading.
23
22
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 )
26
24
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 )
31
28
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 )
32
60
33
61
# Set the gimbal to track a region of interest (lat, lon, altitude)
34
62
# 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 )
38
66
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 )
41
70
71
+ print ("Release control of gimbal again" )
72
+ await drone .gimbal .release_control ()
42
73
43
74
44
75
async def print_gimbal_position (drone ):
45
76
# Report gimbal position updates asynchronously
46
77
# Note that we are getting gimbal position updates in
47
78
# 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 } " )
50
81
51
82
52
83
if __name__ == "__main__" :
0 commit comments