-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathRELATIVE.py
214 lines (187 loc) · 6.27 KB
/
RELATIVE.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
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
#!/usr/bin/env python3
import asyncio
from mavsdk import System
from mavsdk.offboard import (OffboardError, VelocityBodyYawspeed)
import pygame
import time
import math
pygame.init()
pygame.joystick.init()
ctrl = pygame.joystick.Joystick(0)
running=True
pos = pygame.Vector2(0,0)
posrel = pygame.Vector2(0,0)
async def run():
""" Does Offboard control using velocity body coordinates. """
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 setpoint")
await drone.offboard.set_velocity_body(
VelocityBodyYawspeed(0.0, 0.0, 0.0, 0.0))
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("-- Turn clock-wise and climb")
#await drone.offboard.set_velocity_body(VelocityBodyYawspeed(0.0, 0.0, -1.0, 60.0))
#await asyncio.sleep(5)
#print("-- Turn back anti-clockwise")
#await drone.offboard.set_velocity_body(VelocityBodyYawspeed(0.0, 0.0, 0.0, -60.0))
#await asyncio.sleep(5)
#print("-- Wait for a bit")
#await drone.offboard.set_velocity_body(VelocityBodyYawspeed(0.0, 0.0, 0.0, 0.0))
#await asyncio.sleep(2)
#print("-- Fly a circle")
#await drone.offboard.set_velocity_body(VelocityBodyYawspeed(5.0, 0.0, 0.0, 30.0))
#await asyncio.sleep(15)
#print("-- Wait for a bit")
#await drone.offboard.set_velocity_body(VelocityBodyYawspeed(0.0, 0.0, 0.0, 0.0))
#await asyncio.sleep(5)
#print("-- Fly a circle sideways")
#await drone.offboard.set_velocity_body(VelocityBodyYawspeed(0.0, -5.0, 0.0, 30.0))
#await asyncio.sleep(15)
#print("-- Wait for a bit")
#await drone.offboard.set_velocity_body(VelocityBodyYawspeed(0.0, 0.0, 0.0, 0.0))
#await asyncio.sleep(8)
#print("-- Stopping offboard")
#try:
# await drone.offboard.stop()
#except OffboardError as error:
# print(f"Stopping offboard mode failed with error code: \
# {error._result.result}")
alt = 0
airborne = True
counter = 1
running = True
rot = 0
while running:
#x constraints
if pos.x < 0:
pos.x += 0.05
elif pos.x > 0:
pos.x -= 0.05
if pos.x < -1:
pos.x = -1
if pos.x > 1:
pos.x = 1
#y constraints
if pos.y < 0:
pos.y += 0.05
elif pos.y > 0:
pos.y -= 0.05
if pos.y < -1:
pos.y = -1
if pos.y > 1:
pos.y = 1
#climb constraints
if alt < 0:
alt += 0.2
elif alt > 0:
alt -= 0.2
if alt < -5:
alt = -5
if alt > 5:
alt = 5
#yaw constraints
if rot < 0:
rot += 0.5
elif rot > 0:
rot -= 0.5
if rot < -60:
rot = -60
if rot > 60:
rot = 60
#pos.x = 0
#pos.y = 0
#rot = 0
if ctrl.get_button(0) == 1:
print("X")
pygame.quit()
exit()
if ctrl.get_button(1) == 1:
#print("A")
alt += 0.5
if ctrl.get_button(2) == 1:
#print("B")
alt -= 0.5
if ctrl.get_button(3) == 1:
print("Y")
if ctrl.get_button(4) == 1:
#print("L")
rot -= 1.5
if ctrl.get_button(5) == 1:
#print("R")
rot += 1.5
if ctrl.get_button(8) == 1:
print("SELECT")
if ctrl.get_button(9) == 1:
#print("START")
if airborne == True:
await drone.action.land()
await asyncio.sleep(3)
try:
await drone.offboard.stop()
except OffboardError as error:
print(f"Stopping offboard mode failed with error code: {error._result.result}")
airborne = False
else:
await drone.action.arm()
await drone.action.takeoff()
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
airborne = True
await asyncio.sleep(3)
#AXES
if round(ctrl.get_axis(1))==-1:
pos.y += 0.1
#print("forward")
if round(ctrl.get_axis(1))==1:
pos.y -= 0.1
#print("back")
#if round(ctrl.get_axis(1))==0:
# pos.y = 0
if round(ctrl.get_axis(0))==-1:
pos.x += 0.1
#print("left")
if round(ctrl.get_axis(0))==1:
pos.x -= 0.1
#print("right")
#if round(ctrl.get_axis(0))==0:
# pos.x = 0
#pos.y = ctrl.get_axis(0)
#pos.x = ctrl.get_axis(1)
for event in pygame.event.get():
if event.type == pygame.QUIT:
running = False
pos.y += (math.cos(rot)*posrel.y)+(math.cos(rot+90)*posrel.x)
pos.x += (math.sin(rot+90)*posrel.x)+(math.sin(rot)*posrel.y)
print(round(pos,2),round(alt,2))
#await drone.offboard.set_position_ned(PositionNedYaw(pos.y,-pos.x, -alt, rot))
await drone.offboard.set_velocity_body(VelocityBodyYawspeed(pos.y, pos.x, -alt, rot))
time.sleep(0.01)
if __name__ == "__main__":
# Run the asyncio loop
asyncio.run(run())