-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathtest_actuator_control.py
61 lines (48 loc) · 1.86 KB
/
test_actuator_control.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
import asyncio
from mavsdk import System
from mavsdk.offboard import OffboardError, ActuatorControl, ActuatorControlGroup
async def run():
drone = System()
await drone.connect(system_address="udp://:14540")
print("Waiting for drone to connect...")
async for state in drone.core.connection_state():
if state.is_connected:
print(f"-- Connected to drone!")
break
print("Waiting for drone to have a global position estimate...")
async for health in drone.telemetry.health():
if health.is_global_position_ok and health.is_home_position_ok:
print("-- Global position estimate OK")
break
print("-- Arming")
await drone.action.arm()
print("-- Setting initial actuator control")
# Assuming that we are controlling the first group (group 0)
actuator_control_group = ActuatorControlGroup(
controls=[0.0, 0.5, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
)
actuator_controls = ActuatorControl(
groups=[actuator_control_group]
)
print("-- Setting initial actuator control setpoint")
await drone.offboard.set_actuator_control(actuator_controls)
print("-- Starting offboard")
try:
await drone.offboard.start()
except OffboardError as error:
print(f"Starting offboard mode failed with error code: {error._result.result}")
print("-- Disarming")
await drone.action.disarm()
return
print("-- Setting actuator control")
await drone.offboard.set_actuator_control(actuator_controls)
await asyncio.sleep(10)
print("-- Stopping offboard")
try:
await drone.offboard.stop()
except OffboardError as error:
print(f"Stopping offboard mode failed with error code: {error._result.result}")
print("-- Disarming")
await drone.action.disarm()
if __name__ == "__main__":
asyncio.run(run())