|
|
|
|
@ -4,8 +4,8 @@ from PyQt6.QtWidgets import (QApplication, QMainWindow, QVBoxLayout, QHBoxLayout
|
|
|
|
|
QWidget, QLabel, QSplitter, QScrollArea,
|
|
|
|
|
QSizePolicy, QTabWidget, QTableWidget, QTableWidgetItem,
|
|
|
|
|
QHeaderView, QPushButton, QCheckBox, QLineEdit,
|
|
|
|
|
QComboBox, QDialog)
|
|
|
|
|
from PyQt6.QtCore import Qt, QTimer
|
|
|
|
|
QComboBox, QDialog, QPlainTextEdit)
|
|
|
|
|
from PyQt6.QtCore import Qt, QTimer, QObject, pyqtSignal
|
|
|
|
|
from PyQt6.QtGui import QColor
|
|
|
|
|
import sys
|
|
|
|
|
import asyncio
|
|
|
|
|
@ -14,6 +14,11 @@ import subprocess
|
|
|
|
|
import time
|
|
|
|
|
import traceback
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
def _log(level, message):
|
|
|
|
|
print(f"[{level}] {message}", flush=True)
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
# 導入分離的類別
|
|
|
|
|
from communication import DroneMonitor, UDPMavlinkReceiver, WebSocketMavlinkReceiver
|
|
|
|
|
from map_layout import DroneMap
|
|
|
|
|
@ -32,8 +37,41 @@ from mission_group import (
|
|
|
|
|
)
|
|
|
|
|
# ================================================================================
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
class StreamRedirector(QObject):
|
|
|
|
|
"""將 stdout/stderr 同步轉發到 Qt UI。"""
|
|
|
|
|
text_written = pyqtSignal(str)
|
|
|
|
|
|
|
|
|
|
def __init__(self, original_stream=None, parent=None):
|
|
|
|
|
super().__init__(parent)
|
|
|
|
|
self.original_stream = original_stream
|
|
|
|
|
self._buffer = ""
|
|
|
|
|
|
|
|
|
|
def write(self, text):
|
|
|
|
|
if self.original_stream:
|
|
|
|
|
self.original_stream.write(text)
|
|
|
|
|
|
|
|
|
|
if not text:
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
self._buffer += text
|
|
|
|
|
while "\n" in self._buffer:
|
|
|
|
|
line, self._buffer = self._buffer.split("\n", 1)
|
|
|
|
|
line = line.strip()
|
|
|
|
|
if line:
|
|
|
|
|
self.text_written.emit(line)
|
|
|
|
|
|
|
|
|
|
def flush(self):
|
|
|
|
|
if self.original_stream:
|
|
|
|
|
self.original_stream.flush()
|
|
|
|
|
|
|
|
|
|
line = self._buffer.strip()
|
|
|
|
|
if line:
|
|
|
|
|
self.text_written.emit(line)
|
|
|
|
|
self._buffer = ""
|
|
|
|
|
|
|
|
|
|
class ControlStationUI(QMainWindow):
|
|
|
|
|
VERSION = '2.0.8'
|
|
|
|
|
VERSION = '2.1.0'
|
|
|
|
|
|
|
|
|
|
def __init__(self):
|
|
|
|
|
super().__init__()
|
|
|
|
|
@ -78,6 +116,8 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
|
|
|
|
|
# 快取消息數據,以便在沒有新消息時使用上一次的值
|
|
|
|
|
self._message_cache = {}
|
|
|
|
|
self.message_history = []
|
|
|
|
|
self.max_message_history = 500
|
|
|
|
|
|
|
|
|
|
# 初始化UI
|
|
|
|
|
self.drones = {}
|
|
|
|
|
@ -137,6 +177,7 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
# ================================================================================
|
|
|
|
|
|
|
|
|
|
self.init_ui()
|
|
|
|
|
self._setup_stream_redirector()
|
|
|
|
|
|
|
|
|
|
def init_ui(self):
|
|
|
|
|
main_splitter = QSplitter(Qt.Orientation.Horizontal)
|
|
|
|
|
@ -160,7 +201,11 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
self.overview_table = OverviewTable()
|
|
|
|
|
self.left_tab.addTab(self.overview_table, "總覽")
|
|
|
|
|
|
|
|
|
|
# — 分頁 3:通訊設定
|
|
|
|
|
# — 分頁 3:訊息歷史
|
|
|
|
|
self.message_history_tab = self._create_message_history_tab()
|
|
|
|
|
self.left_tab.addTab(self.message_history_tab, "紀錄")
|
|
|
|
|
|
|
|
|
|
# — 分頁 4:通訊設定
|
|
|
|
|
self.comm_panel = CommPanel()
|
|
|
|
|
self.comm_panel.udp_connection_added.connect(self.handle_udp_connection_added)
|
|
|
|
|
self.comm_panel.ws_connection_added.connect(self.handle_ws_connection_added)
|
|
|
|
|
@ -259,6 +304,95 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
main_splitter.setSizes([400, 1000])
|
|
|
|
|
|
|
|
|
|
self.setCentralWidget(main_splitter)
|
|
|
|
|
self.statusBar().messageChanged.connect(self._on_status_bar_message_changed)
|
|
|
|
|
|
|
|
|
|
def _create_message_history_tab(self):
|
|
|
|
|
"""建立左側訊息歷史分頁。"""
|
|
|
|
|
widget = QWidget()
|
|
|
|
|
layout = QVBoxLayout(widget)
|
|
|
|
|
layout.setContentsMargins(10, 10, 10, 10)
|
|
|
|
|
layout.setSpacing(8)
|
|
|
|
|
|
|
|
|
|
header_layout = QHBoxLayout()
|
|
|
|
|
title = QLabel("操作與訊息歷史")
|
|
|
|
|
title.setStyleSheet("color: #DDD; font-size: 14px; font-weight: bold;")
|
|
|
|
|
header_layout.addWidget(title)
|
|
|
|
|
header_layout.addStretch()
|
|
|
|
|
|
|
|
|
|
clear_btn = QPushButton("清空")
|
|
|
|
|
clear_btn.setStyleSheet("""
|
|
|
|
|
QPushButton { background-color: #555; color: white; border: none;
|
|
|
|
|
padding: 5px 10px; border-radius: 4px; font-size: 12px; }
|
|
|
|
|
QPushButton:hover { background-color: #666; }
|
|
|
|
|
""")
|
|
|
|
|
clear_btn.clicked.connect(self._clear_message_history)
|
|
|
|
|
header_layout.addWidget(clear_btn)
|
|
|
|
|
layout.addLayout(header_layout)
|
|
|
|
|
|
|
|
|
|
self.message_history_view = QPlainTextEdit()
|
|
|
|
|
self.message_history_view.setReadOnly(True)
|
|
|
|
|
self.message_history_view.setStyleSheet("""
|
|
|
|
|
QPlainTextEdit {
|
|
|
|
|
background-color: #1E1E1E;
|
|
|
|
|
color: #DDD;
|
|
|
|
|
border: 1px solid #444;
|
|
|
|
|
border-radius: 6px;
|
|
|
|
|
padding: 6px;
|
|
|
|
|
font-family: monospace;
|
|
|
|
|
font-size: 12px;
|
|
|
|
|
}
|
|
|
|
|
""")
|
|
|
|
|
self.message_history_view.setPlaceholderText("左下角狀態訊息會顯示在這裡...")
|
|
|
|
|
layout.addWidget(self.message_history_view)
|
|
|
|
|
|
|
|
|
|
return widget
|
|
|
|
|
|
|
|
|
|
def _clear_message_history(self):
|
|
|
|
|
"""清空訊息歷史。"""
|
|
|
|
|
self.message_history.clear()
|
|
|
|
|
if hasattr(self, 'message_history_view'):
|
|
|
|
|
self.message_history_view.clear()
|
|
|
|
|
|
|
|
|
|
def _on_status_bar_message_changed(self, message):
|
|
|
|
|
"""同步狀態列訊息到歷史紀錄。"""
|
|
|
|
|
if not message:
|
|
|
|
|
return
|
|
|
|
|
timestamp = time.strftime("%H:%M:%S")
|
|
|
|
|
entry = f"[{timestamp}] {message}"
|
|
|
|
|
self.message_history.append(entry)
|
|
|
|
|
if len(self.message_history) > self.max_message_history:
|
|
|
|
|
self.message_history = self.message_history[-self.max_message_history:]
|
|
|
|
|
|
|
|
|
|
if hasattr(self, 'message_history_view'):
|
|
|
|
|
self.message_history_view.setPlainText("\n".join(self.message_history))
|
|
|
|
|
scrollbar = self.message_history_view.verticalScrollBar()
|
|
|
|
|
scrollbar.setValue(scrollbar.maximum())
|
|
|
|
|
|
|
|
|
|
def _setup_stream_redirector(self):
|
|
|
|
|
"""將 stdout/stderr 同步到左下角狀態列與訊息紀錄。"""
|
|
|
|
|
self._original_stdout = sys.stdout
|
|
|
|
|
self._original_stderr = sys.stderr
|
|
|
|
|
|
|
|
|
|
self.stdout_redirector = StreamRedirector(self._original_stdout, self)
|
|
|
|
|
self.stderr_redirector = StreamRedirector(self._original_stderr, self)
|
|
|
|
|
self.stdout_redirector.text_written.connect(self.show_in_bottom_left)
|
|
|
|
|
self.stderr_redirector.text_written.connect(self.show_in_bottom_left)
|
|
|
|
|
|
|
|
|
|
sys.stdout = self.stdout_redirector
|
|
|
|
|
sys.stderr = self.stderr_redirector
|
|
|
|
|
|
|
|
|
|
def _restore_stream_redirector(self):
|
|
|
|
|
"""還原 stdout/stderr,避免關閉視窗後仍寫入 UI。"""
|
|
|
|
|
if getattr(self, '_original_stdout', None) is not None:
|
|
|
|
|
sys.stdout = self._original_stdout
|
|
|
|
|
if getattr(self, '_original_stderr', None) is not None:
|
|
|
|
|
sys.stderr = self._original_stderr
|
|
|
|
|
|
|
|
|
|
def show_in_bottom_left(self, text):
|
|
|
|
|
"""將重導向的輸出顯示在左下角狀態列。"""
|
|
|
|
|
if not text:
|
|
|
|
|
return
|
|
|
|
|
self.statusBar().showMessage(text, 5000)
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
# ================================================================================
|
|
|
|
|
@ -384,7 +518,7 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
status_label.setToolTip("運行中")
|
|
|
|
|
self.statusBar().showMessage(f"已啟動 Serial 連接: {conn['port']}", 3000)
|
|
|
|
|
except Exception as e:
|
|
|
|
|
print(f"❌ Serial 連接啟動失敗: {str(e)}")
|
|
|
|
|
_log("ERROR", f"Serial 連接啟動失敗: {str(e)}")
|
|
|
|
|
traceback.print_exc()
|
|
|
|
|
self.statusBar().showMessage(f"啟動 Serial 連接失敗: {str(e)}", 5000)
|
|
|
|
|
|
|
|
|
|
@ -410,39 +544,25 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
# ================================================================================
|
|
|
|
|
|
|
|
|
|
def handle_mode_change(self, drone_id):
|
|
|
|
|
print(f"\n📢 [GUI] handle_mode_change 被调用")
|
|
|
|
|
print(f" drone_id: {drone_id}")
|
|
|
|
|
|
|
|
|
|
# 從 active group 的 mode_combo 讀取模式
|
|
|
|
|
group = self._get_active_group()
|
|
|
|
|
if group:
|
|
|
|
|
panel = self.group_panels.get(group.group_id)
|
|
|
|
|
mode = panel.mode_combo.currentText() if panel else "GUIDED"
|
|
|
|
|
print(f" 从群组读取模式: {mode}")
|
|
|
|
|
else:
|
|
|
|
|
mode = "GUIDED"
|
|
|
|
|
print(f" 没有活跃群组,使用默认模式: {mode}")
|
|
|
|
|
|
|
|
|
|
_log("INFO", f"切換模式請求: drone={drone_id}, mode={mode}")
|
|
|
|
|
loop = asyncio.get_event_loop()
|
|
|
|
|
future = self.monitor.set_mode(drone_id, mode)
|
|
|
|
|
loop.create_task(self.handle_service_response(future, f"切換模式 {mode} {drone_id}"))
|
|
|
|
|
|
|
|
|
|
def handle_arm(self, drone_id):
|
|
|
|
|
print(f"\n📢 [GUI] handle_arm 被調用")
|
|
|
|
|
print(f" drone_id: {drone_id}")
|
|
|
|
|
loop = asyncio.get_event_loop()
|
|
|
|
|
print(f" 獲得事件循環: {loop}")
|
|
|
|
|
arm_state = not self.monitor.get_arm_state(drone_id)
|
|
|
|
|
print(f" 當前鎖定狀態: {not arm_state}, 目標狀態: {arm_state}")
|
|
|
|
|
print(f" 準備調用 arm_drone(drone_id={drone_id}, arm={arm_state})")
|
|
|
|
|
coro = self.monitor.arm_drone(drone_id, arm_state)
|
|
|
|
|
print(f" arm_drone() 返回類型: {type(coro)}")
|
|
|
|
|
print(f" coroutine 對象: {coro}")
|
|
|
|
|
action_text = f"{'解鎖' if arm_state else '上鎖'} {drone_id}"
|
|
|
|
|
print(f" 準備提交到事件循環: {action_text}")
|
|
|
|
|
task = loop.create_task(self.handle_service_response(coro, action_text))
|
|
|
|
|
print(f" task 已創建: {task}")
|
|
|
|
|
print(f" 已提交到事件循環\n")
|
|
|
|
|
_log("INFO", f"{action_text} 請求已送出")
|
|
|
|
|
loop.create_task(self.handle_service_response(coro, action_text))
|
|
|
|
|
|
|
|
|
|
def handle_takeoff(self, drone_id):
|
|
|
|
|
loop = asyncio.get_event_loop()
|
|
|
|
|
@ -453,7 +573,7 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
"""發送位置命令到 active group 的所有選中無人機"""
|
|
|
|
|
group = self._get_active_group()
|
|
|
|
|
if not group:
|
|
|
|
|
self.statusBar().showMessage("⚠ 請先建立任務群組", 3000)
|
|
|
|
|
self.statusBar().showMessage("請先建立任務群組", 3000)
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
try:
|
|
|
|
|
@ -481,34 +601,18 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
self.statusBar().showMessage("座標格式錯誤", 3000)
|
|
|
|
|
|
|
|
|
|
async def handle_service_response(self, future, action):
|
|
|
|
|
print(f"\n📥 [GUI] handle_service_response 開始處理: {action}")
|
|
|
|
|
print(f" Future/Coroutine 類型: {type(future)}")
|
|
|
|
|
print(f" Future/Coroutine 對象: {future}")
|
|
|
|
|
try:
|
|
|
|
|
print(f" ├─ 等待 future/coroutine 完成...")
|
|
|
|
|
print(f" └─ (這是一個阻塞等待,直到服務返回)\n")
|
|
|
|
|
result = await future
|
|
|
|
|
print(f"\n ✓ Future/Coroutine 完成,接收到返回值!")
|
|
|
|
|
print(f" ├─ 返回值類型: {type(result)}")
|
|
|
|
|
print(f" ├─ 返回值內容: {result}")
|
|
|
|
|
print(f" ├─ 返回值 == True: {result == True}")
|
|
|
|
|
print(f" ├─ 返回值 is True: {result is True}")
|
|
|
|
|
print(f" └─ bool(返回值): {bool(result)}")
|
|
|
|
|
|
|
|
|
|
# 詳細檢查 result 結構(用於調試 fc_network 回傳值)
|
|
|
|
|
if hasattr(result, '__dict__'):
|
|
|
|
|
print(f" └─ 返回值屬性: {result.__dict__}")
|
|
|
|
|
|
|
|
|
|
if result:
|
|
|
|
|
print(f"\n✅ {action} 成功 (result={result})")
|
|
|
|
|
_log("INFO", f"{action} 成功")
|
|
|
|
|
self.statusBar().showMessage(f"{action} 成功", 3000)
|
|
|
|
|
else:
|
|
|
|
|
print(f"\n❌ {action} 失敗 (result={result})")
|
|
|
|
|
_log("WARN", f"{action} 失敗")
|
|
|
|
|
self.statusBar().showMessage(f"{action} 失敗", 3000)
|
|
|
|
|
except asyncio.CancelledError:
|
|
|
|
|
print(f"⚠️ {action} 被取消")
|
|
|
|
|
_log("WARN", f"{action} 已取消")
|
|
|
|
|
except Exception as e:
|
|
|
|
|
print(f"❌ {action} 錯誤: {str(e)}")
|
|
|
|
|
_log("ERROR", f"{action} 錯誤: {str(e)}")
|
|
|
|
|
traceback.print_exc()
|
|
|
|
|
self.statusBar().showMessage(f"{action} 錯誤: {str(e)}", 3000)
|
|
|
|
|
|
|
|
|
|
@ -516,38 +620,33 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
"""解鎖 active group 的所有選中無人機"""
|
|
|
|
|
group = self._get_active_group()
|
|
|
|
|
if not group:
|
|
|
|
|
self.statusBar().showMessage("⚠ 請先建立任務群組", 3000)
|
|
|
|
|
self.statusBar().showMessage("請先建立任務群組", 3000)
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
selected = list(group.selected_drone_ids)
|
|
|
|
|
if not selected:
|
|
|
|
|
self.statusBar().showMessage("⚠ 尚未選擇任何無人機", 3000)
|
|
|
|
|
self.statusBar().showMessage("尚未選擇任何無人機", 3000)
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
print(f"\n📢 [GUI] handle_arm_selected 被調用")
|
|
|
|
|
print(f" 已選擇的無人機: {selected}")
|
|
|
|
|
_log("INFO", f"批次解鎖請求: {', '.join(selected)}")
|
|
|
|
|
loop = asyncio.get_event_loop()
|
|
|
|
|
for drone_id in selected:
|
|
|
|
|
print(f" 準備批次解鎖: {drone_id}")
|
|
|
|
|
coro = self.monitor.arm_drone(drone_id, True)
|
|
|
|
|
print(f" arm_drone 返回: {coro}")
|
|
|
|
|
# 使用 run_coroutine_threadsafe() 正確地在事件循環中運行
|
|
|
|
|
asyncio.run_coroutine_threadsafe(
|
|
|
|
|
self.handle_service_response(coro, f"批次解鎖 {drone_id}"),
|
|
|
|
|
loop
|
|
|
|
|
)
|
|
|
|
|
print(f" handle_arm_selected 完成\n")
|
|
|
|
|
|
|
|
|
|
def handle_takeoff_selected(self):
|
|
|
|
|
"""起飛 active group 的所有選中無人機"""
|
|
|
|
|
group = self._get_active_group()
|
|
|
|
|
if not group:
|
|
|
|
|
self.statusBar().showMessage("⚠ 請先建立任務群組", 3000)
|
|
|
|
|
self.statusBar().showMessage("請先建立任務群組", 3000)
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
selected = list(group.selected_drone_ids)
|
|
|
|
|
if not selected:
|
|
|
|
|
self.statusBar().showMessage("⚠ 尚未選擇任何無人機", 3000)
|
|
|
|
|
self.statusBar().showMessage("尚未選擇任何無人機", 3000)
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
loop = asyncio.get_event_loop()
|
|
|
|
|
@ -774,7 +873,7 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
|
|
|
|
|
if blocked:
|
|
|
|
|
self.statusBar().showMessage(
|
|
|
|
|
f"⚠ Group {group_id}: {len(blocked)} 台已被其他 group 勾選,未加入", 4000
|
|
|
|
|
f"Group {group_id}: {len(blocked)} 台已被其他 group 勾選,未加入", 4000
|
|
|
|
|
)
|
|
|
|
|
else:
|
|
|
|
|
self.statusBar().showMessage(
|
|
|
|
|
@ -811,7 +910,7 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
if not group:
|
|
|
|
|
return
|
|
|
|
|
if group.planned_waypoints is None:
|
|
|
|
|
self.statusBar().showMessage(f"⚠ Group {group_id}: 請先規劃任務", 3000)
|
|
|
|
|
self.statusBar().showMessage(f"Group {group_id}: 請先規劃任務", 3000)
|
|
|
|
|
return
|
|
|
|
|
if group.executor is None:
|
|
|
|
|
self._create_executor_for_group(group)
|
|
|
|
|
@ -819,7 +918,7 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
panel = self.group_panels.get(group_id)
|
|
|
|
|
if panel:
|
|
|
|
|
panel.update_status()
|
|
|
|
|
self.statusBar().showMessage(f"🚀 Group {group_id}: 任務已啟動", 3000)
|
|
|
|
|
self.statusBar().showMessage(f"Group {group_id}: 任務已啟動", 3000)
|
|
|
|
|
|
|
|
|
|
def _handle_group_pause(self, group_id):
|
|
|
|
|
"""暫停/恢復群組任務"""
|
|
|
|
|
@ -828,10 +927,10 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
return
|
|
|
|
|
if group.executor.state == MissionState.RUNNING:
|
|
|
|
|
group.executor.pause()
|
|
|
|
|
self.statusBar().showMessage(f"⏸ Group {group_id}: 任務已暫停", 3000)
|
|
|
|
|
self.statusBar().showMessage(f"Group {group_id}: 任務已暫停", 3000)
|
|
|
|
|
elif group.executor.state == MissionState.PAUSED:
|
|
|
|
|
group.executor.resume()
|
|
|
|
|
self.statusBar().showMessage(f"▶ Group {group_id}: 任務已恢復", 3000)
|
|
|
|
|
self.statusBar().showMessage(f"Group {group_id}: 任務已恢復", 3000)
|
|
|
|
|
panel = self.group_panels.get(group_id)
|
|
|
|
|
if panel:
|
|
|
|
|
panel.update_status()
|
|
|
|
|
@ -849,54 +948,44 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
if panel:
|
|
|
|
|
panel.update_status()
|
|
|
|
|
panel.clear_mission_info()
|
|
|
|
|
self.statusBar().showMessage(f"■ Group {group_id}: 任務已停止", 3000)
|
|
|
|
|
self.statusBar().showMessage(f"Group {group_id}: 任務已停止", 3000)
|
|
|
|
|
|
|
|
|
|
def _handle_group_mode_change(self, group_id, mode):
|
|
|
|
|
"""切換群組內所有無人機的飛行模式"""
|
|
|
|
|
print(f"\n📢 [GUI] _handle_group_mode_change 被调用", flush=True)
|
|
|
|
|
print(f" group_id: {group_id}, mode: {mode}", flush=True)
|
|
|
|
|
|
|
|
|
|
group = self.mission_groups.get(group_id)
|
|
|
|
|
if not group:
|
|
|
|
|
print(f"❌ 找不到群組: {group_id}", flush=True)
|
|
|
|
|
_log("ERROR", f"找不到群組: {group_id}")
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
if not group.selected_drone_ids:
|
|
|
|
|
print(f"⚠️ 群組中沒有無人機", flush=True)
|
|
|
|
|
_log("WARN", f"Group {group_id} 中沒有無人機")
|
|
|
|
|
self.statusBar().showMessage(f"群組 {group_id} 中沒有無人機", 3000)
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
print(f" 準備為 {len(group.selected_drone_ids)} 台無人機切換模式...", flush=True)
|
|
|
|
|
self.statusBar().showMessage(f"正在切換模式...", 1000)
|
|
|
|
|
_log("INFO", f"Group {group_id} 準備切換模式為 {mode}")
|
|
|
|
|
self.statusBar().showMessage("正在切換模式", 1000)
|
|
|
|
|
|
|
|
|
|
# 使用 asyncio 執行(通過事件循環)
|
|
|
|
|
async def do_mode_changes_async():
|
|
|
|
|
print(f"\n 【異步任務】開始執行模式切換", flush=True)
|
|
|
|
|
|
|
|
|
|
for drone_id in group.selected_drone_ids:
|
|
|
|
|
print(f"\n 【切換】{drone_id} → {mode}", flush=True)
|
|
|
|
|
try:
|
|
|
|
|
result = await self.monitor.set_mode(drone_id, mode)
|
|
|
|
|
|
|
|
|
|
if result:
|
|
|
|
|
msg = f"✅ {drone_id} 切換成功"
|
|
|
|
|
print(f" {msg}", flush=True)
|
|
|
|
|
msg = f"{drone_id} 切換成功"
|
|
|
|
|
_log("INFO", msg)
|
|
|
|
|
self.message_queue.put((msg, 2000))
|
|
|
|
|
else:
|
|
|
|
|
msg = f"❌ {drone_id} 切換失敗"
|
|
|
|
|
print(f" {msg}", flush=True)
|
|
|
|
|
msg = f"{drone_id} 切換失敗"
|
|
|
|
|
_log("WARN", msg)
|
|
|
|
|
self.message_queue.put((msg, 2000))
|
|
|
|
|
|
|
|
|
|
except Exception as e:
|
|
|
|
|
msg = f"❌ {drone_id} 錯誤: {str(e)}"
|
|
|
|
|
print(f" {msg}", flush=True)
|
|
|
|
|
msg = f"{drone_id} 錯誤: {str(e)}"
|
|
|
|
|
_log("ERROR", msg)
|
|
|
|
|
traceback.print_exc()
|
|
|
|
|
self.message_queue.put((msg, 2000))
|
|
|
|
|
|
|
|
|
|
print(f"\n 【完成】模式切換任務結束\n", flush=True)
|
|
|
|
|
|
|
|
|
|
# 通過事件循環提交異步任務
|
|
|
|
|
print(f" 【排隊】將任務提交至事件循環", flush=True)
|
|
|
|
|
loop = asyncio.get_event_loop()
|
|
|
|
|
asyncio.run_coroutine_threadsafe(
|
|
|
|
|
do_mode_changes_async(),
|
|
|
|
|
@ -905,34 +994,22 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
|
|
|
|
|
def _handle_group_arm(self, group_id):
|
|
|
|
|
"""解鎖群組內所有無人機"""
|
|
|
|
|
print(f"\n📢 [GUI] _handle_group_arm 被調用")
|
|
|
|
|
print(f" 群組 ID: {group_id}")
|
|
|
|
|
group = self.mission_groups.get(group_id)
|
|
|
|
|
print(f" 群組存在: {group is not None}")
|
|
|
|
|
if not group:
|
|
|
|
|
print(f" ⚠️ 群組不存在,返回\n")
|
|
|
|
|
_log("WARN", f"找不到群組: {group_id}")
|
|
|
|
|
return
|
|
|
|
|
print(f" 群組內無人機: {group.selected_drone_ids}")
|
|
|
|
|
loop = asyncio.get_event_loop()
|
|
|
|
|
print(f" 事件循環: {loop}")
|
|
|
|
|
_log("INFO", f"Group {group_id} 批次解鎖 {len(group.selected_drone_ids)} 台無人機")
|
|
|
|
|
|
|
|
|
|
for drone_id in group.selected_drone_ids:
|
|
|
|
|
print(f"\n ┌─ 處理無人機: {drone_id}")
|
|
|
|
|
print(f" ├─ 準備調用 arm_drone(drone_id={drone_id}, arm=True)")
|
|
|
|
|
coro = self.monitor.arm_drone(drone_id, True)
|
|
|
|
|
print(f" ├─ arm_drone 返回類型: {type(coro)}")
|
|
|
|
|
action_text = f"解鎖 {drone_id}"
|
|
|
|
|
print(f" ├─ 準備提交到事件循環: {action_text}")
|
|
|
|
|
# 使用 run_coroutine_threadsafe() 正確地在事件循環中運行 coroutine
|
|
|
|
|
# 這是 Qt + asyncio 整合的正確方式
|
|
|
|
|
future = asyncio.run_coroutine_threadsafe(
|
|
|
|
|
asyncio.run_coroutine_threadsafe(
|
|
|
|
|
self.handle_service_response(coro, action_text),
|
|
|
|
|
loop
|
|
|
|
|
)
|
|
|
|
|
print(f" ├─ Future 已創建: {future}")
|
|
|
|
|
print(f" └─ Future 將在事件循環中執行")
|
|
|
|
|
|
|
|
|
|
print(f"\n _handle_group_arm 完成(coroutine 已提交至事件循環)\n")
|
|
|
|
|
|
|
|
|
|
def _handle_group_takeoff(self, group_id, altitude):
|
|
|
|
|
"""群組內所有無人機起飛"""
|
|
|
|
|
@ -983,7 +1060,7 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
|
|
|
|
|
if blocked:
|
|
|
|
|
self.statusBar().showMessage(
|
|
|
|
|
f"⚠ Group {group_id}: 部分 drone 已被其他 group 勾選,僅加入 {len(allowed)} 台", 4000
|
|
|
|
|
f"Group {group_id}: 部分 drone 已被其他 group 勾選,僅加入 {len(allowed)} 台", 4000
|
|
|
|
|
)
|
|
|
|
|
else:
|
|
|
|
|
self.statusBar().showMessage(
|
|
|
|
|
@ -1049,7 +1126,7 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
"""刪除一個任務群組"""
|
|
|
|
|
# 檢查是否只有一個群組,如果是就禁止刪除
|
|
|
|
|
if len(self.mission_groups) <= 1:
|
|
|
|
|
self.statusBar().showMessage("⚠️ 至少需要保留一個群組!", 3000)
|
|
|
|
|
self.statusBar().showMessage("至少需要保留一個群組", 3000)
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
if group_id not in self.mission_groups:
|
|
|
|
|
@ -1100,7 +1177,7 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
panel = self.group_panels.get(group_id)
|
|
|
|
|
if panel:
|
|
|
|
|
panel.update_status()
|
|
|
|
|
self.statusBar().showMessage(f"✅ Group {group_id}: 所有無人機已完成任務", 5000)
|
|
|
|
|
self.statusBar().showMessage(f"Group {group_id}: 所有無人機已完成任務", 5000)
|
|
|
|
|
|
|
|
|
|
# ================================================================================
|
|
|
|
|
# UI 更新
|
|
|
|
|
@ -1152,7 +1229,7 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
if not selectable:
|
|
|
|
|
if blocked:
|
|
|
|
|
self.statusBar().showMessage(
|
|
|
|
|
f"⚠ Socket {socket_id} 的 drone 已被其他 group 勾選,無法操作", 4000
|
|
|
|
|
f"Socket {socket_id} 的 drone 已被其他 group 勾選,無法操作", 4000
|
|
|
|
|
)
|
|
|
|
|
self.refresh_selection_ui()
|
|
|
|
|
return
|
|
|
|
|
@ -1165,7 +1242,7 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
group.selected_drone_ids.update(selectable)
|
|
|
|
|
if blocked:
|
|
|
|
|
self.statusBar().showMessage(
|
|
|
|
|
f"⚠ 以下 drone 已被其他 group 勾選,略過: {', '.join(blocked)}", 4000
|
|
|
|
|
f"以下 drone 已被其他 group 勾選,略過: {', '.join(blocked)}", 4000
|
|
|
|
|
)
|
|
|
|
|
|
|
|
|
|
self.refresh_selection_ui()
|
|
|
|
|
@ -1217,7 +1294,7 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
if is_checked:
|
|
|
|
|
if self._is_drone_selected_by_other_group(drone_id, group.group_id):
|
|
|
|
|
self.statusBar().showMessage(
|
|
|
|
|
f"⚠ {drone_id} 已被其他 group 勾選,無法加入 Group {group.group_id}", 3000
|
|
|
|
|
f"{drone_id} 已被其他 group 勾選,無法加入 Group {group.group_id}", 3000
|
|
|
|
|
)
|
|
|
|
|
self.refresh_selection_ui()
|
|
|
|
|
return
|
|
|
|
|
@ -1239,7 +1316,7 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
# 嘗試勾選前先檢查是否被其他 group 使用
|
|
|
|
|
if self._is_drone_selected_by_other_group(drone_id, group.group_id):
|
|
|
|
|
self.statusBar().showMessage(
|
|
|
|
|
f"⚠ {drone_id} 已被其他 group 勾選,無法加入 Group {group.group_id}", 3000
|
|
|
|
|
f"{drone_id} 已被其他 group 勾選,無法加入 Group {group.group_id}", 3000
|
|
|
|
|
)
|
|
|
|
|
self.refresh_selection_ui()
|
|
|
|
|
return
|
|
|
|
|
@ -1285,7 +1362,7 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
"""處理地圖點擊事件 — 根據 active group 的任務類型規劃"""
|
|
|
|
|
group = self._get_active_group()
|
|
|
|
|
if not group:
|
|
|
|
|
self.statusBar().showMessage("⚠ 請先建立任務群組", 3000)
|
|
|
|
|
self.statusBar().showMessage("請先建立任務群組", 3000)
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
mode_map = {
|
|
|
|
|
@ -1298,16 +1375,16 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
|
|
|
|
|
selected_drones = self._get_group_drones(group)
|
|
|
|
|
if len(selected_drones) == 0:
|
|
|
|
|
self.statusBar().showMessage(f"⚠ Group {group.group_id}: 請先分配無人機", 3000)
|
|
|
|
|
self.statusBar().showMessage(f"Group {group.group_id}: 請先分配無人機", 3000)
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
print(f"地圖點擊: {lat:.6f}, {lon:.6f} → Group {group.group_id} ({group.mission_type})")
|
|
|
|
|
_log("INFO", f"地圖點擊: {lat:.6f}, {lon:.6f} -> Group {group.group_id} ({group.mission_type})")
|
|
|
|
|
panel = self.group_panels.get(group.group_id)
|
|
|
|
|
params = panel.get_mission_params() if panel else {}
|
|
|
|
|
base_alt = params.get('base_altitude', params.get('altitude', 10.0))
|
|
|
|
|
target_gps = (lat, lon, base_alt)
|
|
|
|
|
self.statusBar().showMessage(
|
|
|
|
|
f"⏳ Group {group.group_id}: 正在規劃 {group.mission_type} ({len(selected_drones)} 台) ...", 2000)
|
|
|
|
|
f"Group {group.group_id}: 正在規劃 {group.mission_type} ({len(selected_drones)} 台)", 2000)
|
|
|
|
|
|
|
|
|
|
try:
|
|
|
|
|
drone_gps_positions = self._collect_drone_gps(selected_drones, base_alt)
|
|
|
|
|
@ -1344,10 +1421,10 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
|
|
|
|
|
total_wps = sum(len(wps) for wps in waypoints_per_drone)
|
|
|
|
|
self.statusBar().showMessage(
|
|
|
|
|
f"✓ Group {group.group_id}: {group.mission_type} 規劃完成!{len(selected_drones)} 台,共 {total_wps} 個航點", 5000
|
|
|
|
|
f"Group {group.group_id}: {group.mission_type} 規劃完成,{len(selected_drones)} 台,共 {total_wps} 個航點", 5000
|
|
|
|
|
)
|
|
|
|
|
except Exception as e:
|
|
|
|
|
self.statusBar().showMessage(f"❌ Group {group.group_id}: 規劃失敗: {str(e)}", 5000)
|
|
|
|
|
self.statusBar().showMessage(f"Group {group.group_id}: 規劃失敗: {str(e)}", 5000)
|
|
|
|
|
traceback.print_exc()
|
|
|
|
|
|
|
|
|
|
# ================================================================================
|
|
|
|
|
@ -1357,28 +1434,28 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
def handle_rectangle_selected(self, points_json):
|
|
|
|
|
group = self._get_active_group()
|
|
|
|
|
if not group:
|
|
|
|
|
self.statusBar().showMessage("⚠ 請先建立任務群組", 3000)
|
|
|
|
|
self.statusBar().showMessage("請先建立任務群組", 3000)
|
|
|
|
|
return
|
|
|
|
|
if group.mission_type != 'GRID_SWEEP':
|
|
|
|
|
return # 非 Grid Sweep 模式不處理矩形選取
|
|
|
|
|
|
|
|
|
|
selected_drones = self._get_group_drones(group)
|
|
|
|
|
if len(selected_drones) == 0:
|
|
|
|
|
self.statusBar().showMessage(f"⚠ Group {group.group_id}: 請先分配無人機", 3000)
|
|
|
|
|
self.statusBar().showMessage(f"Group {group.group_id}: 請先分配無人機", 3000)
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
print(f"矩形選取 → Group {group.group_id}: {points_json}")
|
|
|
|
|
_log("INFO", f"矩形選取 -> Group {group.group_id}: {points_json}")
|
|
|
|
|
try:
|
|
|
|
|
rect_corners = [(p[0], p[1]) for p in json.loads(points_json)]
|
|
|
|
|
except (json.JSONDecodeError, IndexError):
|
|
|
|
|
self.statusBar().showMessage("❌ 矩形座標解析失敗", 3000)
|
|
|
|
|
self.statusBar().showMessage("矩形座標解析失敗", 3000)
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
panel = self.group_panels.get(group.group_id)
|
|
|
|
|
params = panel.get_mission_params() if panel else {}
|
|
|
|
|
base_alt = params.get('altitude', 10.0)
|
|
|
|
|
self.statusBar().showMessage(
|
|
|
|
|
f"⏳ Group {group.group_id}: 正在規劃 Grid Sweep ({len(selected_drones)} 台) ...", 2000)
|
|
|
|
|
f"Group {group.group_id}: 正在規劃 Grid Sweep ({len(selected_drones)} 台)", 2000)
|
|
|
|
|
try:
|
|
|
|
|
drone_gps_positions = self._collect_drone_gps(selected_drones, base_alt)
|
|
|
|
|
if drone_gps_positions is None:
|
|
|
|
|
@ -1419,10 +1496,10 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
|
|
|
|
|
total_wps = sum(len(wps) for wps in waypoints_per_drone)
|
|
|
|
|
self.statusBar().showMessage(
|
|
|
|
|
f"✓ Group {group.group_id}: Grid Sweep 規劃完成!{len(selected_drones)} 台,共 {total_wps} 個航點", 5000
|
|
|
|
|
f"Group {group.group_id}: Grid Sweep 規劃完成,{len(selected_drones)} 台,共 {total_wps} 個航點", 5000
|
|
|
|
|
)
|
|
|
|
|
except Exception as e:
|
|
|
|
|
self.statusBar().showMessage(f"❌ Group {group.group_id}: Grid Sweep 規劃失敗: {str(e)}", 5000)
|
|
|
|
|
self.statusBar().showMessage(f"Group {group.group_id}: Grid Sweep 規劃失敗: {str(e)}", 5000)
|
|
|
|
|
traceback.print_exc()
|
|
|
|
|
|
|
|
|
|
# ================================================================================
|
|
|
|
|
@ -1432,14 +1509,14 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
def handle_route_confirmed(self, points_json):
|
|
|
|
|
group = self._get_active_group()
|
|
|
|
|
if not group:
|
|
|
|
|
self.statusBar().showMessage("⚠ 請先建立任務群組", 3000)
|
|
|
|
|
self.statusBar().showMessage("請先建立任務群組", 3000)
|
|
|
|
|
return
|
|
|
|
|
if group.mission_type != 'LEADER_FOLLOWER':
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
selected_drones = self._get_group_drones(group)
|
|
|
|
|
if len(selected_drones) == 0:
|
|
|
|
|
self.statusBar().showMessage(f"⚠ Group {group.group_id}: 請先分配無人機", 3000)
|
|
|
|
|
self.statusBar().showMessage(f"Group {group.group_id}: 請先分配無人機", 3000)
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
# LEADER_FOLLOWER:把指定的領隊放到 rank 0
|
|
|
|
|
@ -1447,23 +1524,23 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
if leader and leader in selected_drones:
|
|
|
|
|
selected_drones = [leader] + [d for d in selected_drones if d != leader]
|
|
|
|
|
|
|
|
|
|
print(f"路徑確認 → Group {group.group_id}: {points_json}")
|
|
|
|
|
_log("INFO", f"路徑確認 -> Group {group.group_id}: {points_json}")
|
|
|
|
|
try:
|
|
|
|
|
route_points = json.loads(points_json)
|
|
|
|
|
route_waypoints = [(p[0], p[1]) for p in route_points]
|
|
|
|
|
except (json.JSONDecodeError, IndexError):
|
|
|
|
|
self.statusBar().showMessage("❌ 路徑座標解析失敗", 3000)
|
|
|
|
|
self.statusBar().showMessage("路徑座標解析失敗", 3000)
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
if len(route_waypoints) < 2:
|
|
|
|
|
self.statusBar().showMessage("⚠ 至少需要 2 個路徑點", 3000)
|
|
|
|
|
self.statusBar().showMessage("至少需要 2 個路徑點", 3000)
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
panel = self.group_panels.get(group.group_id)
|
|
|
|
|
params = panel.get_mission_params() if panel else {}
|
|
|
|
|
base_alt = params.get('altitude', 10.0)
|
|
|
|
|
self.statusBar().showMessage(
|
|
|
|
|
f"⏳ Group {group.group_id}: 正在規劃跟隨模式 ({len(selected_drones)} 台) ...", 2000)
|
|
|
|
|
f"Group {group.group_id}: 正在規劃跟隨模式 ({len(selected_drones)} 台)", 2000)
|
|
|
|
|
|
|
|
|
|
try:
|
|
|
|
|
drone_gps_positions = self._collect_drone_gps(selected_drones, base_alt)
|
|
|
|
|
@ -1507,10 +1584,10 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
|
|
|
|
|
total_wps = sum(len(wps) for wps in waypoints_per_drone)
|
|
|
|
|
self.statusBar().showMessage(
|
|
|
|
|
f"✓ Group {group.group_id}: 跟隨模式規劃完成!{len(selected_drones)} 台,共 {total_wps} 個航點", 5000
|
|
|
|
|
f"Group {group.group_id}: 跟隨模式規劃完成,{len(selected_drones)} 台,共 {total_wps} 個航點", 5000
|
|
|
|
|
)
|
|
|
|
|
except Exception as e:
|
|
|
|
|
self.statusBar().showMessage(f"❌ Group {group.group_id}: 跟隨模式規劃失敗: {str(e)}", 5000)
|
|
|
|
|
self.statusBar().showMessage(f"Group {group.group_id}: 跟隨模式規劃失敗: {str(e)}", 5000)
|
|
|
|
|
traceback.print_exc()
|
|
|
|
|
|
|
|
|
|
# ================================================================================
|
|
|
|
|
@ -1519,20 +1596,20 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
|
|
|
|
|
def on_drone_waypoint_reached(self, drone_id, wp_index, total):
|
|
|
|
|
if wp_index >= total:
|
|
|
|
|
self.statusBar().showMessage(f"📍 {drone_id} 完成所有航點", 3000)
|
|
|
|
|
self.statusBar().showMessage(f"{drone_id} 已完成所有航點", 3000)
|
|
|
|
|
else:
|
|
|
|
|
self.statusBar().showMessage(f"📍 {drone_id} → WP {wp_index}/{total}", 2000)
|
|
|
|
|
self.statusBar().showMessage(f"{drone_id} 到達 WP {wp_index}/{total}", 2000)
|
|
|
|
|
|
|
|
|
|
def _on_task_status_changed(self, drone_id, status, message):
|
|
|
|
|
"""MissionExecutor.task_status_changed slot:把 goto 失敗/重試/fallback/barrier 丟到 status bar"""
|
|
|
|
|
if status == "retrying":
|
|
|
|
|
self.statusBar().showMessage(f"⚠ {drone_id} {message}", 4000)
|
|
|
|
|
self.statusBar().showMessage(f"{drone_id} {message}", 4000)
|
|
|
|
|
elif status == "fallback_loiter":
|
|
|
|
|
self.statusBar().showMessage(f"❌ {drone_id} {message}", 8000)
|
|
|
|
|
self.statusBar().showMessage(f"{drone_id} {message}", 8000)
|
|
|
|
|
elif status == "waiting_at_barrier":
|
|
|
|
|
self.statusBar().showMessage(f"⏸ {drone_id} {message}", 3000)
|
|
|
|
|
self.statusBar().showMessage(f"{drone_id} {message}", 3000)
|
|
|
|
|
elif status == "normal":
|
|
|
|
|
self.statusBar().showMessage(f"▶ {drone_id} {message or '已恢復'}", 2000)
|
|
|
|
|
self.statusBar().showMessage(f"{drone_id} {message or '已恢復'}", 2000)
|
|
|
|
|
|
|
|
|
|
# ================================================================================
|
|
|
|
|
# 輔助方法
|
|
|
|
|
@ -1551,7 +1628,7 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
alt_drone = pos[2] if len(pos) > 2 else base_alt
|
|
|
|
|
drone_gps_positions.append((lat_drone, lon_drone, alt_drone))
|
|
|
|
|
else:
|
|
|
|
|
self.statusBar().showMessage(f"⚠ 找不到 {drone_id} 的位置資料", 3000)
|
|
|
|
|
self.statusBar().showMessage(f"找不到 {drone_id} 的位置資料", 3000)
|
|
|
|
|
return None
|
|
|
|
|
return drone_gps_positions
|
|
|
|
|
|
|
|
|
|
@ -1580,7 +1657,7 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
|
|
|
|
|
script_path = os.path.join(os.path.dirname(os.path.abspath(__file__)), 'validation', 'verify_waypoints.py')
|
|
|
|
|
subprocess.Popen([sys.executable, script_path, '--file', json_path])
|
|
|
|
|
print(f"驗證視窗已啟動: {json_path}")
|
|
|
|
|
_log("INFO", f"驗證視窗已啟動: {json_path}")
|
|
|
|
|
|
|
|
|
|
def show_planned_waypoints(self, group=None):
|
|
|
|
|
pw = group.planned_waypoints if group else None
|
|
|
|
|
@ -1739,7 +1816,7 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
panel._last_roll = roll
|
|
|
|
|
panel._last_pitch = pitch
|
|
|
|
|
if hasattr(panel, 'update_attitude'):
|
|
|
|
|
heading = self.drone_headings.get(drone_id, 0)
|
|
|
|
|
heading = self.drone_headings.get(drone_id, yaw)
|
|
|
|
|
panel.update_attitude(heading, roll, pitch)
|
|
|
|
|
|
|
|
|
|
elif msg_type == 'gps':
|
|
|
|
|
@ -1780,7 +1857,7 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
|
|
|
|
|
elapsed = (time.time() - start_time) * 1000
|
|
|
|
|
if elapsed > 33:
|
|
|
|
|
print(f"[WARNING] UI update took {elapsed:.1f}ms (target: <33ms)")
|
|
|
|
|
_log("WARN", f"UI 更新耗時 {elapsed:.1f}ms (目標 <33ms)")
|
|
|
|
|
|
|
|
|
|
finally:
|
|
|
|
|
# ✅ 步驟 3: 恢復表格重繪(所有資料已填好,一次性重繪)
|
|
|
|
|
@ -1800,7 +1877,7 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
except:
|
|
|
|
|
break
|
|
|
|
|
except Exception as e:
|
|
|
|
|
print(f"❌ 消息隊列處理錯誤: {e}", flush=True)
|
|
|
|
|
_log("ERROR", f"訊息佇列處理錯誤: {e}")
|
|
|
|
|
traceback.print_exc()
|
|
|
|
|
|
|
|
|
|
def _spin_asyncio(self):
|
|
|
|
|
@ -1831,15 +1908,16 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
except RuntimeError as e:
|
|
|
|
|
# ROS2 context 被破坏或不可用
|
|
|
|
|
if "Context" in str(e) or "context" in str(e).lower():
|
|
|
|
|
print(f"⚠️ ROS2 context 錯誤(忽略): {e}", flush=True)
|
|
|
|
|
_log("WARN", f"ROS2 context 錯誤(已忽略): {e}")
|
|
|
|
|
else:
|
|
|
|
|
print(f"ROS spin error: {e}", flush=True)
|
|
|
|
|
_log("ERROR", f"ROS spin error: {e}")
|
|
|
|
|
traceback.print_exc()
|
|
|
|
|
except Exception as e:
|
|
|
|
|
print(f"ROS spin error: {e}", flush=True)
|
|
|
|
|
_log("ERROR", f"ROS spin error: {e}")
|
|
|
|
|
traceback.print_exc()
|
|
|
|
|
|
|
|
|
|
def closeEvent(self, event):
|
|
|
|
|
self._restore_stream_redirector()
|
|
|
|
|
try:
|
|
|
|
|
for group in self.mission_groups.values():
|
|
|
|
|
if group.executor:
|
|
|
|
|
@ -1867,7 +1945,7 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
self.monitor.destroy_node()
|
|
|
|
|
self.executor.shutdown()
|
|
|
|
|
except Exception as e:
|
|
|
|
|
print(f"⚠️ 清理資源時出錯: {e}", flush=True)
|
|
|
|
|
_log("WARN", f"清理資源時發生錯誤: {e}")
|
|
|
|
|
traceback.print_exc()
|
|
|
|
|
|
|
|
|
|
# 安全地 shutdown ROS2
|
|
|
|
|
@ -1875,7 +1953,7 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
if rclpy.ok():
|
|
|
|
|
rclpy.shutdown()
|
|
|
|
|
except RuntimeError as e:
|
|
|
|
|
print(f"⚠️ ROS2 shutdown 錯誤: {e}", flush=True)
|
|
|
|
|
_log("WARN", f"ROS2 shutdown 錯誤: {e}")
|
|
|
|
|
traceback.print_exc()
|
|
|
|
|
|
|
|
|
|
event.accept()
|
|
|
|
|
@ -1894,36 +1972,36 @@ def main():
|
|
|
|
|
"""
|
|
|
|
|
# 第一步:在最外層只初始化一次 ROS2(終極防護)
|
|
|
|
|
# 添加 rclpy.ok() 檢查,防止重複初始化導致 "Context.init() must only be called once" 錯誤
|
|
|
|
|
print("🚀 [GUI 主程式] 檢查 ROS2 初始化狀態...", flush=True)
|
|
|
|
|
_log("INFO", "GUI 主程式檢查 ROS2 初始化狀態")
|
|
|
|
|
if not rclpy.ok():
|
|
|
|
|
print("🚀 [GUI 主程式] ROS2 未初始化,開始初始化...", flush=True)
|
|
|
|
|
_log("INFO", "ROS2 尚未初始化,開始初始化")
|
|
|
|
|
rclpy.init()
|
|
|
|
|
print("✅ [GUI 主程式] ROS2 已全局初始化(由 GUI 主程式霸佔)", flush=True)
|
|
|
|
|
_log("INFO", "ROS2 已完成全域初始化")
|
|
|
|
|
else:
|
|
|
|
|
print("ℹ️ [GUI 主程式] ROS2 已初始化,跳過重複初始化", flush=True)
|
|
|
|
|
_log("INFO", "ROS2 已初始化,略過重複初始化")
|
|
|
|
|
|
|
|
|
|
try:
|
|
|
|
|
# 第二步:啟動 Qt 應用程式
|
|
|
|
|
print("🚀 [GUI 主程式] 啟動 Qt 應用程式...", flush=True)
|
|
|
|
|
_log("INFO", "啟動 Qt 應用程式")
|
|
|
|
|
app = QApplication(sys.argv)
|
|
|
|
|
station = ControlStationUI()
|
|
|
|
|
station.show()
|
|
|
|
|
print("✓ [GUI 主程式] 應用程式已啟動", flush=True)
|
|
|
|
|
_log("INFO", "應用程式已啟動")
|
|
|
|
|
|
|
|
|
|
# 第三步:進入 Qt 事件循環(阻塞直到用戶關閉應用)
|
|
|
|
|
print("🎯 [GUI 主程式] 進入主事件循環,等待用戶操作...", flush=True)
|
|
|
|
|
_log("INFO", "進入主事件循環")
|
|
|
|
|
sys.exit(app.exec())
|
|
|
|
|
|
|
|
|
|
finally:
|
|
|
|
|
# 第四步:只有當 GUI 視窗被關閉時,才做 ROS2 cleanup(終極防護)
|
|
|
|
|
# 這裡確保 ROS2 被正確且安全地關閉
|
|
|
|
|
print("\n🛑 [GUI 主程式] 應用程式關閉,正在清理 ROS2 資源...", flush=True)
|
|
|
|
|
_log("INFO", "應用程式關閉,開始清理 ROS2 資源")
|
|
|
|
|
if rclpy.ok():
|
|
|
|
|
rclpy.shutdown()
|
|
|
|
|
print("✓ [GUI 主程式] ROS2 已安全關閉", flush=True)
|
|
|
|
|
_log("INFO", "ROS2 已安全關閉")
|
|
|
|
|
else:
|
|
|
|
|
print("ℹ️ [GUI 主程式] ROS2 已關閉或不可用,無需重複 shutdown", flush=True)
|
|
|
|
|
print("✓ [GUI 主程式] 應用程式完全退出", flush=True)
|
|
|
|
|
_log("INFO", "ROS2 已關閉或不可用,無需重複 shutdown")
|
|
|
|
|
_log("INFO", "應用程式已完全退出")
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if __name__ == '__main__':
|
|
|
|
|
|