|
|
|
|
@ -3,18 +3,21 @@ import rclpy
|
|
|
|
|
from rclpy.node import Node
|
|
|
|
|
from PyQt6.QtWidgets import (QApplication, QMainWindow, QVBoxLayout, QHBoxLayout,
|
|
|
|
|
QWidget, QLabel, QSplitter, QScrollArea,
|
|
|
|
|
QSizePolicy, QApplication)
|
|
|
|
|
QSizePolicy, QTabWidget, QTableWidget, QTableWidgetItem,
|
|
|
|
|
QHeaderView, QPushButton, QCheckBox)
|
|
|
|
|
from PyQt6.QtCore import Qt, QTimer, QObject, pyqtSignal
|
|
|
|
|
from PyQt6.QtWebEngineWidgets import QWebEngineView
|
|
|
|
|
import math
|
|
|
|
|
import re
|
|
|
|
|
import os
|
|
|
|
|
import sys
|
|
|
|
|
from threading import Lock
|
|
|
|
|
from geometry_msgs.msg import Point, Vector3
|
|
|
|
|
from sensor_msgs.msg import BatteryState, NavSatFix, Imu
|
|
|
|
|
from std_msgs.msg import Float64
|
|
|
|
|
from mavros_msgs.msg import VfrHud, State
|
|
|
|
|
from mavros_msgs.msg import State, VfrHud
|
|
|
|
|
from mavros_msgs.srv import CommandBool, CommandTOL, SetMode
|
|
|
|
|
import asyncio
|
|
|
|
|
from functools import partial
|
|
|
|
|
|
|
|
|
|
class DroneSignals(QObject):
|
|
|
|
|
update_signal = pyqtSignal(str, str, object) # (msg_type, drone_id, data)
|
|
|
|
|
@ -26,6 +29,10 @@ class DroneMonitor(Node):
|
|
|
|
|
self.drone_topics = {}
|
|
|
|
|
self.lock = Lock()
|
|
|
|
|
|
|
|
|
|
self.arm_clients = {}
|
|
|
|
|
self.takeoff_clients = {}
|
|
|
|
|
self.selected_drones = set()
|
|
|
|
|
|
|
|
|
|
# 主题检测定时器
|
|
|
|
|
self.create_timer(1.0, self.scan_topics)
|
|
|
|
|
|
|
|
|
|
@ -43,11 +50,22 @@ class DroneMonitor(Node):
|
|
|
|
|
|
|
|
|
|
for drone_id in found_drones:
|
|
|
|
|
if not hasattr(self, f'drone_{drone_id}_subs'):
|
|
|
|
|
self.setup_drone_subs(drone_id)
|
|
|
|
|
self.setup_drone(drone_id)
|
|
|
|
|
|
|
|
|
|
def setup_drone_subs(self, drone_id):
|
|
|
|
|
def setup_drone(self, drone_id):
|
|
|
|
|
base_topic = f'/MavLinkBus/{drone_id}'
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
# Add service clients
|
|
|
|
|
self.arm_clients[drone_id] = self.create_client(
|
|
|
|
|
CommandBool,
|
|
|
|
|
f'{base_topic}/cmd/arming'
|
|
|
|
|
)
|
|
|
|
|
self.takeoff_clients[drone_id] = self.create_client(
|
|
|
|
|
CommandTOL,
|
|
|
|
|
f'{base_topic}/cmd/takeoff'
|
|
|
|
|
)
|
|
|
|
|
|
|
|
|
|
subs = {
|
|
|
|
|
'attitude': self.create_subscription(
|
|
|
|
|
Imu,
|
|
|
|
|
@ -61,12 +79,6 @@ class DroneMonitor(Node):
|
|
|
|
|
lambda msg, did=drone_id: self.battery_callback(did, msg),
|
|
|
|
|
10
|
|
|
|
|
),
|
|
|
|
|
'state': self.create_subscription(
|
|
|
|
|
State,
|
|
|
|
|
f'{base_topic}/state',
|
|
|
|
|
lambda msg, did=drone_id: self.state_callback(did, msg),
|
|
|
|
|
10
|
|
|
|
|
),
|
|
|
|
|
'global': self.create_subscription(
|
|
|
|
|
NavSatFix,
|
|
|
|
|
f'{base_topic}/global_position/global',
|
|
|
|
|
@ -91,6 +103,24 @@ class DroneMonitor(Node):
|
|
|
|
|
lambda msg, did=drone_id: self.local_vel_callback(did, msg),
|
|
|
|
|
10
|
|
|
|
|
),
|
|
|
|
|
'loss_rate': self.create_subscription(
|
|
|
|
|
Float64,
|
|
|
|
|
f'{base_topic}/packet_loss_rate',
|
|
|
|
|
lambda msg, did=drone_id: self.loss_rate_callback(did, msg),
|
|
|
|
|
10
|
|
|
|
|
),
|
|
|
|
|
'state': self.create_subscription(
|
|
|
|
|
State,
|
|
|
|
|
f'{base_topic}/state',
|
|
|
|
|
lambda msg, did=drone_id: self.state_callback(did, msg),
|
|
|
|
|
10
|
|
|
|
|
),
|
|
|
|
|
'ping': self.create_subscription(
|
|
|
|
|
Float64,
|
|
|
|
|
f'{base_topic}/ping',
|
|
|
|
|
lambda msg, did=drone_id: self.ping_callback(did, msg),
|
|
|
|
|
10
|
|
|
|
|
),
|
|
|
|
|
'vfr_hud': self.create_subscription(
|
|
|
|
|
VfrHud,
|
|
|
|
|
f'{base_topic}/vfr_hud',
|
|
|
|
|
@ -102,6 +132,46 @@ class DroneMonitor(Node):
|
|
|
|
|
setattr(self, f'drone_{drone_id}_subs', subs)
|
|
|
|
|
self.signals.update_signal.emit('new_drone', drone_id, None)
|
|
|
|
|
|
|
|
|
|
async def arm_drone(self, drone_id, arm):
|
|
|
|
|
if drone_id not in self.arm_clients:
|
|
|
|
|
return False
|
|
|
|
|
|
|
|
|
|
client = self.arm_clients[drone_id]
|
|
|
|
|
if not client.wait_for_service(timeout_sec=1.0):
|
|
|
|
|
return False
|
|
|
|
|
|
|
|
|
|
request = CommandBool.Request()
|
|
|
|
|
request.value = arm
|
|
|
|
|
|
|
|
|
|
future = client.call_async(request)
|
|
|
|
|
try:
|
|
|
|
|
response = await future
|
|
|
|
|
return response.success
|
|
|
|
|
except Exception as e:
|
|
|
|
|
self.get_logger().error(f'Arm service call failed: {e}')
|
|
|
|
|
return False
|
|
|
|
|
|
|
|
|
|
async def takeoff_drone(self, drone_id, altitude=10.0):
|
|
|
|
|
if drone_id not in self.takeoff_clients:
|
|
|
|
|
return False
|
|
|
|
|
|
|
|
|
|
client = self.takeoff_clients[drone_id]
|
|
|
|
|
if not client.wait_for_service(timeout_sec=1.0):
|
|
|
|
|
return False
|
|
|
|
|
|
|
|
|
|
request = CommandTOL.Request()
|
|
|
|
|
request.altitude = altitude
|
|
|
|
|
request.min_pitch = 0.0
|
|
|
|
|
request.yaw = 0.0
|
|
|
|
|
|
|
|
|
|
future = client.call_async(request)
|
|
|
|
|
try:
|
|
|
|
|
response = await future
|
|
|
|
|
return response.success
|
|
|
|
|
except Exception as e:
|
|
|
|
|
self.get_logger().error(f'Takeoff service call failed: {e}')
|
|
|
|
|
return False
|
|
|
|
|
|
|
|
|
|
def quaternion_to_euler(self, q):
|
|
|
|
|
sinr_cosp = 2 * (q.w * q.x + q.y * q.z)
|
|
|
|
|
cosr_cosp = 1 - 2 * (q.x**2 + q.y**2)
|
|
|
|
|
@ -116,7 +186,7 @@ class DroneMonitor(Node):
|
|
|
|
|
|
|
|
|
|
return math.degrees(roll), math.degrees(pitch), math.degrees(yaw)
|
|
|
|
|
|
|
|
|
|
# 回调函数
|
|
|
|
|
# callbacks
|
|
|
|
|
def attitude_callback(self, drone_id, msg):
|
|
|
|
|
if hasattr(msg, 'orientation'):
|
|
|
|
|
roll, pitch, yaw = self.quaternion_to_euler(msg.orientation)
|
|
|
|
|
@ -176,12 +246,21 @@ class DroneMonitor(Node):
|
|
|
|
|
'climb': msg.climb
|
|
|
|
|
})
|
|
|
|
|
|
|
|
|
|
def loss_rate_callback(self, drone_id, msg):
|
|
|
|
|
self.signals.update_signal.emit('loss_rate', drone_id, {
|
|
|
|
|
'loss_rate': msg.data
|
|
|
|
|
})
|
|
|
|
|
|
|
|
|
|
def ping_callback(self, drone_id, msg):
|
|
|
|
|
self.signals.update_signal.emit('ping', drone_id, {
|
|
|
|
|
'ping': msg.data
|
|
|
|
|
})
|
|
|
|
|
|
|
|
|
|
class ControlStationUI(QMainWindow):
|
|
|
|
|
def __init__(self):
|
|
|
|
|
super().__init__()
|
|
|
|
|
self.setWindowTitle('GCS')
|
|
|
|
|
self.resize(1400, 900)
|
|
|
|
|
self.drones = {}
|
|
|
|
|
|
|
|
|
|
# 初始化ROS2
|
|
|
|
|
rclpy.init()
|
|
|
|
|
@ -193,7 +272,26 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
self.executor.add_node(self.monitor)
|
|
|
|
|
|
|
|
|
|
# 初始化UI
|
|
|
|
|
self.drones = {}
|
|
|
|
|
self.info_types = ["模式", "ARM", "電壓", "高度", "Local", "Velocity", "地速", "航向",
|
|
|
|
|
"Roll", "Pitch", "Yaw", "丟包", "延遲"]
|
|
|
|
|
self.info_type_map = {
|
|
|
|
|
"mode": 0,
|
|
|
|
|
"armed": 1,
|
|
|
|
|
"battery": 2,
|
|
|
|
|
"altitude": 3,
|
|
|
|
|
"local": 4,
|
|
|
|
|
"velocity": 5,
|
|
|
|
|
"groundspeed": 6,
|
|
|
|
|
"heading": 7,
|
|
|
|
|
"roll": 8,
|
|
|
|
|
"pitch": 9,
|
|
|
|
|
"yaw": 10,
|
|
|
|
|
"loss_rate": 11,
|
|
|
|
|
"ping": 12
|
|
|
|
|
}
|
|
|
|
|
self.drone_positions = {}
|
|
|
|
|
self.drone_headings = {}
|
|
|
|
|
self.map_loaded = False
|
|
|
|
|
self.init_ui()
|
|
|
|
|
|
|
|
|
|
@ -203,22 +301,94 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
self.timer.start(50)
|
|
|
|
|
|
|
|
|
|
def init_ui(self):
|
|
|
|
|
|
|
|
|
|
# 只呼叫一次
|
|
|
|
|
main_splitter = QSplitter(Qt.Orientation.Horizontal)
|
|
|
|
|
|
|
|
|
|
# 左侧信息面板
|
|
|
|
|
left_panel = QWidget()
|
|
|
|
|
left_layout = QVBoxLayout(left_panel)
|
|
|
|
|
left_layout.setContentsMargins(5, 5, 5, 5)
|
|
|
|
|
# 左側 TabWidget
|
|
|
|
|
self.left_tab = QTabWidget()
|
|
|
|
|
|
|
|
|
|
# — 分頁 1:Drone Panel
|
|
|
|
|
self.drone_panel_container = QWidget()
|
|
|
|
|
self.drone_panel_layout = QVBoxLayout(self.drone_panel_container)
|
|
|
|
|
self.drone_panel_layout.setAlignment(Qt.AlignmentFlag.AlignTop)
|
|
|
|
|
self.drone_panel_layout.setSpacing(0)
|
|
|
|
|
self.drone_panel_layout.setContentsMargins(10, 10, 10, 10)
|
|
|
|
|
|
|
|
|
|
# Wrap drone panel in scroll area
|
|
|
|
|
scroll = QScrollArea()
|
|
|
|
|
scroll.setWidget(self.drone_panel_container)
|
|
|
|
|
scroll.setWidgetResizable(True)
|
|
|
|
|
self.left_tab.addTab(scroll, "無人機")
|
|
|
|
|
|
|
|
|
|
# 底部控制按鈕區域
|
|
|
|
|
bottom_control = QWidget()
|
|
|
|
|
bottom_layout = QHBoxLayout(bottom_control)
|
|
|
|
|
|
|
|
|
|
select_all_btn = QPushButton("全選")
|
|
|
|
|
select_all_btn.clicked.connect(self.handle_select_all)
|
|
|
|
|
select_all_btn.setStyleSheet("""
|
|
|
|
|
QPushButton {
|
|
|
|
|
background-color: #444;
|
|
|
|
|
color: #DDD;
|
|
|
|
|
border: none;
|
|
|
|
|
padding: 5px 10px;
|
|
|
|
|
border-radius: 4px;
|
|
|
|
|
min-width: 80px;
|
|
|
|
|
}
|
|
|
|
|
QPushButton:hover { background-color: #555; }
|
|
|
|
|
""")
|
|
|
|
|
|
|
|
|
|
# 信息滚动区域
|
|
|
|
|
scroll_area = QScrollArea()
|
|
|
|
|
scroll_area.setWidgetResizable(True)
|
|
|
|
|
self.info_container = QWidget()
|
|
|
|
|
self.info_layout = QVBoxLayout(self.info_container)
|
|
|
|
|
self.info_layout.setAlignment(Qt.AlignmentFlag.AlignTop)
|
|
|
|
|
scroll_area.setWidget(self.info_container)
|
|
|
|
|
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: 5px 10px;
|
|
|
|
|
border-radius: 4px;
|
|
|
|
|
min-width: 80px;
|
|
|
|
|
}
|
|
|
|
|
QPushButton:hover { background-color: #555; }
|
|
|
|
|
""")
|
|
|
|
|
|
|
|
|
|
left_layout.addWidget(scroll_area)
|
|
|
|
|
takeoff_all_btn = QPushButton("批次起飛")
|
|
|
|
|
takeoff_all_btn.clicked.connect(self.handle_takeoff_selected)
|
|
|
|
|
takeoff_all_btn.setStyleSheet("""
|
|
|
|
|
QPushButton {
|
|
|
|
|
background-color: #444;
|
|
|
|
|
color: #DDD;
|
|
|
|
|
border: none;
|
|
|
|
|
padding: 5px 10px;
|
|
|
|
|
border-radius: 4px;
|
|
|
|
|
min-width: 80px;
|
|
|
|
|
}
|
|
|
|
|
QPushButton:hover { background-color: #555; }
|
|
|
|
|
""")
|
|
|
|
|
|
|
|
|
|
bottom_layout.addWidget(select_all_btn)
|
|
|
|
|
bottom_layout.addWidget(arm_all_btn)
|
|
|
|
|
bottom_layout.addWidget(takeoff_all_btn)
|
|
|
|
|
bottom_layout.addStretch()
|
|
|
|
|
|
|
|
|
|
# — 分頁 2:Overview Table
|
|
|
|
|
self.overview_table = QTableWidget()
|
|
|
|
|
# 一開始只有一欄
|
|
|
|
|
self.overview_table.setColumnCount(1)
|
|
|
|
|
self.overview_table.setRowCount(len(self.info_types))
|
|
|
|
|
self.overview_table.setHorizontalHeaderLabels(["資訊"])
|
|
|
|
|
header = self.overview_table.horizontalHeader()
|
|
|
|
|
# 只有第一欄自動收縮到內容寬度,其它欄不動
|
|
|
|
|
header.setSectionResizeMode(0, QHeaderView.ResizeMode.ResizeToContents)
|
|
|
|
|
self.overview_table.verticalHeader().setVisible(False)
|
|
|
|
|
for i, txt in enumerate(self.info_types):
|
|
|
|
|
item = QTableWidgetItem(txt)
|
|
|
|
|
item.setFlags(Qt.ItemFlag.ItemIsEnabled)
|
|
|
|
|
item.setTextAlignment(Qt.AlignmentFlag.AlignCenter)
|
|
|
|
|
self.overview_table.setItem(i, 0, item)
|
|
|
|
|
|
|
|
|
|
self.left_tab.addTab(self.overview_table, "總覽")
|
|
|
|
|
|
|
|
|
|
# 右侧地图区域
|
|
|
|
|
self.map_view = QWebEngineView()
|
|
|
|
|
@ -305,7 +475,17 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
self.map_view.setHtml(inline_html)
|
|
|
|
|
self.map_view.loadFinished.connect(self.on_map_loaded)
|
|
|
|
|
|
|
|
|
|
main_splitter.addWidget(left_panel)
|
|
|
|
|
# Create left container and its layout
|
|
|
|
|
left_container = QWidget()
|
|
|
|
|
left_layout = QVBoxLayout(left_container)
|
|
|
|
|
left_layout.setContentsMargins(0, 0, 0, 0)
|
|
|
|
|
|
|
|
|
|
# Add tab widget and bottom control to left container
|
|
|
|
|
left_layout.addWidget(self.left_tab)
|
|
|
|
|
left_layout.addWidget(bottom_control)
|
|
|
|
|
|
|
|
|
|
# Add widgets to splitter
|
|
|
|
|
main_splitter.addWidget(left_container)
|
|
|
|
|
main_splitter.addWidget(self.map_view)
|
|
|
|
|
main_splitter.setSizes([400, 1000])
|
|
|
|
|
|
|
|
|
|
@ -344,6 +524,14 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
header_layout = QHBoxLayout(header)
|
|
|
|
|
header_layout.setContentsMargins(0, 0, 0, 0)
|
|
|
|
|
|
|
|
|
|
# 在標題列加入勾選框
|
|
|
|
|
checkbox = QCheckBox()
|
|
|
|
|
checkbox.setObjectName(f"{drone_id}_checkbox")
|
|
|
|
|
checkbox.setStyleSheet("QCheckBox { color: #DDD; }")
|
|
|
|
|
checkbox.stateChanged.connect(lambda state: self.handle_drone_selection(drone_id, state))
|
|
|
|
|
|
|
|
|
|
header_layout.insertWidget(0, checkbox) # 插入到最前面
|
|
|
|
|
|
|
|
|
|
# ID显示
|
|
|
|
|
id_label = QLabel(drone_id)
|
|
|
|
|
id_label.setStyleSheet("""
|
|
|
|
|
@ -365,14 +553,79 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
|
|
|
|
|
# 数据字段(带标签)
|
|
|
|
|
self.create_data_row(layout, "模式:", f"{drone_id}_mode", "--")
|
|
|
|
|
self.create_data_row(layout, "電壓:", f"{drone_id}_battery", "--")
|
|
|
|
|
self.create_data_row(layout, "GPS:", f"{drone_id}_gps", "--")
|
|
|
|
|
self.create_data_row(layout, "ARM:", f"{drone_id}_armed", "--")
|
|
|
|
|
self.create_data_row(layout, "電池:", f"{drone_id}_battery", "--")
|
|
|
|
|
self.create_data_row(layout, "高度:", f"{drone_id}_altitude", "--")
|
|
|
|
|
self.create_data_row(layout, "Local:", f"{drone_id}_local", "--")
|
|
|
|
|
self.create_data_row(layout, "HUD:", f"{drone_id}_hud", "--")
|
|
|
|
|
self.create_data_row(layout, "地速:", f"{drone_id}_groundspeed", "--")
|
|
|
|
|
self.create_data_row(layout, "航向:", f"{drone_id}_heading", "--")
|
|
|
|
|
|
|
|
|
|
# Add control buttons
|
|
|
|
|
control_widget = QWidget()
|
|
|
|
|
control_layout = QHBoxLayout(control_widget)
|
|
|
|
|
control_layout.setContentsMargins(0, 0, 0, 0)
|
|
|
|
|
|
|
|
|
|
arm_btn = QPushButton("解鎖")
|
|
|
|
|
arm_btn.setObjectName(f"{drone_id}_arm_btn")
|
|
|
|
|
arm_btn.clicked.connect(lambda: self.handle_arm(drone_id))
|
|
|
|
|
arm_btn.setStyleSheet("""
|
|
|
|
|
QPushButton {
|
|
|
|
|
background-color: #444;
|
|
|
|
|
color: #DDD;
|
|
|
|
|
border: none;
|
|
|
|
|
padding: 5px 10px;
|
|
|
|
|
border-radius: 4px;
|
|
|
|
|
}
|
|
|
|
|
QPushButton:hover {
|
|
|
|
|
background-color: #555;
|
|
|
|
|
}
|
|
|
|
|
""")
|
|
|
|
|
|
|
|
|
|
takeoff_btn = QPushButton("起飛")
|
|
|
|
|
takeoff_btn.setObjectName(f"{drone_id}_takeoff_btn")
|
|
|
|
|
takeoff_btn.clicked.connect(lambda: self.handle_takeoff(drone_id))
|
|
|
|
|
takeoff_btn.setStyleSheet("""
|
|
|
|
|
QPushButton {
|
|
|
|
|
background-color: #444;
|
|
|
|
|
color: #DDD;
|
|
|
|
|
border: none;
|
|
|
|
|
padding: 5px 10px;
|
|
|
|
|
border-radius: 4px;
|
|
|
|
|
}
|
|
|
|
|
QPushButton:hover {
|
|
|
|
|
background-color: #555;
|
|
|
|
|
}
|
|
|
|
|
""")
|
|
|
|
|
|
|
|
|
|
control_layout.addWidget(arm_btn)
|
|
|
|
|
control_layout.addWidget(takeoff_btn)
|
|
|
|
|
control_layout.addStretch()
|
|
|
|
|
|
|
|
|
|
layout.addWidget(control_widget)
|
|
|
|
|
|
|
|
|
|
return panel
|
|
|
|
|
|
|
|
|
|
def handle_arm(self, drone_id):
|
|
|
|
|
loop = asyncio.get_event_loop()
|
|
|
|
|
arm_state = not self.monitor.get_arm_state(drone_id) # Toggle arm state
|
|
|
|
|
future = self.monitor.arm_drone(drone_id, arm_state)
|
|
|
|
|
loop.create_task(self.handle_service_response(future, f"{'解鎖' if arm_state else '上鎖'} {drone_id}"))
|
|
|
|
|
|
|
|
|
|
def handle_takeoff(self, drone_id):
|
|
|
|
|
loop = asyncio.get_event_loop()
|
|
|
|
|
future = self.monitor.takeoff_drone(drone_id, 10.0) # 10 meters default
|
|
|
|
|
loop.create_task(self.handle_service_response(future, f"起飛 {drone_id}"))
|
|
|
|
|
|
|
|
|
|
async def handle_service_response(self, future, action):
|
|
|
|
|
try:
|
|
|
|
|
result = await future
|
|
|
|
|
if result:
|
|
|
|
|
self.statusBar().showMessage(f"{action} 成功", 3000)
|
|
|
|
|
else:
|
|
|
|
|
self.statusBar().showMessage(f"{action} 失敗", 3000)
|
|
|
|
|
except Exception as e:
|
|
|
|
|
self.statusBar().showMessage(f"{action} 錯誤: {str(e)}", 3000)
|
|
|
|
|
|
|
|
|
|
def create_data_row(self, layout, title, object_name, default):
|
|
|
|
|
row = QWidget()
|
|
|
|
|
hbox = QHBoxLayout(row)
|
|
|
|
|
@ -394,90 +647,235 @@ class ControlStationUI(QMainWindow):
|
|
|
|
|
layout.addWidget(row)
|
|
|
|
|
|
|
|
|
|
def update_ui(self, msg_type, drone_id, data):
|
|
|
|
|
# 檢查是否為新無人機,若是則加入無人機面板
|
|
|
|
|
if msg_type == 'new_drone':
|
|
|
|
|
self.add_drone(drone_id)
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
# 確認無人機面板存在
|
|
|
|
|
if not (panel := self.drones.get(drone_id)):
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
# 更新特定欄位並在總覽頁面更新
|
|
|
|
|
if msg_type == 'state':
|
|
|
|
|
mode = data['mode']
|
|
|
|
|
self.update_field(panel, drone_id, 'mode', f"{mode}",
|
|
|
|
|
'#FF5555' if '返航' in data else '#55FF55')
|
|
|
|
|
mode = data.get('mode', 'UNKNOWN')
|
|
|
|
|
armed = data.get('armed', False)
|
|
|
|
|
mode_color = '#FF5555' if any(x in mode.upper() for x in ['RTL', '返航', 'EMERGENCY']) else '#55FF55'
|
|
|
|
|
arm_text = "ARMED" if armed else "DISARMED"
|
|
|
|
|
arm_color = '#55FF55' if armed else '#FF5555'
|
|
|
|
|
|
|
|
|
|
# 更新無人機面板欄位
|
|
|
|
|
self.update_field(panel, drone_id, 'mode', mode, mode_color)
|
|
|
|
|
self.update_field(panel, drone_id, 'armed', arm_text, arm_color)
|
|
|
|
|
|
|
|
|
|
# 更新總覽頁面欄位
|
|
|
|
|
self.update_overview_table(drone_id, 'mode', mode)
|
|
|
|
|
self.update_overview_table(drone_id, 'armed', arm_text)
|
|
|
|
|
|
|
|
|
|
elif msg_type == 'battery':
|
|
|
|
|
voltage = data.get('voltage', 0)
|
|
|
|
|
self.update_field(panel, drone_id, 'battery',
|
|
|
|
|
f"{voltage:.1f} V",
|
|
|
|
|
'#FF6464' if voltage < 12 else '#FFFFFF')
|
|
|
|
|
voltage = 14.8
|
|
|
|
|
|
|
|
|
|
# 使用標準電壓判斷電池節數
|
|
|
|
|
cells_by_max = voltage / 4.2
|
|
|
|
|
cells_by_min = voltage / 3.7
|
|
|
|
|
|
|
|
|
|
# 檢查是否為合理的電池組
|
|
|
|
|
is_valid_cells = abs(round(cells_by_max) - cells_by_min) < 0.5
|
|
|
|
|
num_cells = round(cells_by_max)
|
|
|
|
|
|
|
|
|
|
if not is_valid_cells or num_cells < 2:
|
|
|
|
|
# 電壓異常,顯示錯誤
|
|
|
|
|
text = f"{voltage:.1f}V (電壓異常!)"
|
|
|
|
|
voltage_color = '#FF0000' # 紅色
|
|
|
|
|
else:
|
|
|
|
|
# 正常電壓計算
|
|
|
|
|
cell_voltage = voltage / num_cells
|
|
|
|
|
cell_max = 4.2
|
|
|
|
|
cell_min = 3.7
|
|
|
|
|
|
|
|
|
|
# 計算電量百分比
|
|
|
|
|
percentage = max(0, min(100, ((cell_voltage - cell_min) / (cell_max - cell_min)) * 100))
|
|
|
|
|
|
|
|
|
|
# 根據百分比設置顏色
|
|
|
|
|
if percentage < 20:
|
|
|
|
|
voltage_color = '#FF6464' # 紅色 (低電量)
|
|
|
|
|
elif percentage < 40:
|
|
|
|
|
voltage_color = '#FFA500' # 橘色 (中低電量)
|
|
|
|
|
else:
|
|
|
|
|
voltage_color = '#FFFFFF' # 白色 (正常電量)
|
|
|
|
|
|
|
|
|
|
# 顯示總電壓、電池節數、單節電壓和百分比
|
|
|
|
|
text = f"{voltage:.1f}V ({cell_voltage:.2f}V / {percentage:.0f}%)"
|
|
|
|
|
|
|
|
|
|
self.update_field(panel, drone_id, 'battery', text, voltage_color)
|
|
|
|
|
self.update_overview_table(drone_id, 'battery', text)
|
|
|
|
|
|
|
|
|
|
elif msg_type == 'gps':
|
|
|
|
|
lat, lon = data['lat'], data['lon']
|
|
|
|
|
lat, lon = data.get('lat', 0), data.get('lon', 0)
|
|
|
|
|
self.drone_positions[drone_id] = (lat, lon)
|
|
|
|
|
text = (f"緯度: {lat:.6f}°\n"
|
|
|
|
|
f"經度: {lon:.6f}°")
|
|
|
|
|
text = f"{lat:.6f}°, {lon:.6f}°"
|
|
|
|
|
self.update_field(panel, drone_id, 'gps', text)
|
|
|
|
|
self.update_overview_table(drone_id, 'gps', text)
|
|
|
|
|
|
|
|
|
|
elif msg_type == 'altitude':
|
|
|
|
|
text = (f"{data['altitude']:.1f} m")
|
|
|
|
|
altitude = data.get('altitude', 0)
|
|
|
|
|
text = f"{altitude:.1f} m"
|
|
|
|
|
self.update_field(panel, drone_id, 'altitude', text)
|
|
|
|
|
self.update_overview_table(drone_id, 'altitude', text)
|
|
|
|
|
|
|
|
|
|
elif msg_type == 'local_pose':
|
|
|
|
|
text = (f"({data['x']:.1f}, {data['y']:.1f}, {data['z']:.1f})")
|
|
|
|
|
text = f"{data['x']:.1f}, {data['y']:.1f}"
|
|
|
|
|
self.update_field(panel, drone_id, 'local', text)
|
|
|
|
|
self.update_overview_table(drone_id, 'local', text)
|
|
|
|
|
|
|
|
|
|
elif msg_type == 'hud':
|
|
|
|
|
heading = data['heading']
|
|
|
|
|
text = (f"地速: {data['groundspeed']:.1f} m/s\n"
|
|
|
|
|
f"航向: {heading:.1f}°")
|
|
|
|
|
self.update_field(panel, drone_id, 'hud', text)
|
|
|
|
|
|
|
|
|
|
if self.map_loaded and drone_id in self.drone_positions:
|
|
|
|
|
lat, lon = self.drone_positions[drone_id]
|
|
|
|
|
js = f"updateDrone({lat:.6f}, {lon:.6f}, '{drone_id}', {heading:.1f});"
|
|
|
|
|
self.map_view.page().runJavaScript(js)
|
|
|
|
|
'''
|
|
|
|
|
heading = data.get('heading', 0)
|
|
|
|
|
self.drone_headings[drone_id] = heading
|
|
|
|
|
groundspeed = data.get('groundspeed', 0)
|
|
|
|
|
heading_text = f"{heading:.1f}°"
|
|
|
|
|
groundspeed_text = f"{groundspeed:.1f} m/s"
|
|
|
|
|
self.update_field(panel, drone_id, 'heading', heading_text)
|
|
|
|
|
self.update_field(panel, drone_id, 'groundspeed', groundspeed_text)
|
|
|
|
|
self.update_overview_table(drone_id, 'heading', heading_text)
|
|
|
|
|
self.update_overview_table(drone_id, 'groundspeed', groundspeed_text)
|
|
|
|
|
|
|
|
|
|
elif msg_type == 'loss_rate':
|
|
|
|
|
loss_rate = data.get('loss_rate', 0)
|
|
|
|
|
text = f"{loss_rate:.1f}%"
|
|
|
|
|
self.update_field(panel, drone_id, 'loss_rate', text)
|
|
|
|
|
self.update_overview_table(drone_id, 'loss_rate', text)
|
|
|
|
|
|
|
|
|
|
elif msg_type == 'ping':
|
|
|
|
|
ping = data.get('ping', 0)
|
|
|
|
|
text = f"{ping:.1f} ms"
|
|
|
|
|
self.update_field(panel, drone_id, 'ping', text)
|
|
|
|
|
self.update_overview_table(drone_id, 'ping', text)
|
|
|
|
|
|
|
|
|
|
elif msg_type == 'velocity':
|
|
|
|
|
text = (f"VX: {data['vx']:.1f} m/s\n"
|
|
|
|
|
f"VY: {data['vy']:.1f} m/s\n"
|
|
|
|
|
f"VZ: {data['vz']:.1f} m/s")
|
|
|
|
|
self.update_field(panel, drone_id, 'velocity', text)
|
|
|
|
|
text = f"{data['vx']:.1f}, {data['vy']:.1f}"
|
|
|
|
|
self.update_overview_table(drone_id, 'velocity', text)
|
|
|
|
|
|
|
|
|
|
elif msg_type == 'attitude':
|
|
|
|
|
text = (f"Roll: {data['roll']:.1f}°\n"
|
|
|
|
|
f"Pitch: {data['pitch']:.1f}°\n"
|
|
|
|
|
f"Yaw: {data['yaw']:.1f}°")
|
|
|
|
|
self.update_field(panel, drone_id, 'attitude', text)
|
|
|
|
|
'''
|
|
|
|
|
roll = data.get('roll', 0)
|
|
|
|
|
pitch = data.get('pitch', 0)
|
|
|
|
|
yaw = data.get('yaw', 0)
|
|
|
|
|
roll_text = f"{roll:.1f}°"
|
|
|
|
|
pitch_text = f"{pitch:.1f}°"
|
|
|
|
|
yaw_text = f"{yaw:.1f}°"
|
|
|
|
|
self.update_overview_table(drone_id, 'roll', roll_text)
|
|
|
|
|
self.update_overview_table(drone_id, 'pitch', pitch_text)
|
|
|
|
|
self.update_overview_table(drone_id, 'yaw', yaw_text)
|
|
|
|
|
|
|
|
|
|
# 如果地圖已經載入,則更新地圖顯示無人機位置
|
|
|
|
|
if self.map_loaded and drone_id in self.drone_positions and drone_id in self.drone_headings:
|
|
|
|
|
lat, lon = self.drone_positions[drone_id]
|
|
|
|
|
heading = self.drone_headings[drone_id]
|
|
|
|
|
js = f"updateDrone({lat:.6f}, {lon:.6f}, '{drone_id}', {heading:.1f});"
|
|
|
|
|
self.map_view.page().runJavaScript(js)
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
def handle_drone_selection(self, drone_id, state):
|
|
|
|
|
"""處理個別無人機勾選狀態變化"""
|
|
|
|
|
if state == Qt.CheckState.Checked.value:
|
|
|
|
|
self.monitor.selected_drones.add(drone_id)
|
|
|
|
|
else:
|
|
|
|
|
self.monitor.selected_drones.discard(drone_id)
|
|
|
|
|
|
|
|
|
|
def handle_select_all(self):
|
|
|
|
|
"""處理全選按鈕 - 再次點擊時取消全選"""
|
|
|
|
|
# 檢查是否所有無人機都已被選中
|
|
|
|
|
all_selected = all(
|
|
|
|
|
self.drones[drone_id].findChild(QCheckBox, f"{drone_id}_checkbox").isChecked()
|
|
|
|
|
for drone_id in self.drones
|
|
|
|
|
)
|
|
|
|
|
|
|
|
|
|
# 如果全部已選中,則取消全選;否則全選
|
|
|
|
|
new_state = not all_selected
|
|
|
|
|
|
|
|
|
|
# 更新所有勾選框狀態
|
|
|
|
|
for drone_id in self.drones:
|
|
|
|
|
checkbox = self.drones[drone_id].findChild(QCheckBox, f"{drone_id}_checkbox")
|
|
|
|
|
if checkbox:
|
|
|
|
|
checkbox.setChecked(new_state)
|
|
|
|
|
|
|
|
|
|
def handle_arm_selected(self):
|
|
|
|
|
"""處理批次解鎖"""
|
|
|
|
|
loop = asyncio.get_event_loop()
|
|
|
|
|
for drone_id in self.monitor.selected_drones:
|
|
|
|
|
future = self.monitor.arm_drone(drone_id, True)
|
|
|
|
|
loop.create_task(self.handle_service_response(future, f"批次解鎖 {drone_id}"))
|
|
|
|
|
|
|
|
|
|
def handle_takeoff_selected(self):
|
|
|
|
|
"""處理批次起飛"""
|
|
|
|
|
loop = asyncio.get_event_loop()
|
|
|
|
|
for drone_id in self.monitor.selected_drones:
|
|
|
|
|
future = self.monitor.takeoff_drone(drone_id, 10.0)
|
|
|
|
|
loop.create_task(self.handle_service_response(future, f"批次起飛 {drone_id}"))
|
|
|
|
|
|
|
|
|
|
def update_field(self, panel, drone_id, field, text, color=None):
|
|
|
|
|
"""Update a specific field in the panel."""
|
|
|
|
|
if label := panel.findChild(QLabel, f"{drone_id}_{field}"):
|
|
|
|
|
label.setText(text)
|
|
|
|
|
if color:
|
|
|
|
|
label.setStyleSheet(f"color: {color};")
|
|
|
|
|
'''
|
|
|
|
|
def add_drone(self, drone_id):
|
|
|
|
|
if drone_id not in self.drones:
|
|
|
|
|
panel = self.create_drone_panel(drone_id)
|
|
|
|
|
self.info_layout.addWidget(panel)
|
|
|
|
|
self.drones[drone_id] = panel
|
|
|
|
|
'''
|
|
|
|
|
|
|
|
|
|
def update_overview_table(self, drone_id=None, field=None, value=None):
|
|
|
|
|
# Ensure the widget is available
|
|
|
|
|
if not hasattr(self, 'overview_table') or self.overview_table is None:
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
# Update a specific cell in the overview table
|
|
|
|
|
if drone_id and field and value:
|
|
|
|
|
col = 1 + list(self.drones.keys()).index(drone_id)
|
|
|
|
|
row = self.info_type_map.get(field, -1) # Get row from field mapping
|
|
|
|
|
|
|
|
|
|
if row == -1:
|
|
|
|
|
return # Invalid field, exit
|
|
|
|
|
|
|
|
|
|
item = self.overview_table.item(row, col)
|
|
|
|
|
if not item:
|
|
|
|
|
item = QTableWidgetItem()
|
|
|
|
|
self.overview_table.setItem(row, col, item)
|
|
|
|
|
|
|
|
|
|
item.setText(value) # Update the cell's text
|
|
|
|
|
item.setTextAlignment(Qt.AlignmentFlag.AlignCenter) # Center the text
|
|
|
|
|
|
|
|
|
|
# If no specific update, refresh entire table
|
|
|
|
|
if drone_id is None:
|
|
|
|
|
cols = 1 + len(self.drones)
|
|
|
|
|
self.overview_table.setColumnCount(cols)
|
|
|
|
|
headers = ["資訊"] + list(self.drones.keys())
|
|
|
|
|
self.overview_table.setHorizontalHeaderLabels(headers)
|
|
|
|
|
|
|
|
|
|
for col, did in enumerate(self.drones, start=1):
|
|
|
|
|
panel = self.drones[did]
|
|
|
|
|
for field, row in self.info_type_map.items():
|
|
|
|
|
lbl = panel.findChild(QLabel, f"{did}_{field}")
|
|
|
|
|
val = lbl.text() if lbl else "--"
|
|
|
|
|
val_item = QTableWidgetItem(val)
|
|
|
|
|
val_item.setTextAlignment(Qt.AlignmentFlag.AlignCenter)
|
|
|
|
|
self.overview_table.setItem(row, col, val_item)
|
|
|
|
|
|
|
|
|
|
def add_drone(self, drone_id):
|
|
|
|
|
if drone_id not in self.drones:
|
|
|
|
|
panel = self.create_drone_panel(drone_id)
|
|
|
|
|
self.info_layout.addWidget(panel)
|
|
|
|
|
self.drones[drone_id] = panel
|
|
|
|
|
|
|
|
|
|
# 清空原有 layout
|
|
|
|
|
for i in reversed(range(self.info_layout.count())):
|
|
|
|
|
widget = self.info_layout.itemAt(i).widget()
|
|
|
|
|
if widget:
|
|
|
|
|
self.info_layout.removeWidget(widget)
|
|
|
|
|
widget.setParent(None)
|
|
|
|
|
|
|
|
|
|
# 根據 key 排序後重新加入
|
|
|
|
|
for sorted_id in sorted(self.drones, key=lambda x: int(''.join(filter(str.isdigit, x)) or 0)):
|
|
|
|
|
self.info_layout.addWidget(self.drones[sorted_id])
|
|
|
|
|
"""只這一個 add_drone,不要再重複定義。"""
|
|
|
|
|
if drone_id in self.drones:
|
|
|
|
|
return
|
|
|
|
|
panel = self.create_drone_panel(drone_id)
|
|
|
|
|
self.drones[drone_id] = panel
|
|
|
|
|
|
|
|
|
|
# 重新排序並顯示所有 panel
|
|
|
|
|
# 先清空
|
|
|
|
|
while self.drone_panel_layout.count():
|
|
|
|
|
w = self.drone_panel_layout.takeAt(0).widget()
|
|
|
|
|
if w:
|
|
|
|
|
w.setParent(None)
|
|
|
|
|
# 再依照數字排序加入
|
|
|
|
|
for did in sorted(self.drones, key=lambda x: int(x[1:])):
|
|
|
|
|
self.drone_panel_layout.addWidget(self.drones[did])
|
|
|
|
|
|
|
|
|
|
# 更新總覽表
|
|
|
|
|
self.update_overview_table()
|
|
|
|
|
|
|
|
|
|
def spin_ros(self):
|
|
|
|
|
try:
|
|
|
|
|
@ -495,4 +893,4 @@ if __name__ == '__main__':
|
|
|
|
|
app = QApplication(sys.argv)
|
|
|
|
|
station = ControlStationUI()
|
|
|
|
|
station.show()
|
|
|
|
|
app.exec(app.exec())
|
|
|
|
|
app.exec()
|