Upload files to 'src/GUI'

chiyu
ken910606 3 months ago
parent 7694f29d1a
commit f7f90c3168

@ -20,12 +20,15 @@ class DroneSignals(QObject):
class UDPMavlinkReceiver(threading.Thread): class UDPMavlinkReceiver(threading.Thread):
"""UDP MAVLink 接收器""" """UDP MAVLink 接收器"""
def __init__(self, ip, port, signals, connection_name): def __init__(self, ip, port, signals, connection_name, monitor=None):
super().__init__(daemon=True) super().__init__(daemon=True)
self.ip = ip self.ip = ip
self.port = port self.port = port
self.signals = signals self.signals = signals
self.connection_name = connection_name 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.running = False
self.sock = None self.sock = None
@ -61,7 +64,7 @@ class UDPMavlinkReceiver(threading.Thread):
try: try:
msg_type = msg.get_type() msg_type = msg.get_type()
system_id = msg.get_srcSystem() 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": if msg_type == "HEARTBEAT":
mode = mavutil.mode_string_v10(msg) mode = mavutil.mode_string_v10(msg)
@ -116,11 +119,13 @@ class UDPMavlinkReceiver(threading.Thread):
}) })
elif msg_type == "VFR_HUD": elif msg_type == "VFR_HUD":
groundspeed = msg.groundspeed
heading = msg.heading
self.signals.update_signal.emit('hud', drone_id, { self.signals.update_signal.emit('hud', drone_id, {
'heading': heading, 'airspeed': msg.airspeed,
'groundspeed': groundspeed 'groundspeed': msg.groundspeed,
'heading': msg.heading,
'throttle': msg.throttle,
'alt': msg.alt,
'climb': msg.climb
}) })
except Exception as e: except Exception as e:
@ -132,12 +137,15 @@ class UDPMavlinkReceiver(threading.Thread):
class SerialMavlinkReceiver(threading.Thread): class SerialMavlinkReceiver(threading.Thread):
"""串口 MAVLink 接收器""" """串口 MAVLink 接收器"""
def __init__(self, port, baudrate, signals, connection_name): def __init__(self, port, baudrate, signals, connection_name, monitor=None):
super().__init__(daemon=True) super().__init__(daemon=True)
self.port = port self.port = port
self.baudrate = baudrate self.baudrate = baudrate
self.signals = signals self.signals = signals
self.connection_name = connection_name 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.running = False
self.mav = None self.mav = None
@ -184,7 +192,7 @@ class SerialMavlinkReceiver(threading.Thread):
try: try:
msg_type = msg.get_type() msg_type = msg.get_type()
system_id = msg.get_srcSystem() 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": if msg_type == "HEARTBEAT":
mode = mavutil.mode_string_v10(msg) mode = mavutil.mode_string_v10(msg)
@ -239,11 +247,13 @@ class SerialMavlinkReceiver(threading.Thread):
}) })
elif msg_type == "VFR_HUD": elif msg_type == "VFR_HUD":
groundspeed = msg.groundspeed
heading = msg.heading
self.signals.update_signal.emit('hud', drone_id, { self.signals.update_signal.emit('hud', drone_id, {
'heading': heading, 'airspeed': msg.airspeed,
'groundspeed': groundspeed 'groundspeed': msg.groundspeed,
'heading': msg.heading,
'throttle': msg.throttle,
'alt': msg.alt,
'climb': msg.climb
}) })
except Exception as e: except Exception as e:
@ -255,12 +265,12 @@ class SerialMavlinkReceiver(threading.Thread):
class WebSocketMavlinkReceiver(threading.Thread): class WebSocketMavlinkReceiver(threading.Thread):
"""WebSocket MAVLink 接收器""" """WebSocket MAVLink 接收器"""
def __init__(self, url, signals, connection_name): def __init__(self, url, signals, connection_name, monitor=None):
super().__init__(daemon=True) super().__init__(daemon=True)
self.url = url self.url = url
self.signals = signals self.signals = signals
self.connection_name = connection_name 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.max_retries = 5
self.base_delay = 1.0 self.base_delay = 1.0
@ -319,10 +329,10 @@ class WebSocketMavlinkReceiver(threading.Thread):
def process_websocket_message(self, data): def process_websocket_message(self, data):
"""處理 WebSocket 訊息""" """處理 WebSocket 訊息"""
try: try:
drone_id = data.get('system_id') system_id = data.get('system_id')
drone_id = f"s9_{drone_id}" if drone_id else None if not system_id:
if not drone_id:
return return
drone_id = f"s{self.socket_id}_{system_id}"
# 模式 # 模式
if 'mode' in data: if 'mode' in data:
@ -398,15 +408,39 @@ class DroneMonitor(Node):
self.drone_gps = {} # {drone_id: {'lat': ..., 'lon': ..., 'alt': ...}} 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 獲取) # 【新增】儲存 sys_id 到 actual_drone_id 的映射 (從 summary 獲取)
# ================================================================================ # ================================================================================
self.sys_to_actual_id = {} # {sys_id: actual_drone_id} e.g. {'sys11': 's0_11'} 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.serial_receivers = []
# 主题检测定时器 # 主题检测定时器
self.create_timer(1.0, self.scan_topics) 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): def scan_topics(self):
topics = self.get_topic_names_and_types() topics = self.get_topic_names_and_types()
@ -416,34 +450,36 @@ class DroneMonitor(Node):
for topic_name, _ in topics: for topic_name, _ in topics:
if match := drone_pattern.match(topic_name): if match := drone_pattern.match(topic_name):
sys_id, topic_type = match.groups() sys_id, topic_type = match.groups()
# 將 sys11 轉換為 s0_11 格式以保持兼容性 found_drones.add(sys_id)
drone_num = sys_id.replace('sys', '')
drone_id = f's0_{drone_num}'
found_drones.add(drone_id)
with self.lock: 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: for sys_id in found_drones:
if not hasattr(self, f'drone_{drone_id}_subs'): # 為每個 sys_id 分配 socket_id如果還沒有分配
self.setup_drone(drone_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): def setup_drone(self, sys_id):
# 從 s0_11 轉換回 sys11 格式 # sys_id 格式: sys11, sys12, ...
sys_id = drone_id.replace('s0_', 'sys')
base_topic = f'/fc_network/vehicle/{sys_id}' base_topic = f'/fc_network/vehicle/{sys_id}'
# Add service clients (保留但可能無法使用,因為新 topic 可能沒有這些服務) # Add service clients (保留但可能無法使用,因為新 topic 可能沒有這些服務)
self.arm_clients[drone_id] = self.create_client( self.arm_clients[sys_id] = self.create_client(
CommandBool, CommandBool,
f'{base_topic}/cmd/arming' f'{base_topic}/cmd/arming'
) )
self.takeoff_clients[drone_id] = self.create_client( self.takeoff_clients[sys_id] = self.create_client(
CommandTOL, CommandTOL,
f'{base_topic}/cmd/takeoff' f'{base_topic}/cmd/takeoff'
) )
# Add setpoint publisher # Add setpoint publisher
self.setpoint_pubs[drone_id] = self.create_publisher( self.setpoint_pubs[sys_id] = self.create_publisher(
Point, Point,
f'{base_topic}/setpoint_position/local', f'{base_topic}/setpoint_position/local',
10 10
@ -453,30 +489,30 @@ class DroneMonitor(Node):
'battery': self.create_subscription( 'battery': self.create_subscription(
BatteryState, BatteryState,
f'{base_topic}/battery', 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 10
), ),
'position': self.create_subscription( 'position': self.create_subscription(
NavSatFix, NavSatFix,
f'{base_topic}/position', 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 10
), ),
'summary': self.create_subscription( 'summary': self.create_subscription(
String, String,
f'{base_topic}/summary', 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 10
), ),
'vfr_hud': self.create_subscription( 'vfr_hud': self.create_subscription(
VfrHud, VfrHud,
f'{base_topic}/vfr_hud', 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 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): async def arm_drone(self, drone_id, arm):
if drone_id not in self.arm_clients: if drone_id not in self.arm_clients:
@ -558,9 +594,9 @@ class DroneMonitor(Node):
msg.angular_velocity.z) msg.angular_velocity.z)
} }
def battery_callback(self, drone_id, msg): def battery_callback(self, sys_id, msg):
# 使用映射獲取實際的 drone_id # 使用映射獲取實際的 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 獲取到映射,則不處理 # 如果還沒有從 summary 獲取到映射,則不處理
if actual_drone_id is None: if actual_drone_id is None:
return return
@ -578,7 +614,7 @@ class DroneMonitor(Node):
'armed': msg.armed 'armed': msg.armed
} }
def summary_callback(self, drone_id, msg): def summary_callback(self, sys_id, msg):
"""處理 summary topic (JSON 格式)""" """處理 summary topic (JSON 格式)"""
try: try:
data = json.loads(msg.data) data = json.loads(msg.data)
@ -586,28 +622,34 @@ class DroneMonitor(Node):
if mode in self.filtered_modes: if mode in self.filtered_modes:
return return
# 根據 socket_id 更新 drone_id # 從 summary 獲取原始 socket_id並映射到分配的 socket_id
socket_id = data.get('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') sysid = data.get('sysid')
if socket_id is not None and sysid is not None: if sysid is not None:
# 使用 socket_id 作為前綴 actual_drone_id = f's{assigned_socket_id}_{sysid}'
actual_drone_id = f's{socket_id}_{sysid}'
# ================================================================================ # ================================================================================
# 【關鍵】保存 sys_id 到 actual_drone_id 的映射 # 【關鍵】保存 sys_id 到 actual_drone_id 的映射
# ================================================================================ # ================================================================================
sys_key = f'sys{sysid}' self.sys_to_actual_id[sys_id] = actual_drone_id
self.sys_to_actual_id[sys_key] = actual_drone_id
# 也保存原始的 s0_ 格式到實際 ID 的映射
self.sys_to_actual_id[drone_id] = actual_drone_id
# ================================================================================ # ================================================================================
else: 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')] = { self.latest_data[(actual_drone_id, 'state')] = {
'mode': mode, 'mode': mode,
'armed': data.get('armed', False), 'armed': data.get('armed', False),
'socket_id': socket_id, 'socket_id': original_socket_id,
'sysid': sysid, 'sysid': sysid,
'vehicle_type': data.get('vehicle_type'), 'vehicle_type': data.get('vehicle_type'),
'autopilot': data.get('autopilot'), 'autopilot': data.get('autopilot'),
@ -616,13 +658,13 @@ class DroneMonitor(Node):
'connected': data.get('connected') 'connected': data.get('connected')
} }
except json.JSONDecodeError as e: 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: 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 # 使用映射獲取實際的 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 獲取到映射,則不處理 # 如果還沒有從 summary 獲取到映射,則不處理
if actual_drone_id is None: if actual_drone_id is None:
return return
@ -662,9 +704,9 @@ class DroneMonitor(Node):
'z': msg.z 'z': msg.z
} }
def hud_callback(self, drone_id, msg): def hud_callback(self, sys_id, msg):
# 使用映射獲取實際的 drone_id # 使用映射獲取實際的 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 獲取到映射,則不處理 # 如果還沒有從 summary 獲取到映射,則不處理
if actual_drone_id is None: if actual_drone_id is None:
return return
@ -691,7 +733,7 @@ class DroneMonitor(Node):
def start_serial_connection(self, port='/dev/ttyUSB0', baudrate=57600): def start_serial_connection(self, port='/dev/ttyUSB0', baudrate=57600):
"""啟動串口 MAVLink 連接""" """啟動串口 MAVLink 連接"""
connection_name = f"Serial_{port.replace('/', '_')}" 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() receiver.start()
self.serial_receivers.append(receiver) self.serial_receivers.append(receiver)
print(f"Started serial connection on {port} at {baudrate} baud") print(f"Started serial connection on {port} at {baudrate} baud")

@ -276,7 +276,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() receiver.start()
self.udp_receivers.append(receiver) self.udp_receivers.append(receiver)
new_conn['receiver'] = receiver new_conn['receiver'] = receiver
@ -299,7 +299,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() receiver.start()
self.monitor.ws_receivers.append(receiver) self.monitor.ws_receivers.append(receiver)
new_conn['receiver'] = receiver new_conn['receiver'] = receiver
@ -845,10 +845,13 @@ class ControlStationUI(QMainWindow):
self.overview_table.update_table(drone_id, field, value) self.overview_table.update_table(drone_id, field, value)
def get_socket_id(self, drone_id): def get_socket_id(self, drone_id):
"""從 drone_id 提取 socket_id (例如 's9_1' -> '9')""" """從 drone_id 提取 socket_id (例如 's0_1' -> '0')"""
import re import re
match = re.match(r's(\d+)_\d+', drone_id) match = re.match(r's(\d+)_(\d+)', drone_id)
return match.group(1) if match else 'unknown' if not match:
return 'unknown'
return match.group(1)
def add_drone(self, drone_id): def add_drone(self, drone_id):
if drone_id in self.drones: if drone_id in self.drones:

@ -32,15 +32,27 @@ class DroneMap:
<script src="qrc:///qtwebchannel/qwebchannel.js"></script> <script src="qrc:///qtwebchannel/qwebchannel.js"></script>
<style> <style>
html, body, #map { height: 100%; margin: 0; } html, body, #map { height: 100%; margin: 0; }
#map {
user-select: none;
-webkit-user-select: none;
-moz-user-select: none;
-ms-user-select: none;
}
.map-controls { .map-controls {
position: absolute; position: absolute;
top: 10px; top: 10px;
right: 10px; right: 10px;
z-index: 1000; z-index: 1000;
} }
.map-controls-bottom {
position: absolute;
bottom: 10px;
left: 10px;
z-index: 1000;
}
.control-button { .control-button {
padding: 8px 12px; padding: 8px 12px;
background-color: #f44336; background-color: #F44336;
color: white; color: white;
border: none; border: none;
border-radius: 4px; border-radius: 4px;
@ -49,7 +61,88 @@ class DroneMap:
box-shadow: 0 2px 5px rgba(0,0,0,0.2); box-shadow: 0 2px 5px rgba(0,0,0,0.2);
} }
.control-button:hover { .control-button:hover {
background-color: #d32f2f; background-color: #D32F2F;
}
.map-toggle-button {
padding: 8px 12px;
background-color: #2E7D32;
color: white;
border: none;
border-radius: 4px;
cursor: pointer;
font-size: 12px;
box-shadow: 0 2px 5px rgba(0,0,0,0.2);
}
.map-toggle-button:hover {
background-color: #1B5E20;
}
.mission-info-panel {
position: absolute;
bottom: 10px;
right: 10px;
z-index: 1000;
background-color: rgba(255, 255, 255, 0.95);
padding: 12px;
border-radius: 6px;
box-shadow: 0 2px 8px rgba(0,0,0,0.3);
min-width: 250px;
}
.mission-info-row {
margin-bottom: 8px;
font-size: 12px;
color: #333;
}
.mission-info-label {
font-weight: bold;
color: #555;
}
.mission-info-value {
color: #2196F3;
font-family: monospace;
}
.mission-start-button {
width: 100%;
padding: 10px;
background-color: #7FBA82;
color: white;
border: none;
border-radius: 4px;
cursor: pointer;
font-size: 13px;
font-weight: bold;
margin-top: 8px;
}
.mission-start-button:hover {
background-color: #6FA872;
}
.mission-start-button:disabled {
background-color: #ccc;
cursor: not-allowed;
}
.selection-buttons {
display: flex;
flex-direction: column;
gap: 5px;
margin-bottom: 10px;
padding-bottom: 10px;
border-bottom: 1px solid #ddd;
}
.selection-button {
width: 100%;
padding: 8px;
background-color: #64B5F6;
color: white;
border: none;
border-radius: 4px;
cursor: pointer;
font-size: 11px;
transition: background-color 0.2s;
}
.selection-button:hover {
background-color: #42A5F5;
}
.selection-button.active {
background-color: #1976D2;
} }
</style> </style>
</head> </head>
@ -58,6 +151,25 @@ class DroneMap:
<div class="map-controls"> <div class="map-controls">
<button class="control-button" onclick="clearAllTrajectories()">清除軌跡</button> <button class="control-button" onclick="clearAllTrajectories()">清除軌跡</button>
</div> </div>
<div class="map-controls-bottom">
<button class="map-toggle-button" onclick="toggleMapLayer()">地圖預設</button>
</div>
<div class="mission-info-panel">
<div class="selection-buttons">
<button class="selection-button" id="select-drones-btn" onclick="toggleDroneSelection()">框選無人機</button>
<button class="selection-button" id="select-rect-btn" onclick="toggleRectSelection()">框選方形區域</button>
<button class="selection-button" id="select-polygon-btn" onclick="togglePolygonSelection()">多點選擇區域</button>
</div>
<div class="mission-info-row">
<span class="mission-info-label">中心點: </span>
<span class="mission-info-value" id="center-position">未設定</span>
</div>
<div class="mission-info-row">
<span class="mission-info-label">目標點: </span>
<span class="mission-info-value" id="target-position">未設定</span>
</div>
<button class="mission-start-button" id="start-mission-btn" onclick="startMission()" disabled>開始任務</button>
</div>
<script> <script>
var bridge; var bridge;
@ -66,16 +178,83 @@ class DroneMap:
}); });
var map = L.map('map').setView([0, 0], 19); var map = L.map('map').setView([0, 0], 19);
L.tileLayer('https://{s}.tile.openstreetmap.org/{z}/{x}/{y}.png', {
// 創建不同的地圖圖層
var streetLayer = L.tileLayer('https://{s}.tile.openstreetmap.org/{z}/{x}/{y}.png', {
maxZoom: 19, maxZoom: 19,
attribution: '© OpenStreetMap contributors' attribution: '© OpenStreetMap contributors'
}).addTo(map); });
var satelliteLayer = L.tileLayer('https://server.arcgisonline.com/ArcGIS/rest/services/World_Imagery/MapServer/tile/{z}/{y}/{x}', {
maxZoom: 19,
attribution: 'Tiles © Esri'
});
// 默認使用街道圖
var currentLayer = streetLayer;
currentLayer.addTo(map);
var isSatellite = false;
// 切換地圖圖層函數
function toggleMapLayer() {
if (isSatellite) {
map.removeLayer(satelliteLayer);
streetLayer.addTo(map);
isSatellite = false;
document.querySelector('.map-toggle-button').textContent = '地圖:預設';
} else {
map.removeLayer(streetLayer);
satelliteLayer.addTo(map);
isSatellite = true;
document.querySelector('.map-toggle-button').textContent = '地圖:衛星';
}
}
// 地圖點擊事件 // 地圖點擊事件
map.on('click', function(e) { map.on('click', function(e) {
if (bridge) { if (selectionMode === 'polygon') {
bridge.emitGpsSignal(e.latlng.lat, e.latlng.lng); // 多點選擇模式添加點
console.log('點擊位置:', e.latlng.lat, e.latlng.lng); addPolygonPoint(e.latlng.lat, e.latlng.lng);
} else if (!selectionMode) {
// 正常模式發送GPS信號
if (bridge) {
bridge.emitGpsSignal(e.latlng.lat, e.latlng.lng);
console.log('點擊位置:', e.latlng.lat, e.latlng.lng);
}
}
});
// 地圖拖曳事件用於矩形選擇
map.on('mousedown', function(e) {
if (selectionMode === 'rect' || selectionMode === 'drones') {
isDrawing = true;
drawStartPoint = e.latlng;
L.DomEvent.preventDefault(e.originalEvent);
L.DomEvent.stopPropagation(e);
}
});
map.on('mousemove', function(e) {
if (isDrawing && (selectionMode === 'rect' || selectionMode === 'drones') && drawStartPoint) {
// 更新臨時矩形
if (tempRectangle) {
selectionLayer.removeLayer(tempRectangle);
}
var bounds = L.latLngBounds(drawStartPoint, e.latlng);
tempRectangle = L.rectangle(bounds, {
color: selectionMode === 'drones' ? '#9C27B0' : '#FF6B6B',
weight: 2,
fillOpacity: 0.2
}).addTo(selectionLayer);
}
});
map.on('mouseup', function(e) {
if (isDrawing && (selectionMode === 'rect' || selectionMode === 'drones') && drawStartPoint) {
isDrawing = false;
var bounds = L.latLngBounds(drawStartPoint, e.latlng);
finishRectSelection(bounds);
drawStartPoint = null;
} }
}); });
@ -150,6 +329,251 @@ class DroneMap:
var centerMarker = null; // 中心點標記 var centerMarker = null; // 中心點標記
var targetMarker = null; // 目標點標記 var targetMarker = null; // 目標點標記
var missionLine = null; // 中心點到目標點的虛線 var missionLine = null; // 中心點到目標點的虛線
var centerPosition = null; // 中心點經緯度
var targetPosition = null; // 目標點經緯度
// 選擇工具變量
var selectionMode = null; // 'drones', 'rect', 'polygon', null
var selectionLayer = L.layerGroup().addTo(map);
var polygonPoints = []; // 多點選擇的點
var polygonMarkers = []; // 多點選擇的標記
var tempRectangle = null; // 臨時矩形
var isDrawing = false; // 是否正在繪製
var drawStartPoint = null; // 繪製起點
// ================================================================================
// 更新任務信息面板
function updateMissionInfo() {
const centerElem = document.getElementById('center-position');
const targetElem = document.getElementById('target-position');
const startBtn = document.getElementById('start-mission-btn');
if (centerPosition) {
centerElem.textContent = `${centerPosition.lat.toFixed(6)}, ${centerPosition.lng.toFixed(6)}`;
} else {
centerElem.textContent = '未設定';
}
if (targetPosition) {
targetElem.textContent = `${targetPosition.lat.toFixed(6)}, ${targetPosition.lng.toFixed(6)}`;
} else {
targetElem.textContent = '未設定';
}
// 只有當中心點和目標點都設定時才啟用按鈕
if (centerPosition && targetPosition) {
startBtn.disabled = false;
} else {
startBtn.disabled = true;
}
}
// ================================================================================
// 選擇工具函數
// ================================================================================
function toggleDroneSelection() {
clearSelectionMode();
if (selectionMode === 'drones') {
selectionMode = null;
document.getElementById('select-drones-btn').classList.remove('active');
map.dragging.enable();
} else {
selectionMode = 'drones';
document.getElementById('select-drones-btn').classList.add('active');
map.dragging.disable();
}
}
function toggleRectSelection() {
clearSelectionMode();
if (selectionMode === 'rect') {
selectionMode = null;
document.getElementById('select-rect-btn').classList.remove('active');
map.dragging.enable();
} else {
selectionMode = 'rect';
document.getElementById('select-rect-btn').classList.add('active');
map.dragging.disable();
}
}
function togglePolygonSelection() {
if (selectionMode === 'polygon') {
// 第二次點擊完成選擇
if (polygonPoints.length >= 3) {
finishPolygonSelection();
} else {
alert('至少需要3個點來形成區域');
// 清除並重置
clearSelectionMode();
clearPolygonPoints();
selectionMode = null;
document.getElementById('select-polygon-btn').classList.remove('active');
}
} else {
// 第一次點擊清除上次的點位並啟動模式
clearSelectionMode();
clearPolygonPoints();
selectionMode = 'polygon';
document.getElementById('select-polygon-btn').classList.add('active');
map.dragging.disable();
}
}
function clearSelectionMode() {
// 清除所有按鈕的激活狀態
document.getElementById('select-drones-btn').classList.remove('active');
document.getElementById('select-rect-btn').classList.remove('active');
document.getElementById('select-polygon-btn').classList.remove('active');
// 清除選擇圖層
selectionLayer.clearLayers();
tempRectangle = null;
// 重新啟用地圖拖曳
map.dragging.enable();
}
function addPolygonPoint(lat, lng) {
polygonPoints.push([lat, lng]);
// 添加邊界點標記
var marker = L.circleMarker([lat, lng], {
radius: 5,
color: '#FF6B6B',
fillColor: '#FF6B6B',
fillOpacity: 0.8
}).addTo(selectionLayer);
polygonMarkers.push(marker);
// 如果有多個點繪製連線
if (polygonPoints.length > 1) {
L.polyline(polygonPoints, {
color: '#FF6B6B',
weight: 2,
dashArray: '5, 5'
}).addTo(selectionLayer);
}
console.log('添加邊界點:', lat, lng, '總共:', polygonPoints.length);
}
function clearPolygonPoints() {
polygonPoints = [];
polygonMarkers.forEach(m => selectionLayer.removeLayer(m));
polygonMarkers = [];
selectionLayer.clearLayers();
}
function finishPolygonSelection() {
if (polygonPoints.length < 3) {
alert('至少需要3個點來形成區域');
return;
}
// 繪製最終多邊形
var polygon = L.polygon(polygonPoints, {
color: '#FF6B6B',
fillColor: '#FF6B6B',
fillOpacity: 0.2,
weight: 2
}).addTo(selectionLayer);
// 發送多邊形數據到Python
if (bridge) {
var pointsStr = JSON.stringify(polygonPoints);
bridge.polygonSelected(pointsStr);
console.log('多邊形選擇完成:', polygonPoints);
}
// 重置狀態
selectionMode = null;
document.getElementById('select-polygon-btn').classList.remove('active');
map.dragging.enable();
}
function finishRectSelection(bounds) {
var selectedDrones = [];
// 清除臨時矩形
if (tempRectangle) {
selectionLayer.removeLayer(tempRectangle);
tempRectangle = null;
}
if (selectionMode === 'drones') {
// 框選無人機模式
Object.keys(markers).forEach(droneId => {
var pos = markers[droneId].getLatLng();
if (bounds.contains(pos)) {
selectedDrones.push(droneId);
// 觸發無人機點擊信號
if (bridge) {
bridge.emitDroneClicked(droneId);
}
}
});
console.log('框選無人機:', selectedDrones);
// 不保留選擇框直接完成
} else if (selectionMode === 'rect') {
// 框選區域模式
var rectPoints = [
[bounds.getNorth(), bounds.getWest()],
[bounds.getNorth(), bounds.getEast()],
[bounds.getSouth(), bounds.getEast()],
[bounds.getSouth(), bounds.getWest()]
];
// 繪製最終矩形
L.rectangle(bounds, {
color: '#FF6B6B',
fillColor: '#FF6B6B',
fillOpacity: 0.2,
weight: 2
}).addTo(selectionLayer);
// 添加四個角的標記
rectPoints.forEach(point => {
L.circleMarker(point, {
radius: 5,
color: '#FF6B6B',
fillColor: '#FF6B6B',
fillOpacity: 0.8
}).addTo(selectionLayer);
});
// 發送矩形數據到Python
if (bridge) {
var pointsStr = JSON.stringify(rectPoints);
bridge.rectangleSelected(pointsStr);
console.log('矩形選擇完成:', rectPoints);
}
}
// 重置狀態
selectionMode = null;
document.getElementById('select-drones-btn').classList.remove('active');
document.getElementById('select-rect-btn').classList.remove('active');
map.dragging.enable();
}
// ================================================================================
// 開始任務
function startMission() {
if (!centerPosition || !targetPosition) {
alert('請先設定中心點和目標點');
return;
}
if (bridge) {
bridge.startMissionSignal(
centerPosition.lat, centerPosition.lng,
targetPosition.lat, targetPosition.lng
);
console.log('開始任務:', centerPosition, targetPosition);
}
}
// ================================================================================ // ================================================================================
function initTrajectory(id) { function initTrajectory(id) {
@ -256,6 +680,11 @@ class DroneMap:
// 清除舊的任務規劃標記 // 清除舊的任務規劃標記
clearMissionPlan(); clearMissionPlan();
// 保存中心點和目標點位置
centerPosition = {lat: centerLat, lng: centerLon};
targetPosition = {lat: targetLat, lng: targetLon};
updateMissionInfo();
// 繪製中心點標記 "C"縮小到 20px // 繪製中心點標記 "C"縮小到 20px
var centerIcon = L.divIcon({ var centerIcon = L.divIcon({
className: 'mission-center', className: 'mission-center',
@ -342,6 +771,11 @@ class DroneMap:
missionLine = null; missionLine = null;
} }
// 清除位置資訊
centerPosition = null;
targetPosition = null;
updateMissionInfo();
console.log('任務規劃已清除'); console.log('任務規劃已清除');
} }
// ================================================================================ // ================================================================================
@ -433,10 +867,25 @@ class DroneMap:
"""獲取無人機點擊信號""" """獲取無人機點擊信號"""
return self.bridge.drone_clicked return self.bridge.drone_clicked
def get_start_mission_signal(self):
"""獲取開始任務信號"""
return self.bridge.start_mission_signal
def get_rectangle_selected_signal(self):
"""獲取矩形選擇信號"""
return self.bridge.rectangle_selected
def get_polygon_selected_signal(self):
"""獲取多邊形選擇信號"""
return self.bridge.polygon_selected
class MapBridge(QObject): class MapBridge(QObject):
"""JavaScript 和 Python 之間的橋接類""" """JavaScript 和 Python 之間的橋接類"""
gps_signal = pyqtSignal(float, float) # lat, lon gps_signal = pyqtSignal(float, float) # lat, lon
drone_clicked = pyqtSignal(str) # drone_id drone_clicked = pyqtSignal(str) # drone_id
start_mission_signal = pyqtSignal(float, float, float, float) # center_lat, center_lon, target_lat, target_lon
rectangle_selected = pyqtSignal(str) # JSON string of rectangle points
polygon_selected = pyqtSignal(str) # JSON string of polygon points
def __init__(self): def __init__(self):
super().__init__() super().__init__()
@ -449,4 +898,22 @@ class MapBridge(QObject):
@pyqtSlot(str) @pyqtSlot(str)
def emitDroneClicked(self, drone_id): def emitDroneClicked(self, drone_id):
"""供 JavaScript 調用的方法 - 當無人機被點擊時""" """供 JavaScript 調用的方法 - 當無人機被點擊時"""
self.drone_clicked.emit(drone_id) self.drone_clicked.emit(drone_id)
@pyqtSlot(float, float, float, float)
def startMissionSignal(self, center_lat, center_lon, target_lat, target_lon):
"""供 JavaScript 調用的方法 - 開始任務"""
self.start_mission_signal.emit(center_lat, center_lon, target_lat, target_lon)
print(f"🚀 開始任務信號已發出: C({center_lat}, {center_lon}) -> T({target_lat}, {target_lon})")
@pyqtSlot(str)
def rectangleSelected(self, points_json):
"""供 JavaScript 調用的方法 - 矩形選擇完成"""
self.rectangle_selected.emit(points_json)
print(f"📦 矩形區域已選擇: {points_json}")
@pyqtSlot(str)
def polygonSelected(self, points_json):
"""供 JavaScript 調用的方法 - 多邊形選擇完成"""
self.polygon_selected.emit(points_json)
print(f"🔷 多邊形區域已選擇: {points_json}")
Loading…
Cancel
Save