-
Notifications
You must be signed in to change notification settings - Fork 0
/
dvic_demo.py
262 lines (204 loc) · 9.26 KB
/
dvic_demo.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
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
#!/usr/bin/env python
#Code initiated by txa on 20 October 2020
#Comments added on 27 January 2021
#Saved under https://github.com/ThomasCarstens/cfScripts/blob/master/dvic_demo.py
#Some more explanations at txa-tuto: https://github.com/ThomasCarstens/txa-dvic-projects-tutos/tree/main/Behaviour%20Planning%20with%20ROS
import numpy as np
from pycrazyswarm import *
import uav_trajectory
import keyboard
def fly(id, allcfs, swarm, timeHelper, TRIALS, TIMESCALE):
for i in range(TRIALS):
#for cf in allcfs.crazyflies:
#cf.takeoff(targetHeight=0.5, duration=3.0)
for cf in allcfs.crazyflies:
if cf.id == id:
allcfs.crazyflies[0].takeoff(targetHeight=0.3, duration=3.0)
timeHelper.sleep(2.5)
#for cf in allcfs.crazyflies:
# pos = cf.position() + np.array([0, 0, 1.0])
# cf.goTo(pos, 0, 2.0)
#timeHelper.sleep(2.5)
cf.startTrajectory(0, timescale=TIMESCALE)
#allcfs.crazyflies[0].startTrajectory(0, timescale=TIMESCALE, reverse=False)
#timeHelper.sleep(traj1.duration * TIMESCALE + 2.0)
timeHelper.sleep(1.0)
if id == -1:
allcfs.crazyflies[0].takeoff(targetHeight=0.3, duration=3.0)
timeHelper.sleep(2.5)
#for cf in allcfs.crazyflies:
# pos = cf.position() + np.array([0, 0, 1.0])
# cf.goTo(pos, 0, 2.0)
#timeHelper.sleep(2.5)
cf.startTrajectory(0, timescale=TIMESCALE)
#allcfs.crazyflies[0].startTrajectory(0, timescale=TIMESCALE, reverse=False)
#timeHelper.sleep(traj1.duration * TIMESCALE + 2.0)
timeHelper.sleep(1.0)
print("press button to continue...")
swarm.input.waitUntilButtonPressed()
allcfs.crazyflies[0].land(targetHeight=0.06, duration=2.0)
timeHelper.sleep(3.0)
def fly_two_drones(allcfs, swarm, timeHelper, TRIALS, TIMESCALE):
allcfs.crazyflies[0].takeoff(targetHeight=0.5, duration=3.0)
allcfs.crazyflies[1].takeoff(targetHeight=0.5, duration=3.0)
for i in range(TRIALS):
#allcfs.crazyflies[0].takeoff(targetHeight=0.5, duration=3.0)
#allcfs.crazyflies[1].takeoff(targetHeight=0.5, duration=3.0)
#timeHelper.sleep(2.5)
print("press button to continue...")
swarm.input.waitUntilButtonPressed()
#for cf in allcfs.crazyflies:
# pos = cf.position() + np.array([0, 0, 1.0])
# cf.goTo(pos, 0, 2.0)
#timeHelper.sleep(2.5)
#allcfs.crazyflies[0].startTrajectory(0, timescale=TIMESCALE)
allcfs.crazyflies[1].startTrajectory(0, timescale=TIMESCALE)
allcfs.crazyflies[0].startTrajectory(0, timescale=TIMESCALE, reverse=True)
#timeHelper.sleep(traj1.duration * TIMESCALE + 2.0)
timeHelper.sleep(1.0)
def fly_three_drones():
allcfs.crazyflies[0].takeoff(targetHeight=0.5, duration=3.0)
allcfs.crazyflies[1].takeoff(targetHeight=0.5, duration=3.0)
allcfs.crazyflies[2].takeoff(targetHeight=0.5, duration=3.0)
for i in range(TRIALS):
#allcfs.crazyflies[0].takeoff(targetHeight=0.5, duration=3.0)
#allcfs.crazyflies[1].takeoff(targetHeight=0.5, duration=3.0)
#timeHelper.sleep(2.5)
print("press button to continue...")
swarm.input.waitUntilButtonPressed()
#for cf in allcfs.crazyflies:
# pos = cf.position() + np.array([0, 0, 1.0])
# cf.goTo(pos, 0, 2.0)
#timeHelper.sleep(2.5)
#allcfs.crazyflies[0].startTrajectory(0, timescale=TIMESCALE)
allcfs.crazyflies[0].startTrajectory(0, timescale=TIMESCALE)
allcfs.crazyflies[1].startTrajectory(0, timescale=TIMESCALE)
allcfs.crazyflies[2].startTrajectory(0, timescale=TIMESCALE)
#allcfs.crazyflies[0].startTrajectory(0, timescale=TIMESCALE, reverse=True)
#timeHelper.sleep(traj1.duration * TIMESCALE + 2.0)
timeHelper.sleep(1.0)
def fly_nostops():
for i in range(TRIALS):
for cf in allcfs.crazyflies:
#cf.takeoff(targetHeight=0.5, duration=3.0)
#allcfs.crazyflies[1].takeoff(targetHeight=0.3, duration=3.0)
timeHelper.sleep(2.5)
#for cf in allcfs.crazyflies:
# pos = cf.position() + np.array([0, 0, 1.0])
# cf.goTo(pos, 0, 2.0)
#timeHelper.sleep(2.5)
cf.startTrajectory(0, timescale=TIMESCALE)
#allcfs.crazyflies[0].startTrajectory(0, timescale=TIMESCALE, reverse=False)
#timeHelper.sleep(traj1.duration * TIMESCALE + 2.0)
#timeHelper.sleep(1.0)
#print("press button to continue...")
#swarm.input.waitUntilButtonPressed()
#allcfs.land(targetHeight=0.06, duration=2.0)
timeHelper.sleep(3.0)
if __name__ == "__main__":
swarm = Crazyswarm()
timeHelper = swarm.timeHelper
allcfs = swarm.allcfs
traj0 = uav_trajectory.Trajectory()
traj0.loadcsv("figure8.csv")
traj1 = uav_trajectory.Trajectory()
traj1.loadcsv("trajectory2.csv")
#traj2 = uav_trajectory.Trajectory()
#traj2.loadcsv("timed_waypoints_circle1.csv")
traj3 = uav_trajectory.Trajectory()
traj3.loadcsv("circle_join_longer.csv")
traj4 = uav_trajectory.Trajectory()
traj4.loadcsv("helicoidale.csv")
rdev18_traj = uav_trajectory.Trajectory()
rdev18_traj.loadcsv("demo_shapes/rdev_18deg.csv")
ldev18_traj = uav_trajectory.Trajectory()
ldev18_traj.loadcsv("demo_shapes/ldev_18deg.csv")
f8xz_traj = uav_trajectory.Trajectory()
f8xz_traj.loadcsv("demo_shapes/figure8_xz.csv")
#TRIALS = 1
#TIMESCALE = 0.5
nb_drones = raw_input ("nb of drones: ")
demo = raw_input ("choose a demo: \n 0: xy figure of 8+circle \n 1: zx figure of 8 \n 2: semicircle(issues) \n 3: helicoidale\n 4: rdev18\n 5:ldev18\n 6:f8(xz)\n 7: keyboard ctrl\n 8: demo of the death \n demo:")
#TRIALS = int(raw_input ("nb of repeats: ")
#TIMESCALE = raw_input ("speed factor where 1 is max 1m/s, 1m/s2: ")
if demo == '0':
TRIALS = 1
TIMESCALE = 1
#for i in range(TRIALS):
for cf in allcfs.crazyflies:
cf.uploadTrajectory(0, 0, traj0)
if nb_drones == "3":
fly_three_drones()
print("press button to continue...")
swarm.input.waitUntilButtonPressed()
allcfs.land(targetHeight=0.06, duration=2.0)
timeHelper.sleep(3.0)
if nb_drones == "2":
fly_two_drones(allcfs, swarm, timeHelper, TRIALS, TIMESCALE)
print("press button to continue...")
swarm.input.waitUntilButtonPressed()
allcfs.land(targetHeight=0.06, duration=2.0)
timeHelper.sleep(3.0)
if nb_drones == "1":
fly(-1, allcfs, swarm, timeHelper, TRIALS, TIMESCALE)
#fly()
if demo == '1':
TRIALS = 1
TIMESCALE = 0.5
#for i in range(TRIALS):
for cf in allcfs.crazyflies:
cf.uploadTrajectory(0, 0, traj1)
fly()
if demo == '3':
TRIALS = 1
TIMESCALE = 0.5
#for i in range(TRIALS):
for cf in allcfs.crazyflies:
cf.uploadTrajectory(0, 0, traj4)
if nb_drones == "2":
fly_two_drones(allcfs, timeHelper, TRIALS, TIMESCALE)
if nb_drones == "1":
fly(-1, allcfs, swarm, timeHelper, TRIALS, TIMESCALE)
if demo == '4':
TRIALS = 1
TIMESCALE = 0.75
#for i in range(TRIALS):
for cf in allcfs.crazyflies:
cf.uploadTrajectory(0, 0, rdev18_traj)
fly(-1, allcfs, swarm, timeHelper, TRIALS, TIMESCALE)
if demo == '5':
TRIALS = 1
TIMESCALE = 0.75
#for i in range(TRIALS):
for cf in allcfs.crazyflies:
cf.uploadTrajectory(0, 0, ldev18_traj)
fly(-1, allcfs, swarm, timeHelper, TRIALS, TIMESCALE)
if demo == '6':
TRIALS = 1
TIMESCALE = 0.5
#for i in range(TRIALS):
for cf in allcfs.crazyflies:
cf.uploadTrajectory(0, 0, f8xz_traj)
fly(-1, allcfs, swarm, timeHelper, TRIALS, TIMESCALE)
if demo == '7':
TRIALS = 1
TIMESCALE = 0.75
execfile('keyboard.py')
if demo == '8':
TRIALS = 1
TIMESCALE = 0.5
for cf in allcfs.crazyflies:
cf.takeoff(targetHeight=0.6, duration=3.0)
cf.uploadTrajectory(0, 0, traj1)
fly_nostops()
TRIALS = 1
TIMESCALE = 1
for cf in allcfs.crazyflies:
cf.uploadTrajectory(0, 0, traj0)
fly_nostops()
TRIALS = 1
TIMESCALE = 0.5
for cf in allcfs.crazyflies:
cf.uploadTrajectory(0, 0, traj4)
fly_nostops()
#execfile('keyboard.py')