-
Notifications
You must be signed in to change notification settings - Fork 2
Expand file tree
/
Copy pathgui.py
More file actions
1340 lines (1089 loc) · 55.2 KB
/
gui.py
File metadata and controls
1340 lines (1089 loc) · 55.2 KB
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
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
from PyQt5 import QtWidgets
from PyQt5 import QtCore
from PyQt5.QtWebEngineWidgets import QWebEngineView
from PyQt5.QtGui import QPixmap, QImage
from PyQt5.QtCore import QTimer, QThread, pyqtSignal, Qt, pyqtSlot
from PyQt5.QtWebChannel import QWebChannel
from windows.MainWindow import Ui_MainWindow
from windows.ConnectingWindow import Ui_ConnectingWindow
from windows.WaypointWindow import Ui_WaypointWindow
from windows.WaypointsSettingWindow import Ui_WaypointsSettingWindow
import sys
import io
import folium
from mav_library import Drone
import time
import os
import base64
import cv2
import socket
import pickle
import numpy as np
from windows.FlightDataWidget import FlightIndicatorsWidget
from datetime import datetime
os.environ["QT_QPA_PLATFORM_PLUGIN_PATH"] = "/home/usr/lib/x86_64-linux-gnu/qt5/plugins"
os.environ["QTWEBENGINE_DISABLE_GPU"] = "1"
mapBaslangicKoordinati = (40.18765752437741, 29.128429079470234)
class FlightDataThread(QThread):
updateSignal = pyqtSignal(dict)
def __init__(self, drone):
super().__init__()
self.drone = drone
self.running = True
def run(self):
while self.running:
try:
# Drone verileri
flight_data = {
"airspeed": self.drone.velocity.airspeed or 0,
"altitude": self.drone.location.alt or 0,
"roll": self.drone.attitude.roll or 0,
"pitch": self.drone.attitude.pitch or 0,
"heading": self.drone.attitude.yaw or 0,
"turn_rate": (self.drone.attitude.yawspeed or 0) * 57.2958, # radyan/s'den derece/s'ye
"vertical_speed": self.drone.velocity.vz or 0
}
self.updateSignal.emit(flight_data)
time.sleep(0.2) # 200ms
except Exception as e:
print(f"Flight data thread hatası: {e}")
time.sleep(1)
def stop(self):
self.running = False
self.wait()
class MapUpdateThread(QThread):
def __init__(self, drone):
super().__init__()
self.drone = drone
self.running = True
self.last_update = 0
self.update_interval = 0.1 # 100ms'de bir güncelle (10 FPS)
def run(self):
while self.running:
try:
current_time = time.time()
if current_time - self.last_update >= self.update_interval:
lat = self.drone.location.lat
lon = self.drone.location.lon
if (isinstance(lat, (int, float)) and isinstance(lon, (int, float)) and
-90 <= lat <= 90 and -180 <= lon <= 180):
script = f'updateMarkerPosition({lat}, {lon}); addTrailPoint({lat}, {lon});'
QtCore.QMetaObject.invokeMethod(self.parent(),
"updateMapJS",
Qt.QueuedConnection,
QtCore.Q_ARG(str, script))
self.last_update = current_time
time.sleep(0.05) # 50ms bekle
except Exception as e:
print(f"Map update thread hatası: {e}")
time.sleep(0.1)
def stop(self):
self.running = False
self.wait()
class CameraThread(QThread):
changePixmap = pyqtSignal(QImage)
connectionStatus = pyqtSignal(str)
errorOccurred = pyqtSignal(str)
def __init__(self, host="localhost", port=5000):
super().__init__()
self.host = host
self.port = port
self.maxLength = 1472
self.sock = None
self.running = True
self.frameInfo = None
self.buffer = None
# UDP ile görüntü aktarımı için
"""
def run(self):
try:
self.sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
self.sock.bind((self.host, self.port))
self.sock.settimeout(1.0)
self.connectionStatus.emit("Bağlantı kuruldu.")
self.connectionStatus.emit("Görüntü bekleniyor...")
while self.running:
try:
data, address = self.sock.recvfrom(self.maxLength)
if len(data) < 100:
try:
self.frameInfo = pickle.loads(data)
except Exception as e:
self.errorOccurred.emit(f"Pickle hatası: {e}")
continue
if self.frameInfo:
numsOfPacks = self.frameInfo["packs"]
for i in range(numsOfPacks):
if not self.running:
break
try:
data, address = self.sock.recvfrom(self.maxLength)
if i == 0:
self.buffer = data
else:
self.buffer += data
except socket.timeout:
continue
except Exception as e:
self.errorOccurred.emit(f"Paket alma hatası: {e}")
break
if self.running and self.buffer:
frame = np.frombuffer(self.buffer, dtype=np.uint8)
frame = frame.reshape(frame.shape[0], 1)
frame = cv2.imdecode(frame, cv2.IMREAD_COLOR)
if frame is not None and isinstance(frame, np.ndarray):
frame = cv2.flip(frame, 1)
rgbImage = cv2.cvtColor(frame, cv2.COLOR_BGR2RGB)
h, w, ch = rgbImage.shape
bytesPerLine = ch * w
convertToQtFormat = QImage(
rgbImage.data, w, h, bytesPerLine, QImage.Format_RGB888
)
p = convertToQtFormat.scaled(640, 480, Qt.KeepAspectRatio)
self.changePixmap.emit(p)
except socket.timeout:
continue
except Exception as e:
if self.running:
self.errorOccurred.emit(f"Veri alma hatası: {e}")
break
except Exception as e:
self.errorOccurred.emit(f"Bağlantı kurulamadı: {e}")
finally:
self.cleanup()
"""
# Bilgisayarın kamerası (Test için)
def run(self):
self.cap = cv2.VideoCapture(0)
while self.running:
ret, frame = self.cap.read()
frame = cv2.flip(frame,1)
if ret:
rgbImage = cv2.cvtColor(frame, cv2.COLOR_BGR2RGB)
h, w, ch = rgbImage.shape
bytesPerLine = ch * w
convertToQtFormat = QImage(rgbImage.data, w, h, bytesPerLine, QImage.Format_RGB888)
p = convertToQtFormat.scaled(640, 480, Qt.KeepAspectRatio)
self.changePixmap.emit(p)
def stop(self):
self.running = False
self.cleanup()
self.quit()
self.wait()
def cleanup(self):
if self.sock:
try:
self.sock.close()
self.connectionStatus.emit("Bağlantı sonlandırıldı.")
except:
pass
self.sock = None
def setConnection(self, host, port):
self.host = host
self.port = port
class ParamLoadThread(QThread):
progress_update = pyqtSignal(str)
progress_bar_update = pyqtSignal(int)
finished = pyqtSignal(bool, str, object)
def __init__(self, port, baud_rate):
super().__init__()
self.port = port
self.baud_rate = baud_rate
self.drone = None
def run(self):
try:
self.progress_update.emit("Yükleniyor...")
self.progress_bar_update.emit(0) # Başlangıç değeri
self.drone = Drone(self.port, baud=self.baud_rate)
self.progress_update.emit("Bağlantı kuruluyor...")
self.progress_bar_update.emit(10)
self.drone.vehicle.mav.param_request_list_send(self.drone.vehicle.target_system, self.drone.vehicle.target_component)
params_received = set()
timeout = 30
start_time = time.time()
total_params = None
while True:
msg = self.drone.vehicle.recv_match(type='PARAM_VALUE', blocking=True, timeout=timeout)
if msg is None:
print("Parametreleri tam alırken zaman aşımı!")
break
params_received.add(msg.param_id)
# İlk mesajda toplam parametre sayısını al
if total_params is None:
total_params = msg.param_count
# Progress bar güncelleme
if total_params:
progress = int((len(params_received) / total_params) * 90) + 10 # 10-100 arası
self.progress_bar_update.emit(progress)
self.progress_update.emit(f"Parametreler yükleniyor... ({len(params_received)}/{total_params})")
if len(params_received) >= total_params:
self.progress_bar_update.emit(100)
self.progress_update.emit("Parametreler yüklendi!")
self.finished.emit(True, "Bağlantı başarılı!", self.drone)
break
# Timeout kontrolü
if time.time() - start_time > timeout:
print("Parametreleri alırken zaman aşımı oldu!")
self.finished.emit(False, "Bağlantı zaman aşımına uğradı!", None)
break
except Exception as e:
print(e)
self.finished.emit(False, f"Bağlantı hatası: {str(e)}", None)
class MissionThread(QThread):
missionCompleted = pyqtSignal()
def __init__(self, drone):
super().__init__()
self.drone = drone
def run(self):
print("Görev başladı.")
self.drone.mode = "AUTO"
self.missionCompleted.emit()
class ModeChangeThread(QThread):
modeChanged = pyqtSignal()
def __init__(self, drone, label, combo):
super().__init__()
self.drone = drone
self.label = label
self.combo = combo
def run(self):
currentMode = self.combo.currentText()
self.drone.mode = currentMode
self.modeChanged.emit()
class ArmDisarmThread(QThread):
armed = pyqtSignal()
disarmed = pyqtSignal()
def __init__(self, drone, label, status):
super().__init__()
self.drone = drone
self.label = label
self.status = status
def run(self):
if self.status == True: # Arm et
self.drone.arm_disarm(True)
self.armed.emit()
else: # Disarm et
self.drone.arm_disarm(False)
self.disarmed.emit()
class ChangeAltLabel(QThread):
def __init__(self, drone, label):
super().__init__()
self.drone = drone
self.label = label
self.running = True
def run(self):
while self.running:
self.label.setText(f'<html><head/><body><p><span style=" font-weight:600; text-decoration: underline;">Şuanki yükseklik</span><span style=" font-weight:600;">: </span><span style=" font-weight:600; color:#fffe08;">{self.drone.location.alt}</span></p></body></html>')
time.sleep(0.5)
def stop(self):
self.running = False
self.wait()
class TakeOffThread(QThread):
reached = pyqtSignal()
def __init__(self, drone, label, alt):
super().__init__()
self.drone = drone
self.label = label
self.alt = alt
def run(self):
self.altLabelThread = ChangeAltLabel(self.drone, self.label)
self.altLabelThread.start()
self.drone.takeoff(self.alt)
self.altLabelThread.stop()
self.reached.emit()
class WaypointLoadThread(QThread):
finished = pyqtSignal(bool, str)
progress = pyqtSignal(int, str)
def __init__(self, drone, coordinates):
super().__init__()
self.drone = drone
self.coordinates = coordinates
def run(self):
try:
self.progress.emit(0, "Waypoint'ler yükleniyor...")
success, message = self.drone.upload_waypoints(self.coordinates)
if success:
self.progress.emit(100, message)
self.finished.emit(True, message)
else:
self.progress.emit(0, message)
self.finished.emit(False, message)
except Exception as e:
self.progress.emit(0, str(e))
self.finished.emit(False, f"Waypoint'ler yüklenirken hata oluştu: {str(e)}")
class Window(QtWidgets.QMainWindow):
def __init__(self):
super(Window, self).__init__()
self.ui = Ui_MainWindow()
self.ui.setupUi(self)
print("Arayüz başlatıldı")
self.showMaximized()
self.ui.centralwidget.setStyleSheet("background-color: rgb(0, 0, 0)")
self.icon_base64 = self.getIconBase64()
self.createInitialMap()
self.ui.BaglanButton.clicked.connect(self.connect)
self.droneConnected = False
self.missionCompleted = True
self.ui.gorevButton.clicked.connect(self.gorev)
self.ui.rtlButton.clicked.connect(self.rtl)
self.marker = None
self.pixMap = QPixmap("images/quad.png")
self.ui.logoLabel.setPixmap(self.pixMap)
# Flight indicators widget'ı dataLabel yerine ekle
self.flight_indicators = FlightIndicatorsWidget()
self.ui.dataLabel.setParent(None) # Eski label'ı kaldır
# Widget'ı doğrudan centralwidget'a ekle
self.flight_indicators.setParent(self.ui.centralwidget)
self.flight_indicators.setGeometry(self.ui.dataLabel.geometry()) # Eski label'ın konumunu kullan
self.flight_indicators.show()
self.ui.modButton.clicked.connect(self.modeChange)
self.ui.waypointButton.clicked.connect(self.openWpWindow)
self.ui.armButton.clicked.connect(self.arm)
self.ui.disarmButton.clicked.connect(self.disarm)
self.ui.takeOffButton.clicked.connect(self.takeoff)
# logTable ayarları
self.ui.logTable.setColumnCount(2)
self.ui.logTable.setHorizontalHeaderLabels(["Tarih", "Mesaj"])
self.ui.logTable.horizontalHeader().setSectionResizeMode(QtWidgets.QHeaderView.Fixed)
# Sütun genişliklerini ayarla
self.setupLogTableColumns()
def setupLogTableColumns(self):
total_width = self.ui.logTable.viewport().width()
self.ui.logTable.setColumnWidth(0, int(total_width * 0.25)) # Tarih: %25
self.ui.logTable.setColumnWidth(1, int(total_width * 0.75)) # Mesaj: %75
def resizeEvent(self, event):
super().resizeEvent(event)
if hasattr(self.ui, 'logTable'):
self.setupLogTableColumns()
def tabloItemEkle(self, message):
row = self.ui.logTable.rowCount()
self.ui.logTable.insertRow(row)
time_str = datetime.now().strftime("%H:%M:%S")
time_item = QtWidgets.QTableWidgetItem(time_str)
time_item.setTextAlignment(QtCore.Qt.AlignCenter)
self.ui.logTable.setItem(row, 0, time_item)
message_item = QtWidgets.QTableWidgetItem(str(message))
message_item.setTextAlignment(QtCore.Qt.AlignHCenter | QtCore.Qt.AlignVCenter)
self.ui.logTable.setItem(row, 1, message_item)
self.ui.logTable.scrollToBottom()
@QtCore.pyqtSlot(str)
def updateMapJS(self, script):
"""JavaScript kodunu ana thread'de çalıştır"""
try:
self.webView.page().runJavaScript(script)
except Exception as e:
print(f"Map JS güncelleme hatası: {e}")
def arm(self):
if self.droneConnected is False:
msg = QtWidgets.QMessageBox()
msg.setIcon(QtWidgets.QMessageBox.Critical)
msg.setText("Lütfen önce drone'a bağlanın.")
msg.setWindowTitle("Uyarı")
msg.exec_()
else:
if self.drone.mode != "GUIDED":
msg = QtWidgets.QMessageBox()
msg.setIcon(QtWidgets.QMessageBox.Critical)
msg.setText("Motorları çalıştırmak için önce \"GUIDED\" moduna geçin.")
msg.setWindowTitle("Uyarı")
msg.exec_()
else:
self.tabloItemEkle("Motorlar'a arm emri verildi..")
self.ui.armLabel.setText("<html><head/><body><p><span style=\" font-weight:600; color:#fffe08;\">Arm ediliyor...</span></p></body></html>")
self.armThread = ArmDisarmThread(self.drone, self.ui.armLabel, True)
self.armThread.armed.connect(self.armed)
self.armThread.start()
def armed(self):
self.ui.armLabel.setText(f'<html><head/><body><p><span style=" font-weight:600; text-decoration: underline;">Arm</span><span style=" font-weight:600;">: </span><span style=" font-weight:600; color:#42FF2F;">Armed</span></p></body></html>')
self.tabloItemEkle("Motorlar arm edildi.")
def disarm(self):
if self.droneConnected is False:
msg = QtWidgets.QMessageBox()
msg.setIcon(QtWidgets.QMessageBox.Critical)
msg.setText("Lütfen önce drone'a bağlanın.")
msg.setWindowTitle("Uyarı")
msg.exec_()
else:
self.tabloItemEkle("Motorlar'a disarm emri verildi..")
self.ui.armLabel.setText("<html><head/><body><p><span style=\" font-weight:600; color:#fffe08;\">Disarm ediliyor...</span></p></body></html>")
self.armThread = ArmDisarmThread(self.drone, self.ui.armLabel, False)
self.armThread.disarmed.connect(self.disarmed)
self.armThread.start()
def disarmed(self):
self.ui.armLabel.setText("<html><head/><body><p><span style=\" font-weight:600; text-decoration: underline;\">Arm</span><span style=\" font-weight:600;\">: </span><span style=\" font-weight:600; color:#ff0000;\">Disarmed</span></p></body></html>")
self.tabloItemEkle("Motorlar disarm edildi.")
def takeoff(self):
if self.droneConnected is False:
msg = QtWidgets.QMessageBox()
msg.setIcon(QtWidgets.QMessageBox.Critical)
msg.setText("Lütfen önce drone'a bağlanın.")
msg.setWindowTitle("Uyarı")
msg.exec_()
else:
hedeflenenYukseklik = self.ui.takeOffYukseklik.value()
self.takeoffLabel = TakeOffThread(self.drone, self.ui.yukseklikLabel, hedeflenenYukseklik)
self.takeoffLabel.reached.connect(self.altReached)
self.takeoffLabel.start()
self.tabloItemEkle(f"{hedeflenenYukseklik}m yüksekliğe take off emri verildi.")
def altReached(self):
self.ui.yukseklikLabel.setText(f'<html><head/><body><p><span style=" font-weight:600; text-decoration: underline;">Ulaşılan yükseklik</span><span style=" font-weight:600;">: </span><span style=" font-weight:600; color:#42FF2F;">{self.drone.location.alt}</span></p></body></html>')
self.tabloItemEkle("Hedeflenen yüksekliğe çıkıldı. Görev başlatılabilir.")
def openWpWindow(self):
if self.droneConnected is False:
msg = QtWidgets.QMessageBox()
msg.setIcon(QtWidgets.QMessageBox.Critical)
msg.setText("Lütfen önce drone'a bağlanın.")
msg.setWindowTitle("Uyarı")
msg.exec_()
else:
self.waypointWindow = QtWidgets.QMainWindow()
self.uiWpWindow = Ui_WaypointWindow()
self.uiWpWindow.setupUi(self.waypointWindow)
self.uiWpWindow.centralwidget.setStyleSheet("background-color: rgb(0, 0, 0)")
self.waypointWindow.show()
self.uiWpWindow.yukleButton.clicked.connect(self.wpYukle)
self.uiWpWindow.okuButton.clicked.connect(self.wpOku)
header = self.uiWpWindow.coordinateWidget.horizontalHeader()
header.setDefaultAlignment(Qt.AlignCenter)
header.setSectionResizeMode(QtWidgets.QHeaderView.Stretch)
vertical_header = self.uiWpWindow.coordinateWidget.verticalHeader()
vertical_header.setDefaultAlignment(Qt.AlignCenter)
for row in range(self.uiWpWindow.coordinateWidget.rowCount()):
for col in range(self.uiWpWindow.coordinateWidget.columnCount()):
item = self.uiWpWindow.coordinateWidget.item(row, col)
if item:
item.setTextAlignment(Qt.AlignCenter)
else:
item = QtWidgets.QTableWidgetItem("")
item.setTextAlignment(Qt.AlignCenter)
self.uiWpWindow.coordinateWidget.setItem(row, col, item)
self.wpm = folium.Map(
location=(self.drone.location.lat, self.drone.location.lon),
zoom_start=20,
tiles=folium.TileLayer(tiles='https://mt1.google.com/vt/lyrs=s&x={x}&y={y}&z={z}', attr="QuadRuplet", max_zoom=22)
)
script = f"""
<script src=\"qrc:///qtwebchannel/qwebchannel.js\"></script>
<script>
var droneMarker = null;
var droneMap = null;
var droneIcon = {f'L.icon({{ iconUrl: "{self.icon_base64}", iconSize: [50, 50], iconAnchor: [25, 25] }})' if self.icon_base64 else 'null'};
var droneTrail = [];
var trailLayer = null;
var trackingEnabled = true;
var clickIndex = 1;
var pybridge = null;
new QWebChannel(qt.webChannelTransport, function(channel) {{
pybridge = channel.objects.pybridge;
}});
document.addEventListener('DOMContentLoaded', function() {{
var mapDiv = document.querySelector('.folium-map');
droneMap = window[mapDiv.id.replace('map_', 'map_')];
if (droneMap && !droneMarker && droneIcon) {{
droneMarker = L.marker([{self.drone.location.lat}, {self.drone.location.lon}], {{icon: droneIcon}}).addTo(droneMap);
}}
droneMap.on('click', function(e) {{
var lat = e.latlng.lat;
var lng = e.latlng.lng;
L.marker([lat, lng]).addTo(droneMap)
.bindTooltip(String(clickIndex), {{
permanent: true,
direction: 'center',
offset: [-15, -30],
className: 'waypoint-label',
opacity: 1,
interactive: false
}}).openPopup();
if (pybridge) {{
pybridge.sendCoordinates(lat, lng, clickIndex);
}}
clickIndex += 1;
}});
}});
window.initializeMarker = function(lat, lng) {{
if (droneMap && !droneMarker) {{
droneMarker = L.marker([lat, lng], droneIcon ? {{icon: droneIcon}} : {{}}).addTo(droneMap);
droneMap.setView([lat, lng], droneMap.getZoom());
}}
}};
window.updateMarkerPosition = function(lat, lng) {{
if (droneMarker && droneMap) {{
droneMarker.setLatLng([lat, lng]);
if (trackingEnabled) {{
droneMap.setView([lat, lng], droneMap.getZoom());
}}
}}
}};
window.removeDroneMarker = function() {{
if (droneMarker) {{
droneMap.removeLayer(droneMarker);
droneMarker = null;
}}
}};
window.addTrailPoint = function(lat, lng) {{
var newPoint = [lat,lng];
droneTrail.push(newPoint);
if (trailLayer) {{
droneMap.removeLayer(trailLayer);
}}
if (droneTrail.length > 1) {{
trailLayer = L.polyline(droneTrail, {{color: 'yellow'}}).addTo(droneMap);
}}
setTimeout(function() {{
if (droneTrail.length > 1) {{
droneTrail.shift();
if (trailLayer) {{
droneMap.removeLayer(trailLayer);
}}
if (droneTrail.length > 1) {{
trailLayer = L.polyline(droneTrail, {{color: 'yellow'}}).addTo(droneMap);
}}
}}
}}, 10000)
}}
// Toggle tracking state
window.toggleTracking = function() {{
trackingEnabled = !trackingEnabled;
return trackingEnabled;
}}
</script>
"""
self.wpm.get_root().html.add_child(folium.Element(script))
data = io.BytesIO()
self.wpm.save(data, close_file=False)
self.wpWebView = QWebEngineView()
class WebBridge(QtCore.QObject):
def __init__(self, table_widget):
super().__init__()
self.table_widget = table_widget
@QtCore.pyqtSlot(float, float, int)
def sendCoordinates(self, lat, lng, idx):
if self.table_widget.rowCount() < idx:
self.table_widget.setRowCount(idx)
lat_item = QtWidgets.QTableWidgetItem(f"{lat:.8f}")
lng_item = QtWidgets.QTableWidgetItem(f"{lng:.8f}")
alt_item = QtWidgets.QTableWidgetItem(str(10))
lat_item.setTextAlignment(Qt.AlignCenter)
lng_item.setTextAlignment(Qt.AlignCenter)
alt_item.setTextAlignment(Qt.AlignCenter)
self.table_widget.setItem(idx-1, 0, lat_item)
self.table_widget.setItem(idx-1, 1, lng_item)
self.table_widget.setItem(idx-1, 2, alt_item)
self._wp_bridge = WebBridge(self.uiWpWindow.coordinateWidget)
channel = QWebChannel(self.wpWebView.page())
channel.registerObject('pybridge', self._wp_bridge)
self.wpWebView.page().setWebChannel(channel)
self.wpWebView.setHtml(data.getvalue().decode())
self.uiWpWindow.mapCLayout.addWidget(self.wpWebView)
def wpOku(self):
if not self.droneConnected:
msg = QtWidgets.QMessageBox()
msg.setIcon(QtWidgets.QMessageBox.Warning)
msg.setText("Önce drone'a bağlanmalısınız!")
msg.setWindowTitle("Uyarı")
msg.exec_()
return
waypoints = self.drone.get_waypoints()
if not waypoints or len(waypoints) <= 1:
msg = QtWidgets.QMessageBox()
msg.setIcon(QtWidgets.QMessageBox.Information)
msg.setText("Drone'da kayıtlı waypoint bulunmuyor.")
msg.setWindowTitle("Bilgi")
msg.exec_()
return
self.uiWpWindow.coordinateWidget.setRowCount(len(waypoints) - 1)
# Markerları temizle
markers_script = """
if (window.waypointMarkers) {
window.waypointMarkers.forEach(function(marker) {
droneMap.removeLayer(marker);
});
}
window.waypointMarkers = [];
if (window.waypointPath) {
droneMap.removeLayer(window.waypointPath);
}
"""
path_coords = []
for i, wp in enumerate(waypoints[1:], start=1):
lat_item = QtWidgets.QTableWidgetItem(f"{wp['x']:.8f}")
lon_item = QtWidgets.QTableWidgetItem(f"{wp['y']:.8f}")
alt_item = QtWidgets.QTableWidgetItem(f"{wp['z']:.1f}")
lat_item.setTextAlignment(Qt.AlignCenter)
lon_item.setTextAlignment(Qt.AlignCenter)
alt_item.setTextAlignment(Qt.AlignCenter)
self.uiWpWindow.coordinateWidget.setItem(i-1, 0, lat_item)
self.uiWpWindow.coordinateWidget.setItem(i-1, 1, lon_item)
self.uiWpWindow.coordinateWidget.setItem(i-1, 2, alt_item)
markers_script += f"""
var marker = L.marker([{wp['x']}, {wp['y']}]).addTo(droneMap)
.bindTooltip('{i}', {{
permanent: true,
direction: 'center',
offset: [-15, -30],
className: 'waypoint-label',
opacity: 1,
interactive: false
}});
window.waypointMarkers.push(marker);
"""
path_coords.append([wp['x'], wp['y']])
if len(path_coords) > 1:
path_coords_str = str(path_coords).replace('(', '[').replace(')', ']')
markers_script += f"""
window.waypointPath = L.polyline({path_coords_str}, {{
color: 'red',
weight: 2,
opacity: 0.8
}}).addTo(droneMap);
// Tüm waypoint'leri görecek şekilde haritayı ayarla
var bounds = L.latLngBounds({path_coords_str});
droneMap.fitBounds(bounds, {{padding: [50, 50]}});
"""
self.wpWebView.page().runJavaScript(markers_script)
def readTableCoordinates(self):
coordinates = []
table = self.uiWpWindow.coordinateWidget
for row in range(table.rowCount()):
lat_item = table.item(row, 0)
lon_item = table.item(row, 1)
alt_item = table.item(row, 2)
if lat_item and lon_item and alt_item and lat_item.text() and lon_item.text() and alt_item.text():
try:
lat = float(lat_item.text())
lon = float(lon_item.text())
alt = float(alt_item.text())
coordinates.append((lat, lon, alt))
except ValueError:
continue
return coordinates
def wpYukle(self):
coordinates = self.readTableCoordinates()
if not coordinates:
msg = QtWidgets.QMessageBox()
msg.setIcon(QtWidgets.QMessageBox.Warning)
msg.setText("Tabloda geçerli koordinat bulunamadı.")
msg.setWindowTitle("Uyarı")
msg.exec_()
return
self.uiWpWindow.yukleButton.setEnabled(False)
self.uiWpWindow.yukleButton.setText("Yükleniyor...")
self.wpSettingsWindow = QtWidgets.QMainWindow()
self.uiWpSettingsWindow = Ui_WaypointsSettingWindow()
self.uiWpSettingsWindow.setupUi(self.wpSettingsWindow)
self.wpSettingsWindow.show()
self.wpSettingsWindow.repaint()
screen = QtWidgets.QApplication.primaryScreen()
screen_geometry = screen.availableGeometry()
window_geometry = self.wpSettingsWindow.frameGeometry()
x = (screen_geometry.width() - window_geometry.width()) // 2
y = (screen_geometry.height() - window_geometry.height()) // 2
self.wpSettingsWindow.move(x, y)
self.uiWpSettingsWindow.settingProgressBar.setVisible(True)
self.uiWpSettingsWindow.settingProgressBar.setValue(0)
self.uiWpSettingsWindow.settingLabel.setVisible(True)
self.uiWpSettingsWindow.settingLabel.setText("Başlatılıyor...")
self.wpLoadThread = WaypointLoadThread(self.drone, coordinates)
self.wpLoadThread.finished.connect(self.onWaypointLoadFinished)
self.wpLoadThread.progress.connect(self.onWaypointLoadProgress)
self.wpLoadThread.start()
def onWaypointLoadProgress(self, progress, message):
self.uiWpSettingsWindow.settingProgressBar.setValue(progress)
self.uiWpSettingsWindow.settingLabel.setText(message)
def onWaypointLoadFinished(self, success):
self.uiWpWindow.yukleButton.setEnabled(True)
self.uiWpWindow.yukleButton.setText("Yükle")
if hasattr(self, 'wpSettingsWindow'):
QtCore.QTimer.singleShot(1000, self.wpSettingsWindow.close)
if success:
coordinates = self.readTableCoordinates()
if coordinates:
markers_script = """
if (window.waypointMarkers) {
window.waypointMarkers.forEach(function(marker) {
droneMap.removeLayer(marker);
});
}
window.waypointMarkers = [];
"""
# Waypoint markerları
for i, (lat, lon, alt) in enumerate(coordinates, 1):
markers_script += f"""
var marker = L.marker([{lat}, {lon}]).addTo(droneMap)
.bindTooltip('{i}', {{
permanent: true,
direction: 'center',
offset: [-15, -30],
className: 'waypoint-label',
opacity: 1,
interactive: false
}});
window.waypointMarkers.push(marker);
"""
if len(coordinates) > 1:
path_coords = [[lat, lon] for lat, lon, _ in coordinates]
path_coords_str = str(path_coords).replace('(', '[').replace(')', ']')
markers_script += f"""
if (window.waypointPath) {{
droneMap.removeLayer(window.waypointPath);
}}
window.waypointPath = L.polyline({path_coords_str}, {{
color: 'red',
weight: 2,
opacity: 0.8
}}).addTo(droneMap);
"""
self.webView.page().runJavaScript(markers_script)
def rtl(self):
if self.droneConnected is False:
msg = QtWidgets.QMessageBox()
msg.setIcon(QtWidgets.QMessageBox.Critical)
msg.setText("Lütfen önce drone'a bağlanın.")
msg.setWindowTitle("Uyarı")
msg.exec_()
else:
index = self.ui.modCombo.findText("RTL")
self.ui.modCombo.setCurrentIndex(index)
self.modeChange()
def closeEvent(self, event):
if hasattr(self, 'map_thread') and self.map_thread:
self.map_thread.stop()
self.map_thread.wait()
if hasattr(self, 'cameraThread'):
self.cameraThread.stop()
self.cameraThread.wait()
event.accept()
@pyqtSlot(QImage)
def setImage(self, image):
self.ui.cameraLabel.setPixmap(QPixmap.fromImage(image))
def initUI(self):
self.setWindowTitle(self.title)
self.setGeometry(self.left, self.top, self.width, self.height)
self.resize(1800, 1200)
self.ui.cameraLabel.resize(640, 480)
th = CameraThread(self)
th.changePixmap.connect(self.setImage)
th.start()
self.show()
def modeChange(self):
if self.droneConnected is False:
msg = QtWidgets.QMessageBox()
msg.setIcon(QtWidgets.QMessageBox.Critical)
msg.setText("Lütfen önce drone'a bağlanın.")
msg.setWindowTitle("Uyarı")
msg.exec_()
else:
self.ui.modLabel.setText("<html><head/><body><p><span style=\" font-weight:600; color:#fffe08;\">Mod ayarlanıyor...</span></p></body></html>")
self.modeThread = ModeChangeThread(self.drone, self.ui.modLabel, self.ui.modCombo)
self.modeThread.modeChanged.connect(self.onModeChanged)
self.modeThread.start()
def onModeChanged(self):
self.ui.modLabel.setText(f'<html><head/><body><p><span style=" font-weight:600; text-decoration: underline;">Şuanki mod</span><span style=" font-weight:600;">: </span><span style=" font-weight:600; color:#42FF2F;">{self.drone.mode}</span></p></body></html>')
self.tabloItemEkle(f"Mod değiştirildi. Yeni mod: {self.drone.mode}")
def connect(self):
if self.droneConnected is False:
self.connectingWindow = QtWidgets.QMainWindow()
self.uiConnectingWindow = Ui_ConnectingWindow()
self.uiConnectingWindow.setupUi(self.connectingWindow)
self.connectingWindow.show()
# Progress bar'ı sıfırla
self.uiConnectingWindow.parameterProgressBar.setValue(0)
# Pencereyi ortala
self.connectingWindow.repaint()
screen = QtWidgets.QApplication.primaryScreen()
screen_geometry = screen.availableGeometry()
window_geometry = self.connectingWindow.frameGeometry()
x = (screen_geometry.width() - window_geometry.width()) // 2
y = (screen_geometry.height() - window_geometry.height()) // 2
self.connectingWindow.move(x, y)
self.port = self.ui.PortCombo.currentText()
self.baudRate = int(self.ui.BaudrateCombo.currentText())
self.paramThread = ParamLoadThread(self.port, self.baudRate)
self.paramThread.progress_update.connect(self.updateLoadingText)
self.paramThread.progress_bar_update.connect(self.updateProgressBar)
self.paramThread.finished.connect(self.onConnectionFinished)
self.paramThread.start()