|
|
|
@ -467,13 +467,14 @@ class DroneMonitor(Node):
|
|
|
|
self.serial_receivers = []
|
|
|
|
self.serial_receivers = []
|
|
|
|
|
|
|
|
|
|
|
|
# ================================================================================
|
|
|
|
# ================================================================================
|
|
|
|
# 【新增】初始化 CommandLongClient 字典(為每個 drone 維護獨立的 client)
|
|
|
|
# 【新增】初始化 CommandLongClient(持久化,不會每次調用都創建/銷毀)
|
|
|
|
# ================================================================================
|
|
|
|
# ================================================================================
|
|
|
|
# 改為為每個 drone 創建獨立的 client,避免多機並行時的競態條件
|
|
|
|
self.command_long_client = None
|
|
|
|
self.command_long_clients = {} # {drone_id: CommandLongClient}
|
|
|
|
try:
|
|
|
|
self.client_lock = Lock() # 保護 clients 字典的訪問
|
|
|
|
self.command_long_client = CommandLongClient()
|
|
|
|
self.client_counter = 0 # 用於生成唯一的 client 節點名稱
|
|
|
|
except Exception as e:
|
|
|
|
self.executor = None # 將在 gui.py 中設置,用於添加新的 clients
|
|
|
|
print(f"⚠️ 警告: 無法初始化 CommandLongClient: {e}")
|
|
|
|
|
|
|
|
self.command_long_client = None
|
|
|
|
# ================================================================================
|
|
|
|
# ================================================================================
|
|
|
|
|
|
|
|
|
|
|
|
# 主题检测定时器
|
|
|
|
# 主题检测定时器
|
|
|
|
@ -500,38 +501,6 @@ class DroneMonitor(Node):
|
|
|
|
|
|
|
|
|
|
|
|
return self.socket_id_mapping[original_socket_id]
|
|
|
|
return self.socket_id_mapping[original_socket_id]
|
|
|
|
|
|
|
|
|
|
|
|
def get_or_create_client(self, drone_id):
|
|
|
|
|
|
|
|
"""為每個 drone 獲取或創建獨立的 CommandLongClient,避免競態條件"""
|
|
|
|
|
|
|
|
with self.client_lock:
|
|
|
|
|
|
|
|
if drone_id not in self.command_long_clients:
|
|
|
|
|
|
|
|
try:
|
|
|
|
|
|
|
|
# 生成唯一的 client 節點名稱
|
|
|
|
|
|
|
|
self.client_counter += 1
|
|
|
|
|
|
|
|
unique_name = f"cmd_long_client_{drone_id}_{self.client_counter}"
|
|
|
|
|
|
|
|
client = CommandLongClient(node_name=unique_name)
|
|
|
|
|
|
|
|
self.command_long_clients[drone_id] = client
|
|
|
|
|
|
|
|
print(f" ✓ 為 {drone_id} 創建新的 CommandLongClient (node={unique_name})")
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
# 將新 client 添加到主執行器(這樣它的回調才能被處理)
|
|
|
|
|
|
|
|
if self.executor:
|
|
|
|
|
|
|
|
self.executor.add_node(client)
|
|
|
|
|
|
|
|
print(f" ✓ 將 {drone_id} 的 client 添加到主執行器")
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
except TypeError:
|
|
|
|
|
|
|
|
# 舊版 CommandLongClient 不支持 node_name 參數,使用預設
|
|
|
|
|
|
|
|
client = CommandLongClient()
|
|
|
|
|
|
|
|
self.command_long_clients[drone_id] = client
|
|
|
|
|
|
|
|
print(f" ✓ 為 {drone_id} 創建新的 CommandLongClient (使用預設名稱)")
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if self.executor:
|
|
|
|
|
|
|
|
self.executor.add_node(client)
|
|
|
|
|
|
|
|
print(f" ✓ 將 {drone_id} 的 client 添加到主執行器")
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
except Exception as e:
|
|
|
|
|
|
|
|
print(f"⚠️ 無法為 {drone_id} 創建 CommandLongClient: {e}")
|
|
|
|
|
|
|
|
return None
|
|
|
|
|
|
|
|
return self.command_long_clients[drone_id]
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
def scan_topics(self):
|
|
|
|
def scan_topics(self):
|
|
|
|
topics = self.get_topic_names_and_types()
|
|
|
|
topics = self.get_topic_names_and_types()
|
|
|
|
drone_pattern = re.compile(r'/fc_network/vehicle/(sys\d+)/(\w+)')
|
|
|
|
drone_pattern = re.compile(r'/fc_network/vehicle/(sys\d+)/(\w+)')
|
|
|
|
@ -633,7 +602,7 @@ class DroneMonitor(Node):
|
|
|
|
# ================================================================================
|
|
|
|
# ================================================================================
|
|
|
|
|
|
|
|
|
|
|
|
async def set_mode(self, drone_id, mode_name):
|
|
|
|
async def set_mode(self, drone_id, mode_name):
|
|
|
|
"""使用 CommandLongClient 切換無人機飛行模式(使用非阻塞的 async 方法)"""
|
|
|
|
"""使用 CommandLongClient 切換無人機飛行模式"""
|
|
|
|
try:
|
|
|
|
try:
|
|
|
|
# 解析 drone_id 提取 sysid
|
|
|
|
# 解析 drone_id 提取 sysid
|
|
|
|
parts = drone_id.split('_')
|
|
|
|
parts = drone_id.split('_')
|
|
|
|
@ -650,26 +619,30 @@ class DroneMonitor(Node):
|
|
|
|
|
|
|
|
|
|
|
|
print(f"\n📢 [SET_MODE] {drone_id} → {mode_name} (custom_mode={custom_mode})")
|
|
|
|
print(f"\n📢 [SET_MODE] {drone_id} → {mode_name} (custom_mode={custom_mode})")
|
|
|
|
|
|
|
|
|
|
|
|
# 獲取或創建該 drone 專用的 client(避免多機並行時的競態條件)
|
|
|
|
# 在線程池中調用 CommandLongClient
|
|
|
|
client = self.get_or_create_client(drone_id)
|
|
|
|
loop = asyncio.get_event_loop()
|
|
|
|
|
|
|
|
executor = ThreadPoolExecutor(max_workers=1)
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
def _call_set_mode():
|
|
|
|
|
|
|
|
client = CommandLongClient() if CommandLongClient else None
|
|
|
|
if not client:
|
|
|
|
if not client:
|
|
|
|
print(f"❌ [SET_MODE] CommandLongClient 無法初始化")
|
|
|
|
|
|
|
|
return False
|
|
|
|
return False
|
|
|
|
|
|
|
|
result = client.change_mode(
|
|
|
|
# 直接調用 async 方法,無需線程池(避免嵌套執行器衝突)
|
|
|
|
|
|
|
|
result = await client.change_mode_async(
|
|
|
|
|
|
|
|
target_sysid=sysid,
|
|
|
|
target_sysid=sysid,
|
|
|
|
custom_mode=float(custom_mode),
|
|
|
|
custom_mode=float(custom_mode),
|
|
|
|
target_compid=0,
|
|
|
|
target_compid=0,
|
|
|
|
base_mode=1.0,
|
|
|
|
base_mode=1.0,
|
|
|
|
timeout_sec=5.0, # 增加超時時間以提高多機操作的可靠性
|
|
|
|
timeout_sec=2.0,
|
|
|
|
)
|
|
|
|
)
|
|
|
|
|
|
|
|
client.destroy_node()
|
|
|
|
|
|
|
|
return result.success if result else False
|
|
|
|
|
|
|
|
|
|
|
|
if result and result.success:
|
|
|
|
result = await loop.run_in_executor(executor, _call_set_mode)
|
|
|
|
|
|
|
|
if result:
|
|
|
|
print(f"✅ [SET_MODE] 模式切換成功")
|
|
|
|
print(f"✅ [SET_MODE] 模式切換成功")
|
|
|
|
return True
|
|
|
|
return True
|
|
|
|
else:
|
|
|
|
else:
|
|
|
|
print(f"❌ [SET_MODE] 模式切換失敗 (message={result.message if result else 'None'})")
|
|
|
|
print(f"❌ [SET_MODE] 模式切換失敗")
|
|
|
|
return False
|
|
|
|
return False
|
|
|
|
except Exception as e:
|
|
|
|
except Exception as e:
|
|
|
|
print(f"❌ [SET_MODE] 例外錯誤: {e}")
|
|
|
|
print(f"❌ [SET_MODE] 例外錯誤: {e}")
|
|
|
|
@ -689,18 +662,16 @@ class DroneMonitor(Node):
|
|
|
|
action_name = "解鎖" if arm else "上鎖"
|
|
|
|
action_name = "解鎖" if arm else "上鎖"
|
|
|
|
print(f"\n📢 [ARM] {drone_id} → {action_name}")
|
|
|
|
print(f"\n📢 [ARM] {drone_id} → {action_name}")
|
|
|
|
|
|
|
|
|
|
|
|
# 獲取或創建該 drone 專用的 client(避免多機並行時的競態條件)
|
|
|
|
if not self.command_long_client:
|
|
|
|
client = self.get_or_create_client(drone_id)
|
|
|
|
print(f"❌ [ARM] CommandLongClient 未初始化")
|
|
|
|
if not client:
|
|
|
|
|
|
|
|
print(f"❌ [ARM] CommandLongClient 無法初始化")
|
|
|
|
|
|
|
|
return False
|
|
|
|
return False
|
|
|
|
|
|
|
|
|
|
|
|
# 直接調用 async 方法,無需線程池(避免嵌套執行器衝突)
|
|
|
|
# 直接調用 async 方法,無需線程池(避免嵌套執行器衝突)
|
|
|
|
result = await client.arm_disarm_async(
|
|
|
|
result = await self.command_long_client.arm_disarm_async(
|
|
|
|
target_sysid=sysid,
|
|
|
|
target_sysid=sysid,
|
|
|
|
arm=arm,
|
|
|
|
arm=arm,
|
|
|
|
target_compid=0,
|
|
|
|
target_compid=0,
|
|
|
|
timeout_sec=5.0, # 增加超時時間以提高多機操作的可靠性
|
|
|
|
timeout_sec=2.0,
|
|
|
|
)
|
|
|
|
)
|
|
|
|
|
|
|
|
|
|
|
|
if result and result.success:
|
|
|
|
if result and result.success:
|
|
|
|
@ -726,18 +697,16 @@ class DroneMonitor(Node):
|
|
|
|
|
|
|
|
|
|
|
|
print(f"\n📢 [TAKEOFF] {drone_id} → 起飛 (高度={altitude}m)")
|
|
|
|
print(f"\n📢 [TAKEOFF] {drone_id} → 起飛 (高度={altitude}m)")
|
|
|
|
|
|
|
|
|
|
|
|
# 獲取或創建該 drone 專用的 client(避免多機並行時的競態條件)
|
|
|
|
if not self.command_long_client:
|
|
|
|
client = self.get_or_create_client(drone_id)
|
|
|
|
print(f"❌ [TAKEOFF] CommandLongClient 未初始化")
|
|
|
|
if not client:
|
|
|
|
|
|
|
|
print(f"❌ [TAKEOFF] CommandLongClient 無法初始化")
|
|
|
|
|
|
|
|
return False
|
|
|
|
return False
|
|
|
|
|
|
|
|
|
|
|
|
# 直接調用 async 方法,無需線程池(避免嵌套執行器衝突)
|
|
|
|
# 直接調用 async 方法,無需線程池(避免嵌套執行器衝突)
|
|
|
|
result = await client.takeoff_async(
|
|
|
|
result = await self.command_long_client.takeoff_async(
|
|
|
|
target_sysid=sysid,
|
|
|
|
target_sysid=sysid,
|
|
|
|
altitude_m=float(altitude),
|
|
|
|
altitude_m=float(altitude),
|
|
|
|
target_compid=0,
|
|
|
|
target_compid=0,
|
|
|
|
timeout_sec=5.0, # 增加超時時間以提高多機操作的可靠性
|
|
|
|
timeout_sec=2.0,
|
|
|
|
)
|
|
|
|
)
|
|
|
|
|
|
|
|
|
|
|
|
if result and result.success:
|
|
|
|
if result and result.success:
|
|
|
|
|