From c3c50d87f62ae7d63873b31894ec6899ab2d4df7 Mon Sep 17 00:00:00 2001 From: ken910606 Date: Wed, 4 Mar 2026 04:29:15 +0800 Subject: [PATCH] Update GUI --- src/GUI/communication.py | 156 ++++++---- src/GUI/drone_panel.py | 58 +--- src/GUI/gui.py | 185 ++++++++---- src/GUI/map_layout.py | 604 ++++++++++++++++++++++++++++++++++++-- src/GUI/overview_table.py | 4 +- 5 files changed, 801 insertions(+), 206 deletions(-) diff --git a/src/GUI/communication.py b/src/GUI/communication.py index c95e74e..b97828b 100644 --- a/src/GUI/communication.py +++ b/src/GUI/communication.py @@ -20,12 +20,15 @@ class DroneSignals(QObject): class UDPMavlinkReceiver(threading.Thread): """UDP MAVLink 接收器""" - def __init__(self, ip, port, signals, connection_name): + def __init__(self, ip, port, signals, connection_name, monitor=None): super().__init__(daemon=True) self.ip = ip self.port = port self.signals = signals self.connection_name = connection_name + self.monitor = monitor # 保存 monitor 引用 + # UDP 使用原始 socket_id = 8 + self.socket_id = monitor.get_or_assign_socket_id('8') if monitor else 0 self.running = False self.sock = None @@ -61,7 +64,7 @@ class UDPMavlinkReceiver(threading.Thread): try: msg_type = msg.get_type() system_id = msg.get_srcSystem() - drone_id = f"s8_{system_id}" # 使用 s8_ 前綴表示 UDP 來源 + drone_id = f"s{self.socket_id}_{system_id}" if msg_type == "HEARTBEAT": mode = mavutil.mode_string_v10(msg) @@ -116,11 +119,13 @@ class UDPMavlinkReceiver(threading.Thread): }) elif msg_type == "VFR_HUD": - groundspeed = msg.groundspeed - heading = msg.heading self.signals.update_signal.emit('hud', drone_id, { - 'heading': heading, - 'groundspeed': groundspeed + 'airspeed': msg.airspeed, + 'groundspeed': msg.groundspeed, + 'heading': msg.heading, + 'throttle': msg.throttle, + 'alt': msg.alt, + 'climb': msg.climb }) except Exception as e: @@ -132,12 +137,15 @@ class UDPMavlinkReceiver(threading.Thread): class SerialMavlinkReceiver(threading.Thread): """串口 MAVLink 接收器""" - def __init__(self, port, baudrate, signals, connection_name): + def __init__(self, port, baudrate, signals, connection_name, monitor=None): super().__init__(daemon=True) self.port = port self.baudrate = baudrate self.signals = signals self.connection_name = connection_name + self.monitor = monitor # 保存 monitor 引用 + # Serial 使用原始 socket_id = 5 + self.socket_id = monitor.get_or_assign_socket_id('5') if monitor else 0 self.running = False self.mav = None @@ -184,7 +192,7 @@ class SerialMavlinkReceiver(threading.Thread): try: msg_type = msg.get_type() system_id = msg.get_srcSystem() - drone_id = f"s5_{system_id}" # 使用 serial_ 前綴表示串口來源 + drone_id = f"s{self.socket_id}_{system_id}" if msg_type == "HEARTBEAT": mode = mavutil.mode_string_v10(msg) @@ -239,11 +247,13 @@ class SerialMavlinkReceiver(threading.Thread): }) elif msg_type == "VFR_HUD": - groundspeed = msg.groundspeed - heading = msg.heading self.signals.update_signal.emit('hud', drone_id, { - 'heading': heading, - 'groundspeed': groundspeed + 'airspeed': msg.airspeed, + 'groundspeed': msg.groundspeed, + 'heading': msg.heading, + 'throttle': msg.throttle, + 'alt': msg.alt, + 'climb': msg.climb }) except Exception as e: @@ -255,12 +265,12 @@ class SerialMavlinkReceiver(threading.Thread): class WebSocketMavlinkReceiver(threading.Thread): """WebSocket MAVLink 接收器""" - def __init__(self, url, signals, connection_name): + def __init__(self, url, signals, connection_name, monitor=None): super().__init__(daemon=True) self.url = url self.signals = signals self.connection_name = connection_name - self.running = False + self.monitor = monitor # 保存 monitor 引用 self.socket_id = monitor.get_next_socket_id() if monitor else 0 # 一次性分配 socket_id self.running = False self.max_retries = 5 self.base_delay = 1.0 @@ -319,10 +329,10 @@ class WebSocketMavlinkReceiver(threading.Thread): def process_websocket_message(self, data): """處理 WebSocket 訊息""" try: - drone_id = data.get('system_id') - drone_id = f"s9_{drone_id}" if drone_id else None - if not drone_id: + system_id = data.get('system_id') + if not system_id: return + drone_id = f"s{self.socket_id}_{system_id}" # 模式 if 'mode' in data: @@ -398,15 +408,39 @@ class DroneMonitor(Node): self.drone_gps = {} # {drone_id: {'lat': ..., 'lon': ..., 'alt': ...}} # ================================================================================ + # ================================================================================ + # 【新增】Socket ID 重新分配機制 (從 0 開始) + # ================================================================================ + self.socket_id_mapping = {} # {原始socket_id: 重新分配的socket_id} + self.socket_id_counter = 0 # 當前分配到的最大socket_id + self.socket_id_lock = Lock() # 線程安全鎖 + # ================================================================================ + # ================================================================================ # 【新增】儲存 sys_id 到 actual_drone_id 的映射 (從 summary 獲取) # ================================================================================ self.sys_to_actual_id = {} # {sys_id: actual_drone_id} e.g. {'sys11': 's0_11'} + self.sys_to_socket_id = {} # {sys_id: assigned_socket_id} e.g. {'sys11': 0} # ================================================================================ self.serial_receivers = [] # 主题检测定时器 self.create_timer(1.0, self.scan_topics) + + def get_or_assign_socket_id(self, original_socket_id): + """根據原始 socket_id 分配或獲取對應的 socket_id(從 0 開始連續分配) + 同一個原始 socket_id 會得到同一個分配的 ID + """ + original_socket_id = str(original_socket_id) + + with self.socket_id_lock: + if original_socket_id not in self.socket_id_mapping: + # 分配新的 socket_id + self.socket_id_mapping[original_socket_id] = self.socket_id_counter + print(f"🆕 Socket ID 映射: 原始 {original_socket_id} -> 分配 {self.socket_id_counter}") + self.socket_id_counter += 1 + + return self.socket_id_mapping[original_socket_id] def scan_topics(self): topics = self.get_topic_names_and_types() @@ -416,34 +450,36 @@ class DroneMonitor(Node): for topic_name, _ in topics: if match := drone_pattern.match(topic_name): sys_id, topic_type = match.groups() - # 將 sys11 轉換為 s0_11 格式以保持兼容性 - drone_num = sys_id.replace('sys', '') - drone_id = f's0_{drone_num}' - found_drones.add(drone_id) + found_drones.add(sys_id) with self.lock: - self.drone_topics.setdefault(drone_id, set()).add(topic_type) + self.drone_topics.setdefault(sys_id, set()).add(topic_type) - for drone_id in found_drones: - if not hasattr(self, f'drone_{drone_id}_subs'): - self.setup_drone(drone_id) + for sys_id in found_drones: + # 為每個 sys_id 分配 socket_id(如果還沒有分配) + # 注意:如果後續 summary 提供了 socket_id,會使用 summary 的映射覆蓋 + if sys_id not in self.sys_to_socket_id: + # 暫時所有 ROS2 topic 共享同一個原始 socket_id,等 summary 提供實際的 socket_id + self.sys_to_socket_id[sys_id] = self.get_or_assign_socket_id('0') + + if not hasattr(self, f'drone_{sys_id}_subs'): + self.setup_drone(sys_id) - def setup_drone(self, drone_id): - # 從 s0_11 轉換回 sys11 格式 - sys_id = drone_id.replace('s0_', 'sys') + def setup_drone(self, sys_id): + # sys_id 格式: sys11, sys12, ... base_topic = f'/fc_network/vehicle/{sys_id}' # Add service clients (保留但可能無法使用,因為新 topic 可能沒有這些服務) - self.arm_clients[drone_id] = self.create_client( + self.arm_clients[sys_id] = self.create_client( CommandBool, f'{base_topic}/cmd/arming' ) - self.takeoff_clients[drone_id] = self.create_client( + self.takeoff_clients[sys_id] = self.create_client( CommandTOL, f'{base_topic}/cmd/takeoff' ) # Add setpoint publisher - self.setpoint_pubs[drone_id] = self.create_publisher( + self.setpoint_pubs[sys_id] = self.create_publisher( Point, f'{base_topic}/setpoint_position/local', 10 @@ -453,30 +489,30 @@ class DroneMonitor(Node): 'battery': self.create_subscription( BatteryState, f'{base_topic}/battery', - lambda msg, did=drone_id: self.battery_callback(did, msg), + lambda msg, sid=sys_id: self.battery_callback(sid, msg), 10 ), 'position': self.create_subscription( NavSatFix, f'{base_topic}/position', - lambda msg, did=drone_id: self.gps_callback(did, msg), + lambda msg, sid=sys_id: self.gps_callback(sid, msg), 10 ), 'summary': self.create_subscription( String, f'{base_topic}/summary', - lambda msg, did=drone_id: self.summary_callback(did, msg), + lambda msg, sid=sys_id: self.summary_callback(sid, msg), 10 ), 'vfr_hud': self.create_subscription( VfrHud, f'{base_topic}/vfr_hud', - lambda msg, did=drone_id: self.hud_callback(did, msg), + lambda msg, sid=sys_id: self.hud_callback(sid, msg), 10 ) } - setattr(self, f'drone_{drone_id}_subs', subs) + setattr(self, f'drone_{sys_id}_subs', subs) async def arm_drone(self, drone_id, arm): if drone_id not in self.arm_clients: @@ -558,9 +594,9 @@ class DroneMonitor(Node): msg.angular_velocity.z) } - def battery_callback(self, drone_id, msg): + def battery_callback(self, sys_id, msg): # 使用映射獲取實際的 drone_id - actual_drone_id = self.sys_to_actual_id.get(drone_id, None) + actual_drone_id = self.sys_to_actual_id.get(sys_id, None) # 如果還沒有從 summary 獲取到映射,則不處理 if actual_drone_id is None: return @@ -578,7 +614,7 @@ class DroneMonitor(Node): 'armed': msg.armed } - def summary_callback(self, drone_id, msg): + def summary_callback(self, sys_id, msg): """處理 summary topic (JSON 格式)""" try: data = json.loads(msg.data) @@ -586,28 +622,34 @@ class DroneMonitor(Node): if mode in self.filtered_modes: return - # 根據 socket_id 更新 drone_id - socket_id = data.get('socket_id') + # 從 summary 獲取原始 socket_id,並映射到分配的 socket_id + original_socket_id = data.get('socket_id') + if original_socket_id is not None: + # 使用原始 socket_id 獲取或分配統一的 socket_id + assigned_socket_id = self.get_or_assign_socket_id(original_socket_id) + else: + # 如果沒有 socket_id,使用 sys_to_socket_id 映射 + assigned_socket_id = self.sys_to_socket_id.get(sys_id, 0) + sysid = data.get('sysid') - if socket_id is not None and sysid is not None: - # 使用 socket_id 作為前綴 - actual_drone_id = f's{socket_id}_{sysid}' + if sysid is not None: + actual_drone_id = f's{assigned_socket_id}_{sysid}' # ================================================================================ # 【關鍵】保存 sys_id 到 actual_drone_id 的映射 # ================================================================================ - sys_key = f'sys{sysid}' - self.sys_to_actual_id[sys_key] = actual_drone_id - # 也保存原始的 s0_ 格式到實際 ID 的映射 - self.sys_to_actual_id[drone_id] = actual_drone_id + self.sys_to_actual_id[sys_id] = actual_drone_id # ================================================================================ else: - actual_drone_id = drone_id + # 如果沒有 sysid,使用 sys_id 中的數字 + sys_num = sys_id.replace('sys', '') + actual_drone_id = f's{assigned_socket_id}_{sys_num}' + self.sys_to_actual_id[sys_id] = actual_drone_id self.latest_data[(actual_drone_id, 'state')] = { 'mode': mode, 'armed': data.get('armed', False), - 'socket_id': socket_id, + 'socket_id': original_socket_id, 'sysid': sysid, 'vehicle_type': data.get('vehicle_type'), 'autopilot': data.get('autopilot'), @@ -616,13 +658,13 @@ class DroneMonitor(Node): 'connected': data.get('connected') } except json.JSONDecodeError as e: - print(f"Error parsing summary JSON for {drone_id}: {e}") + print(f"Error parsing summary JSON for {sys_id}: {e}") except Exception as e: - print(f"Error in summary_callback for {drone_id}: {e}") + print(f"Error in summary_callback for {sys_id}: {e}") - def gps_callback(self, drone_id, msg): + def gps_callback(self, sys_id, msg): # 使用映射獲取實際的 drone_id - actual_drone_id = self.sys_to_actual_id.get(drone_id, None) + actual_drone_id = self.sys_to_actual_id.get(sys_id, None) # 如果還沒有從 summary 獲取到映射,則不處理 if actual_drone_id is None: return @@ -662,9 +704,9 @@ class DroneMonitor(Node): 'z': msg.z } - def hud_callback(self, drone_id, msg): + def hud_callback(self, sys_id, msg): # 使用映射獲取實際的 drone_id - actual_drone_id = self.sys_to_actual_id.get(drone_id, None) + actual_drone_id = self.sys_to_actual_id.get(sys_id, None) # 如果還沒有從 summary 獲取到映射,則不處理 if actual_drone_id is None: return @@ -691,7 +733,7 @@ class DroneMonitor(Node): def start_serial_connection(self, port='/dev/ttyUSB0', baudrate=57600): """啟動串口 MAVLink 連接""" connection_name = f"Serial_{port.replace('/', '_')}" - receiver = SerialMavlinkReceiver(port, baudrate, self.signals, connection_name) + receiver = SerialMavlinkReceiver(port, baudrate, self.signals, connection_name, self) receiver.start() self.serial_receivers.append(receiver) print(f"Started serial connection on {port} at {baudrate} baud") diff --git a/src/GUI/drone_panel.py b/src/GUI/drone_panel.py index a5a7bf5..5739063 100644 --- a/src/GUI/drone_panel.py +++ b/src/GUI/drone_panel.py @@ -43,12 +43,8 @@ class DronePanel(QWidget): # 左側資訊區域 info_widget = self._create_info_section() - # 右側控制按鈕區域 - control_widget = self._create_control_section() - - # 將 info 和 control 加入內容容器 + # 將 info 加入內容容器 content_layout.addWidget(info_widget) - content_layout.addWidget(control_widget) # 將內容容器加入主佈局 main_layout.addWidget(content_widget) @@ -205,58 +201,6 @@ class DronePanel(QWidget): return nav_row - def _create_control_section(self): - """創建控制按鈕區域""" - control_widget = QWidget() - control_layout = QVBoxLayout(control_widget) - control_layout.setContentsMargins(0, 0, 0, 0) - control_layout.setSpacing(6) - - control_widget.setFixedWidth(80) - - btn_style = """ - QPushButton { - background-color: #444; - color: #DDD; - border: none; - border-radius: 4px; - font-size: 11px; - } - QPushButton:hover { - background-color: #555; - } - """ - # 模式切換按鈕 - mode_btn = QPushButton("切換模式") - mode_btn.setStyleSheet(btn_style) - mode_btn.setSizePolicy(QSizePolicy.Policy.Preferred, QSizePolicy.Policy.Expanding) - mode_btn.clicked.connect(lambda: self.mode_change_requested.emit(self.drone_id)) - - # 解鎖按鈕 - arm_btn = QPushButton("解鎖") - arm_btn.setStyleSheet(btn_style) - arm_btn.setSizePolicy(QSizePolicy.Policy.Preferred, QSizePolicy.Policy.Expanding) - arm_btn.clicked.connect(lambda: self.arm_requested.emit(self.drone_id)) - - # 起飛按鈕 - takeoff_btn = QPushButton("起飛") - takeoff_btn.setStyleSheet(btn_style) - takeoff_btn.setSizePolicy(QSizePolicy.Policy.Preferred, QSizePolicy.Policy.Expanding) - takeoff_btn.clicked.connect(lambda: self.takeoff_requested.emit(self.drone_id)) - - # Setpoint 按鈕 - setpoint_btn = QPushButton("Setpoint") - setpoint_btn.setStyleSheet(btn_style) - setpoint_btn.setSizePolicy(QSizePolicy.Policy.Preferred, QSizePolicy.Policy.Expanding) - setpoint_btn.clicked.connect(lambda: self.setpoint_requested.emit(self.drone_id)) - - control_layout.addWidget(mode_btn) - control_layout.addWidget(arm_btn) - control_layout.addWidget(takeoff_btn) - control_layout.addWidget(setpoint_btn) - - return control_widget - def update_field(self, field, text, color=None): """更新指定欄位的值""" label = self.findChild(QLabel, f"{self.drone_id}_{field}") diff --git a/src/GUI/gui.py b/src/GUI/gui.py index 1e0c5ab..5b1a8a5 100644 --- a/src/GUI/gui.py +++ b/src/GUI/gui.py @@ -143,30 +143,25 @@ class ControlStationUI(QMainWindow): """) batch_control_layout.addWidget(batch_title) - # 上方按鈕區域 - upper_buttons = QHBoxLayout() + # 第一行:全選按鈕 + first_row = QHBoxLayout() select_all_btn = QPushButton("全選") select_all_btn.clicked.connect(self.handle_select_all) - arm_all_btn = QPushButton("解鎖") - arm_all_btn.clicked.connect(self.handle_arm_selected) - takeoff_all_btn = QPushButton("起飛") - takeoff_all_btn.clicked.connect(self.handle_takeoff_selected) - for btn in [select_all_btn, arm_all_btn, takeoff_all_btn]: - btn.setStyleSheet(""" - QPushButton { - background-color: #444; - color: #DDD; - border: none; - padding: 8px 12px; - border-radius: 4px; - min-width: 80px; - } - QPushButton:hover { background-color: #555; } - """) - upper_buttons.addWidget(btn) - upper_buttons.addStretch() - - # 模式切換區域 + select_all_btn.setStyleSheet(""" + QPushButton { + background-color: #444; + color: #DDD; + border: none; + padding: 8px 12px; + border-radius: 4px; + min-width: 80px; + } + QPushButton:hover { background-color: #555; } + """) + first_row.addWidget(select_all_btn) + first_row.addStretch() + + # 第二行:模式切換 mode_layout = QHBoxLayout() mode_label = QLabel("模式:") mode_label.setStyleSheet("color: #DDD; min-width: 40px;") @@ -197,36 +192,42 @@ class ControlStationUI(QMainWindow): mode_layout.addWidget(batch_mode_btn) mode_layout.addStretch() - # 座標輸入區域 - coord_widget = QWidget() - coord_layout = QHBoxLayout(coord_widget) + # 第三行:解鎖按鈕 + third_row = QHBoxLayout() + arm_all_btn = QPushButton("解鎖") + arm_all_btn.clicked.connect(self.handle_arm_selected) + arm_all_btn.setStyleSheet(""" + QPushButton { + background-color: #444; + color: #DDD; + border: none; + padding: 8px 12px; + border-radius: 4px; + min-width: 80px; + } + QPushButton:hover { background-color: #555; } + """) + third_row.addWidget(arm_all_btn) + third_row.addStretch() + + # 第四行:高度輸入和起飛按鈕 + fourth_row = QHBoxLayout() - self.x_input = QLineEdit() - self.y_input = QLineEdit() self.z_input = QLineEdit() + self.z_input.setFixedWidth(60) + self.z_input.setStyleSheet(""" + QLineEdit { + background-color: #333; + color: #DDD; + border: 1px solid #555; + border-radius: 4px; + padding: 3px; + } + """) - for input_field in [self.x_input, self.y_input, self.z_input]: - input_field.setFixedWidth(60) - input_field.setStyleSheet(""" - QLineEdit { - background-color: #333; - color: #DDD; - border: 1px solid #555; - border-radius: 4px; - padding: 3px; - } - """) - - coord_layout.addWidget(QLabel("X:", styleSheet="color: #DDD;")) - coord_layout.addWidget(self.x_input) - coord_layout.addWidget(QLabel("Y:", styleSheet="color: #DDD;")) - coord_layout.addWidget(self.y_input) - coord_layout.addWidget(QLabel("Z:", styleSheet="color: #DDD;")) - coord_layout.addWidget(self.z_input) - - setpoint_btn = QPushButton("Setpoint") - setpoint_btn.clicked.connect(self.handle_setpoint_selected) - setpoint_btn.setStyleSheet(""" + takeoff_all_btn = QPushButton("起飛") + takeoff_all_btn.clicked.connect(self.handle_takeoff_selected) + takeoff_all_btn.setStyleSheet(""" QPushButton { background-color: #444; color: #DDD; @@ -237,16 +238,17 @@ class ControlStationUI(QMainWindow): } QPushButton:hover { background-color: #555; } """) - - lower_control = QHBoxLayout() - lower_control.addWidget(coord_widget) - lower_control.addWidget(setpoint_btn) - lower_control.addStretch() + + fourth_row.addWidget(QLabel("高度:", styleSheet="color: #DDD;")) + fourth_row.addWidget(self.z_input) + fourth_row.addWidget(takeoff_all_btn) + fourth_row.addStretch() # 組裝批次控制 layout - batch_control_layout.addLayout(upper_buttons) - batch_control_layout.addLayout(mode_layout) - batch_control_layout.addLayout(lower_control) + batch_control_layout.addLayout(first_row) + batch_control_layout.addLayout(mode_layout) + batch_control_layout.addLayout(third_row) + batch_control_layout.addLayout(fourth_row) # 將批次控制 layout 添加到右側容器 right_layout.addLayout(batch_control_layout) @@ -255,6 +257,8 @@ class ControlStationUI(QMainWindow): right_layout.addWidget(self.drone_map.get_widget()) self.drone_map.get_gps_signal().connect(self.handle_map_click) self.drone_map.get_drone_clicked_signal().connect(self.handle_drone_clicked) + self.drone_map.get_clear_all_drone_selection_signal().connect(self.handle_clear_all_drone_selection) + self.drone_map.get_toggle_select_all_drones_signal().connect(self.handle_toggle_select_all_drones) # Add widgets to splitter @@ -276,7 +280,7 @@ class ControlStationUI(QMainWindow): } # 启动接收器 - receiver = UDPMavlinkReceiver(ip, port, self.monitor.signals, new_conn['name']) + receiver = UDPMavlinkReceiver(ip, port, self.monitor.signals, new_conn['name'], self.monitor) receiver.start() self.udp_receivers.append(receiver) new_conn['receiver'] = receiver @@ -299,7 +303,7 @@ class ControlStationUI(QMainWindow): } # 启动接收器 - receiver = WebSocketMavlinkReceiver(url, self.monitor.signals, new_conn['name']) + receiver = WebSocketMavlinkReceiver(url, self.monitor.signals, new_conn['name'], self.monitor) receiver.start() self.monitor.ws_receivers.append(receiver) new_conn['receiver'] = receiver @@ -580,7 +584,10 @@ class ControlStationUI(QMainWindow): cells = round(voltage / 3.95) # 計算電量百分比 - percentage = (voltage / cells - 3.7) / 0.5 * 100 + if cells == 0: + percentage = 0 + else: + percentage = (voltage / cells - 3.7) / 0.5 * 100 # 根據百分比設置顏色 if percentage < 20: @@ -842,10 +849,13 @@ class ControlStationUI(QMainWindow): self.overview_table.update_table(drone_id, field, value) def get_socket_id(self, drone_id): - """從 drone_id 提取 socket_id (例如 's9_1' -> '9')""" + """從 drone_id 提取 socket_id (例如 's0_1' -> '0')""" import re - match = re.match(r's(\d+)_\d+', drone_id) - return match.group(1) if match else 'unknown' + match = re.match(r's(\d+)_(\d+)', drone_id) + if not match: + return 'unknown' + + return match.group(1) def add_drone(self, drone_id): if drone_id in self.drones: @@ -1042,6 +1052,55 @@ class ControlStationUI(QMainWindow): # 切換勾選狀態 checkbox.setChecked(not checkbox.isChecked()) + def handle_clear_all_drone_selection(self): + """清除所有無人機的勾選狀態""" + print("清除所有無人機選擇") + + for drone_id in self.drones.keys(): + checkbox = self.drones[drone_id].get_checkbox() + if checkbox: + checkbox.blockSignals(True) + checkbox.setChecked(False) + checkbox.blockSignals(False) + + # 清除選中集合 + self.monitor.selected_drones.clear() + + # 更新所有分組的勾選框狀態 + for socket_id in self.socket_groups.keys(): + self.update_group_checkbox_state(socket_id) + + def handle_toggle_select_all_drones(self): + """切換全選/取消全選所有無人機""" + # 檢查是否已經全選 + all_selected = all(self.drones[drone_id].get_checkbox().isChecked() + for drone_id in self.drones.keys()) + + if all_selected: + # 已全選,則取消全選 + print("取消全選所有無人機") + for drone_id in self.drones.keys(): + checkbox = self.drones[drone_id].get_checkbox() + if checkbox: + checkbox.blockSignals(True) + checkbox.setChecked(False) + checkbox.blockSignals(False) + self.monitor.selected_drones.clear() + else: + # 未全選,則全選 + print("全選所有無人機") + for drone_id in self.drones.keys(): + checkbox = self.drones[drone_id].get_checkbox() + if checkbox: + checkbox.blockSignals(True) + checkbox.setChecked(True) + checkbox.blockSignals(False) + self.monitor.selected_drones.add(drone_id) + + # 更新所有分組的勾選框狀態 + for socket_id in self.socket_groups.keys(): + self.update_group_checkbox_state(socket_id) + def show_planned_waypoints(self): """ 顯示規劃的航點(在終端輸出) diff --git a/src/GUI/map_layout.py b/src/GUI/map_layout.py index 5b1f6ef..90986a0 100644 --- a/src/GUI/map_layout.py +++ b/src/GUI/map_layout.py @@ -32,24 +32,148 @@ class DroneMap: @@ -57,6 +181,24 @@ class DroneMap:
+ + +
+
+
+ + +
+
+ 中心點: + 未設定 +
+
+ 目標點: + 未設定 +
+ +