-
Notifications
You must be signed in to change notification settings - Fork 0
/
kc_functions.py
222 lines (181 loc) · 7.84 KB
/
kc_functions.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
import threading
import time
from threading import Thread
from pynput import keyboard
from other_functions import videoCapture, movementSender, flyAction
import global_variables as var
# Variables para el control de movimientos
left_vel = 0
right_vel = 0
forward_vel = 0
backward_vel = 0
up_vel = 0
down_vel = 0
left_yaw_vel = 0
right_yaw_vel = 0
def sendMovement():
var.tello.send_rc_control(var.l_r_vel_keyboard + var.l_r_vel_aruco + var.l_r_vel_op,
var.f_b_vel_keyboard + var.f_b_vel_aruco + var.f_b_vel_op,
var.u_d_vel_keyboard + var.u_d_vel_aruco + var.u_d_vel_op,
var.y_vel_keyboard + var.y_vel_aruco + var.y_vel_op)
def keyboardInterrupts():
def on_press(key):
global left_vel, right_vel, forward_vel, backward_vel, up_vel, down_vel, left_yaw_vel, right_yaw_vel
try:
# Left
if key.char == 'a' and not var.pressedKeys['a']:
var.pressedKeys['a'] = True
left_vel = -var.kc_speed
var.l_r_vel_keyboard = left_vel + right_vel
sendMovement()
# Right
elif key.char == 'd' and not var.pressedKeys['d']:
var.pressedKeys['d'] = True
right_vel = var.kc_speed
var.l_r_vel_keyboard = left_vel + right_vel
sendMovement()
# Forward
elif key.char == 'w' and not var.pressedKeys['w']:
var.pressedKeys['w'] = True
forward_vel = var.kc_speed
var.f_b_vel_keyboard = forward_vel + backward_vel
sendMovement()
# Backward
elif key.char == 's' and not var.pressedKeys['s']:
var.pressedKeys['s'] = True
backward_vel = -var.kc_speed
var.f_b_vel_keyboard = forward_vel + backward_vel
sendMovement()
# Grabación de video
elif key.char == 'r':
if not var.videoCaptureThread or not var.videoCaptureThread.is_alive():
print("Comenzando la grabación")
var.recording = True
var.videoCaptureThread = Thread(target=videoCapture, daemon=True)
var.videoCaptureThread.start()
else:
print("Deteniendo la grabación")
var.recording = False
# Fin del programa
elif key.char == 'q' and not var.takingoff:
var.finish = True
except AttributeError:
# Up
if key == keyboard.Key.up and not var.pressedKeys['up']:
var.pressedKeys['up'] = True
if not var.tello.is_flying and not var.takingoff:
bateria = var.tello.get_battery()
if bateria > var.minBattery:
# Permite el envío de órdenes de movimiento
var.sendMovements = True
# Envío periódico de órdenes de movimiento
var.movementSenderThread = Thread(target=movementSender, daemon=True)
var.movementSenderThread.start()
# Orden de despegue (no bloqueante)
takeoffThread = Thread(target=flyAction, args=('takeoff',), daemon=True)
takeoffThread.start()
else:
print("Batería insuficiente para el despegue: " + str(bateria) + "%")
else:
up_vel = var.kc_speed
var.u_d_vel_keyboard = up_vel + down_vel
sendMovement()
# Down
elif key == keyboard.Key.down and not var.pressedKeys['down']:
var.pressedKeys['down'] = True
down_vel = -var.kc_speed
var.u_d_vel_keyboard = up_vel + down_vel
sendMovement()
# Land
elif key == keyboard.Key.ctrl_l and not var.pressedKeys['ctrl']:
var.pressedKeys['ctrl'] = True
if var.tello.is_flying and not var.landing:
# Cancela el envío de órdenes de movimiento
var.sendMovements = False
# Ordena al dron cancelar los movimientos
var.tello.send_rc_control(0, 0, 0, 0)
# Espera a que el senderThread finalice
while var.movementSenderThread.is_alive():
time.sleep(0.05)
# Ordena al dron cancelar los movimientos (por si el caso)
var.tello.send_rc_control(0, 0, 0, 0)
# Orden de aterrizaje (no bloqueante)
landThread = Thread(target=flyAction, args=('land',), daemon=True)
landThread.start()
# Rotate Left
elif key == keyboard.Key.left and not var.pressedKeys['rotleft']:
var.pressedKeys['rotleft'] = True
left_yaw_vel = -2 * var.kc_speed
var.y_vel_keyboard = left_yaw_vel + right_yaw_vel
sendMovement()
# Rotate Right
elif key == keyboard.Key.right and not var.pressedKeys['rotright']:
var.pressedKeys['rotright'] = True
right_yaw_vel = 2 * var.kc_speed
var.y_vel_keyboard = left_yaw_vel + right_yaw_vel
sendMovement()
except ValueError:
print("ValueError exception")
def on_release(key):
global left_vel, right_vel, forward_vel, backward_vel, up_vel, down_vel, left_yaw_vel, right_yaw_vel
try:
# Left
if key.char == 'a':
var.pressedKeys['a'] = False
left_vel = 0
var.l_r_vel_keyboard = left_vel + right_vel
sendMovement()
# Right
elif key.char == 'd':
var.pressedKeys['d'] = False
right_vel = 0
var.l_r_vel_keyboard = left_vel + right_vel
sendMovement()
# Forward
elif key.char == 'w':
var.pressedKeys['w'] = False
forward_vel = 0
var.f_b_vel_keyboard = forward_vel + backward_vel
sendMovement()
# Backward
elif key.char == 's':
var.pressedKeys['s'] = False
backward_vel = 0
var.f_b_vel_keyboard = forward_vel + backward_vel
sendMovement()
except AttributeError:
# Up
if key == keyboard.Key.up:
var.pressedKeys['up'] = False
if int(var.tello.get_height()) > 0:
up_vel = 0
var.u_d_vel_keyboard = up_vel + down_vel
sendMovement()
# Down
elif key == keyboard.Key.down:
var.pressedKeys['down'] = False
down_vel = 0
var.u_d_vel_keyboard = up_vel + down_vel
sendMovement()
# Land
elif key == keyboard.Key.ctrl_l:
var.pressedKeys['ctrl'] = False
# Rotate Left
elif key == keyboard.Key.left:
var.pressedKeys['rotleft'] = False
left_yaw_vel = 0
var.y_vel_keyboard = left_yaw_vel + right_yaw_vel
sendMovement()
# Rotate Right
elif key == keyboard.Key.right:
var.pressedKeys['rotright'] = False
right_yaw_vel = 0
var.y_vel_keyboard = left_yaw_vel + right_yaw_vel
sendMovement()
except ValueError:
print("ValueError exception")
var.kc_thread = keyboard.Listener(
on_press=on_press,
on_release=on_release
)
var.kc_thread.start()