mirror of
https://github.com/dptech-corp/Uni-Lab-OS.git
synced 2025-12-17 13:01:12 +00:00
Fix/resource UUID and doc fix (#109)
* Fix ResourceTreeSet load error * Raise error when using unsupported type to create ResourceTreeSet * Fix children key error * Fix children key error * Fix workstation resource not tracking * Fix workstation deck & children resource dupe * Fix workstation deck & children resource dupe * Fix multiple resource error * Fix resource tree update * Fix resource tree update * Force confirm uuid * Tip more error log * Refactor Bioyond workstation and experiment workflow (#105) Refactored the Bioyond workstation classes to improve parameter handling and workflow management. Updated experiment.py to use BioyondReactionStation with deck and material mappings, and enhanced workflow step parameter mapping and execution logic. Adjusted JSON experiment configs, improved workflow sequence handling, and added UUID assignment to PLR materials. Removed unused station_config and material cache logic, and added detailed docstrings and debug output for workflow methods. * Fix resource get. Fix resource parent not found. Mapping uuid for all resources. * mount parent uuid * Add logging configuration based on BasicConfig in main function * fix workstation node error * fix workstation node error * Update boot example * temp fix for resource get * temp fix for resource get * provide error info when cant find plr type * pack repo info * fix to plr type error * fix to plr type error * Update regular container method * support no size init * fix comprehensive_station.json * fix comprehensive_station.json * fix type conversion * fix state loading for regular container * Update deploy-docs.yml * Update deploy-docs.yml --------- Co-authored-by: ZiWei <131428629+ZiWei09@users.noreply.github.com>
This commit is contained in:
@@ -26,6 +26,7 @@ def initialize_device_from_dict(device_id, device_config) -> Optional[ROS2Device
|
||||
d = None
|
||||
original_device_config = copy.deepcopy(device_config)
|
||||
device_class_config = device_config["class"]
|
||||
uid = device_config["uuid"]
|
||||
if isinstance(device_class_config, str): # 如果是字符串,则直接去lab_registry中查找,获取class
|
||||
if len(device_class_config) == 0:
|
||||
raise DeviceClassInvalid(f"Device [{device_id}] class cannot be an empty string. {device_config}")
|
||||
@@ -50,7 +51,7 @@ def initialize_device_from_dict(device_id, device_config) -> Optional[ROS2Device
|
||||
)
|
||||
try:
|
||||
d = DEVICE(
|
||||
device_id=device_id, driver_is_ros=device_class_config["type"] == "ros2", driver_params=device_config.get("config", {})
|
||||
device_id=device_id, device_uuid=uid, driver_is_ros=device_class_config["type"] == "ros2", driver_params=device_config.get("config", {})
|
||||
)
|
||||
except DeviceInitError as ex:
|
||||
return d
|
||||
|
||||
@@ -6,7 +6,7 @@ import threading
|
||||
import time
|
||||
import traceback
|
||||
import uuid
|
||||
from typing import get_type_hints, TypeVar, Generic, Dict, Any, Type, TypedDict, Optional, List, TYPE_CHECKING
|
||||
from typing import get_type_hints, TypeVar, Generic, Dict, Any, Type, TypedDict, Optional, List, TYPE_CHECKING, Union
|
||||
|
||||
from concurrent.futures import ThreadPoolExecutor
|
||||
import asyncio
|
||||
@@ -132,6 +132,7 @@ class ROSLoggerAdapter:
|
||||
def init_wrapper(
|
||||
self,
|
||||
device_id: str,
|
||||
device_uuid: str,
|
||||
driver_class: type[T],
|
||||
device_config: Dict[str, Any],
|
||||
status_types: Dict[str, Any],
|
||||
@@ -150,6 +151,7 @@ def init_wrapper(
|
||||
if children is None:
|
||||
children = []
|
||||
kwargs["device_id"] = device_id
|
||||
kwargs["device_uuid"] = device_uuid
|
||||
kwargs["driver_class"] = driver_class
|
||||
kwargs["device_config"] = device_config
|
||||
kwargs["driver_params"] = driver_params
|
||||
@@ -266,6 +268,7 @@ class BaseROS2DeviceNode(Node, Generic[T]):
|
||||
self,
|
||||
driver_instance: T,
|
||||
device_id: str,
|
||||
device_uuid: str,
|
||||
status_types: Dict[str, Any],
|
||||
action_value_mappings: Dict[str, Any],
|
||||
hardware_interface: Dict[str, Any],
|
||||
@@ -278,6 +281,7 @@ class BaseROS2DeviceNode(Node, Generic[T]):
|
||||
Args:
|
||||
driver_instance: 设备实例
|
||||
device_id: 设备标识符
|
||||
device_uuid: 设备标识符
|
||||
status_types: 需要发布的状态和传感器信息
|
||||
action_value_mappings: 设备动作
|
||||
hardware_interface: 硬件接口配置
|
||||
@@ -285,7 +289,7 @@ class BaseROS2DeviceNode(Node, Generic[T]):
|
||||
"""
|
||||
self.driver_instance = driver_instance
|
||||
self.device_id = device_id
|
||||
self.uuid = str(uuid.uuid4())
|
||||
self.uuid = device_uuid
|
||||
self.publish_high_frequency = False
|
||||
self.callback_group = ReentrantCallbackGroup()
|
||||
self.resource_tracker = resource_tracker
|
||||
@@ -554,6 +558,11 @@ class BaseROS2DeviceNode(Node, Generic[T]):
|
||||
async def update_resource(self, resources: List["ResourcePLR"]):
|
||||
r = SerialCommand.Request()
|
||||
tree_set = ResourceTreeSet.from_plr_resources(resources)
|
||||
for tree in tree_set.trees:
|
||||
root_node = tree.root_node
|
||||
if not root_node.res_content.uuid_parent:
|
||||
logger.warning(f"更新无父节点物料{root_node},自动以当前设备作为根节点")
|
||||
root_node.res_content.parent_uuid = self.uuid
|
||||
r.command = json.dumps({"data": {"data": tree_set.dump()}, "action": "update"})
|
||||
response: SerialCommand_Response = await self._resource_clients["c2s_update_resource_tree"].call_async(r) # type: ignore
|
||||
try:
|
||||
@@ -648,15 +657,27 @@ class BaseROS2DeviceNode(Node, Generic[T]):
|
||||
results.append({"success": True, "action": "update"})
|
||||
elif action == "remove":
|
||||
# 移除资源
|
||||
plr_resources: List[ResourcePLR] = [
|
||||
self.resource_tracker.uuid_to_resources[i] for i in resources_uuid
|
||||
]
|
||||
found_resources: List[List[Union[ResourcePLR, dict]]] = self.resource_tracker.figure_resource(
|
||||
[{"uuid": uid} for uid in resources_uuid], try_mode=True
|
||||
)
|
||||
found_plr_resources = []
|
||||
other_plr_resources = []
|
||||
for res_list in found_resources:
|
||||
for res in res_list:
|
||||
if issubclass(res.__class__, ResourcePLR):
|
||||
found_plr_resources.append(res)
|
||||
else:
|
||||
other_plr_resources.append(res)
|
||||
func = getattr(self.driver_instance, "resource_tree_remove", None)
|
||||
if callable(func):
|
||||
func(plr_resources)
|
||||
for plr_resource in plr_resources:
|
||||
func(found_plr_resources)
|
||||
for plr_resource in found_plr_resources:
|
||||
plr_resource.parent.unassign_child_resource(plr_resource)
|
||||
self.resource_tracker.remove_resource(plr_resource)
|
||||
self.lab_logger().info(f"移除物料 {plr_resource} 及其子节点")
|
||||
for res in other_plr_resources:
|
||||
self.resource_tracker.remove_resource(res)
|
||||
self.lab_logger().info(f"移除物料 {res} 及其子节点")
|
||||
results.append({"success": True, "action": "remove"})
|
||||
except Exception as e:
|
||||
error_msg = f"Error processing {action} operation: {str(e)}"
|
||||
@@ -936,7 +957,10 @@ class BaseROS2DeviceNode(Node, Generic[T]):
|
||||
|
||||
# 通过资源跟踪器获取本地实例
|
||||
final_resources = queried_resources if is_sequence else queried_resources[0]
|
||||
action_kwargs[k] = self.resource_tracker.figure_resource(final_resources, try_mode=False)
|
||||
final_resources = self.resource_tracker.figure_resource({"name": final_resources.name}, try_mode=False) if not is_sequence else [
|
||||
self.resource_tracker.figure_resource({"name": res.name}, try_mode=False) for res in queried_resources
|
||||
]
|
||||
action_kwargs[k] = final_resources
|
||||
|
||||
except Exception as e:
|
||||
self.lab_logger().error(f"{action_name} 物料实例获取失败: {e}\n{traceback.format_exc()}")
|
||||
@@ -1347,6 +1371,7 @@ class ROS2DeviceNode:
|
||||
def __init__(
|
||||
self,
|
||||
device_id: str,
|
||||
device_uuid: str,
|
||||
driver_class: Type[T],
|
||||
device_config: Dict[str, Any],
|
||||
driver_params: Dict[str, Any],
|
||||
@@ -1362,6 +1387,7 @@ class ROS2DeviceNode:
|
||||
|
||||
Args:
|
||||
device_id: 设备标识符
|
||||
device_uuid: 设备uuid
|
||||
driver_class: 设备类
|
||||
device_config: 原始初始化的json
|
||||
driver_params: driver初始化的参数
|
||||
@@ -1436,6 +1462,7 @@ class ROS2DeviceNode:
|
||||
children=children,
|
||||
driver_instance=self._driver_instance, # type: ignore
|
||||
device_id=device_id,
|
||||
device_uuid=device_uuid,
|
||||
status_types=status_types,
|
||||
action_value_mappings=action_value_mappings,
|
||||
hardware_interface=hardware_interface,
|
||||
@@ -1446,6 +1473,7 @@ class ROS2DeviceNode:
|
||||
self._ros_node = BaseROS2DeviceNode(
|
||||
driver_instance=self._driver_instance,
|
||||
device_id=device_id,
|
||||
device_uuid=device_uuid,
|
||||
status_types=status_types,
|
||||
action_value_mappings=action_value_mappings,
|
||||
hardware_interface=hardware_interface,
|
||||
|
||||
@@ -18,7 +18,7 @@ from unilabos_msgs.srv import (
|
||||
ResourceDelete,
|
||||
ResourceUpdate,
|
||||
ResourceList,
|
||||
SerialCommand,
|
||||
SerialCommand, ResourceGet,
|
||||
) # type: ignore
|
||||
from unilabos_msgs.srv._serial_command import SerialCommand_Request, SerialCommand_Response
|
||||
from unique_identifier_msgs.msg import UUID
|
||||
@@ -41,6 +41,7 @@ from unilabos.ros.nodes.resource_tracker import (
|
||||
ResourceTreeSet,
|
||||
ResourceTreeInstance,
|
||||
)
|
||||
from unilabos.utils import logger
|
||||
from unilabos.utils.exception import DeviceClassInvalid
|
||||
from unilabos.utils.type_check import serialize_result_info
|
||||
from unilabos.registry.placeholder_type import ResourceSlot, DeviceSlot
|
||||
@@ -99,17 +100,6 @@ class HostNode(BaseROS2DeviceNode):
|
||||
"""
|
||||
if self._instance is not None:
|
||||
self._instance.lab_logger().critical("[Host Node] HostNode instance already exists.")
|
||||
# 初始化Node基类,传递空参数覆盖列表
|
||||
BaseROS2DeviceNode.__init__(
|
||||
self,
|
||||
driver_instance=self,
|
||||
device_id=device_id,
|
||||
status_types={},
|
||||
action_value_mappings=lab_registry.device_type_registry["host_node"]["class"]["action_value_mappings"],
|
||||
hardware_interface={},
|
||||
print_publish=False,
|
||||
resource_tracker=self._resource_tracker, # host node并不是通过initialize 包一层传进来的
|
||||
)
|
||||
|
||||
# 设置单例实例
|
||||
self.__class__._instance = self
|
||||
@@ -127,6 +117,91 @@ class HostNode(BaseROS2DeviceNode):
|
||||
bridges = []
|
||||
self.bridges = bridges
|
||||
|
||||
# 创建 host_node 作为一个单独的 ResourceTree
|
||||
host_node_dict = {
|
||||
"id": "host_node",
|
||||
"uuid": str(uuid.uuid4()),
|
||||
"parent_uuid": "",
|
||||
"name": "host_node",
|
||||
"type": "device",
|
||||
"class": "host_node",
|
||||
"config": {},
|
||||
"data": {},
|
||||
"children": [],
|
||||
"description": "",
|
||||
"schema": {},
|
||||
"model": {},
|
||||
"icon": "",
|
||||
}
|
||||
|
||||
# 创建 host_node 的 ResourceTree
|
||||
host_node_instance = ResourceDictInstance.get_resource_instance_from_dict(host_node_dict)
|
||||
host_node_tree = ResourceTreeInstance(host_node_instance)
|
||||
resources_config.trees.insert(0, host_node_tree)
|
||||
try:
|
||||
for bridge in self.bridges:
|
||||
if hasattr(bridge, "resource_tree_add") and resources_config:
|
||||
from unilabos.app.web.client import HTTPClient
|
||||
|
||||
client: HTTPClient = bridge
|
||||
resource_start_time = time.time()
|
||||
# 传递 ResourceTreeSet 对象,在 client 中转换为字典并获取 UUID 映射
|
||||
uuid_mapping = client.resource_tree_add(resources_config, "", True)
|
||||
device_uuid = resources_config.root_nodes[0].res_content.uuid
|
||||
resource_end_time = time.time()
|
||||
logger.info(
|
||||
f"[Host Node-Resource] 物料上传 {round(resource_end_time - resource_start_time, 5) * 1000} ms"
|
||||
)
|
||||
for edge in self.resources_edge_config:
|
||||
edge["source_uuid"] = uuid_mapping.get(edge["source_uuid"], edge["source_uuid"])
|
||||
edge["target_uuid"] = uuid_mapping.get(edge["target_uuid"], edge["target_uuid"])
|
||||
resource_add_res = client.resource_edge_add(self.resources_edge_config)
|
||||
resource_edge_end_time = time.time()
|
||||
logger.info(
|
||||
f"[Host Node-Resource] 物料关系上传 {round(resource_edge_end_time - resource_end_time, 5) * 1000} ms"
|
||||
)
|
||||
# resources_config 通过各个设备的 resource_tracker 进行uuid更新,利用uuid_mapping
|
||||
# resources_config 的 root node 是
|
||||
# # 创建反向映射:new_uuid -> old_uuid
|
||||
# reverse_uuid_mapping = {new_uuid: old_uuid for old_uuid, new_uuid in uuid_mapping.items()}
|
||||
# for tree in resources_config.trees:
|
||||
# node = tree.root_node
|
||||
# if node.res_content.type == "device":
|
||||
# if node.res_content.id == "host_node":
|
||||
# continue
|
||||
# # slave节点走c2s更新接口,拿到add自行update uuid
|
||||
# device_tracker = self.devices_instances[node.res_content.id].resource_tracker
|
||||
# old_uuid = reverse_uuid_mapping.get(node.res_content.uuid)
|
||||
# if old_uuid:
|
||||
# # 找到旧UUID,使用UUID查找
|
||||
# resource_instance = device_tracker.uuid_to_resources.get(old_uuid)
|
||||
# else:
|
||||
# # 未找到旧UUID,使用name查找
|
||||
# resource_instance = device_tracker.figure_resource(
|
||||
# {"name": node.res_content.name}
|
||||
# )
|
||||
# device_tracker.loop_update_uuid(resource_instance, uuid_mapping)
|
||||
# else:
|
||||
# try:
|
||||
# for plr_resource in ResourceTreeSet([tree]).to_plr_resources():
|
||||
# self.resource_tracker.add_resource(plr_resource)
|
||||
# except Exception as ex:
|
||||
# self.lab_logger().warning("[Host Node-Resource] 根节点物料序列化失败!")
|
||||
except Exception as ex:
|
||||
logger.error(f"[Host Node-Resource] 添加物料出错!\n{traceback.format_exc()}")
|
||||
# 初始化Node基类,传递空参数覆盖列表
|
||||
BaseROS2DeviceNode.__init__(
|
||||
self,
|
||||
driver_instance=self,
|
||||
device_id=device_id,
|
||||
device_uuid=host_node_dict["uuid"],
|
||||
status_types={},
|
||||
action_value_mappings=lab_registry.device_type_registry["host_node"]["class"]["action_value_mappings"],
|
||||
hardware_interface={},
|
||||
print_publish=False,
|
||||
resource_tracker=self._resource_tracker, # host node并不是通过initialize 包一层传进来的
|
||||
)
|
||||
|
||||
# 创建设备、动作客户端和目标存储
|
||||
self.devices_names: Dict[str, str] = {device_id: self.namespace} # 存储设备名称和命名空间的映射
|
||||
self.devices_instances: Dict[str, ROS2DeviceNode] = {} # 存储设备实例
|
||||
@@ -207,81 +282,7 @@ class HostNode(BaseROS2DeviceNode):
|
||||
].items():
|
||||
controller_config["update_rate"] = update_rate
|
||||
self.initialize_controller(controller_id, controller_config)
|
||||
# 创建 host_node 作为一个单独的 ResourceTree
|
||||
|
||||
host_node_dict = {
|
||||
"id": "host_node",
|
||||
"uuid": str(uuid.uuid4()),
|
||||
"parent_uuid": "",
|
||||
"name": "host_node",
|
||||
"type": "device",
|
||||
"class": "host_node",
|
||||
"config": {},
|
||||
"data": {},
|
||||
"children": [],
|
||||
"description": "",
|
||||
"schema": {},
|
||||
"model": {},
|
||||
"icon": "",
|
||||
}
|
||||
|
||||
# 创建 host_node 的 ResourceTree
|
||||
host_node_instance = ResourceDictInstance.get_resource_instance_from_dict(host_node_dict)
|
||||
host_node_tree = ResourceTreeInstance(host_node_instance)
|
||||
resources_config.trees.insert(0, host_node_tree)
|
||||
try:
|
||||
for bridge in self.bridges:
|
||||
if hasattr(bridge, "resource_tree_add") and resources_config:
|
||||
from unilabos.app.web.client import HTTPClient
|
||||
|
||||
client: HTTPClient = bridge
|
||||
resource_start_time = time.time()
|
||||
# 传递 ResourceTreeSet 对象,在 client 中转换为字典并获取 UUID 映射
|
||||
uuid_mapping = client.resource_tree_add(resources_config, "", True)
|
||||
resource_end_time = time.time()
|
||||
self.lab_logger().info(
|
||||
f"[Host Node-Resource] 物料上传 {round(resource_end_time - resource_start_time, 5) * 1000} ms"
|
||||
)
|
||||
for edge in self.resources_edge_config:
|
||||
edge["source_uuid"] = uuid_mapping.get(edge["source_uuid"], edge["source_uuid"])
|
||||
edge["target_uuid"] = uuid_mapping.get(edge["target_uuid"], edge["target_uuid"])
|
||||
resource_add_res = client.resource_edge_add(self.resources_edge_config)
|
||||
resource_edge_end_time = time.time()
|
||||
self.lab_logger().info(
|
||||
f"[Host Node-Resource] 物料关系上传 {round(resource_edge_end_time - resource_end_time, 5) * 1000} ms"
|
||||
)
|
||||
# resources_config 通过各个设备的 resource_tracker 进行uuid更新,利用uuid_mapping
|
||||
# resources_config 的 root node 是
|
||||
# 创建反向映射:new_uuid -> old_uuid
|
||||
reverse_uuid_mapping = {new_uuid: old_uuid for old_uuid, new_uuid in uuid_mapping.items()}
|
||||
for tree in resources_config.trees:
|
||||
node = tree.root_node
|
||||
if node.res_content.type == "device":
|
||||
for sub_node in node.children:
|
||||
# 只有二级子设备
|
||||
if sub_node.res_content.type != "device":
|
||||
# slave节点走c2s更新接口,拿到add自行update uuid
|
||||
device_tracker = self.devices_instances[node.res_content.id].resource_tracker
|
||||
# sub_node.res_content.uuid 已经是新UUID,需要用旧UUID去查找
|
||||
old_uuid = reverse_uuid_mapping.get(sub_node.res_content.uuid)
|
||||
if old_uuid:
|
||||
# 找到旧UUID,使用UUID查找
|
||||
resource_instance = device_tracker.figure_resource({"uuid": old_uuid})
|
||||
else:
|
||||
# 未找到旧UUID,使用name查找
|
||||
resource_instance = device_tracker.figure_resource(
|
||||
{"name": sub_node.res_content.name}
|
||||
)
|
||||
device_tracker.loop_update_uuid(resource_instance, uuid_mapping)
|
||||
else:
|
||||
try:
|
||||
for plr_resource in ResourceTreeSet([tree]).to_plr_resources():
|
||||
self.resource_tracker.add_resource(plr_resource)
|
||||
except Exception as ex:
|
||||
self.lab_logger().warning("[Host Node-Resource] 根节点物料序列化失败!")
|
||||
except Exception as ex:
|
||||
self.lab_logger().error("[Host Node-Resource] 添加物料出错!")
|
||||
self.lab_logger().error(traceback.format_exc())
|
||||
# 创建定时器,定期发现设备
|
||||
self._discovery_timer = self.create_timer(
|
||||
discovery_interval, self._discovery_devices_callback, callback_group=ReentrantCallbackGroup()
|
||||
@@ -862,7 +863,7 @@ class HostNode(BaseROS2DeviceNode):
|
||||
),
|
||||
}
|
||||
|
||||
def _resource_tree_action_add_callback(self, data: dict, response: SerialCommand_Response): # OK
|
||||
async def _resource_tree_action_add_callback(self, data: dict, response: SerialCommand_Response): # OK
|
||||
resource_tree_set = ResourceTreeSet.load(data["data"])
|
||||
mount_uuid = data["mount_uuid"]
|
||||
first_add = data["first_add"]
|
||||
@@ -903,7 +904,7 @@ class HostNode(BaseROS2DeviceNode):
|
||||
response.response = json.dumps(uuid_mapping) if success else "FAILED"
|
||||
self.lab_logger().info(f"[Host Node-Resource] Resource tree add completed, success: {success}")
|
||||
|
||||
def _resource_tree_action_get_callback(self, data: dict, response: SerialCommand_Response): # OK
|
||||
async def _resource_tree_action_get_callback(self, data: dict, response: SerialCommand_Response): # OK
|
||||
uuid_list: List[str] = data["data"]
|
||||
with_children: bool = data["with_children"]
|
||||
from unilabos.app.web.client import http_client
|
||||
@@ -911,7 +912,7 @@ class HostNode(BaseROS2DeviceNode):
|
||||
resource_response = http_client.resource_tree_get(uuid_list, with_children)
|
||||
response.response = json.dumps(resource_response)
|
||||
|
||||
def _resource_tree_action_remove_callback(self, data: dict, response: SerialCommand_Response):
|
||||
async def _resource_tree_action_remove_callback(self, data: dict, response: SerialCommand_Response):
|
||||
"""
|
||||
子节点通知Host物料树删除
|
||||
"""
|
||||
@@ -919,7 +920,7 @@ class HostNode(BaseROS2DeviceNode):
|
||||
response.response = "OK"
|
||||
self.lab_logger().info(f"[Host Node-Resource] Resource tree remove completed")
|
||||
|
||||
def _resource_tree_action_update_callback(self, data: dict, response: SerialCommand_Response):
|
||||
async def _resource_tree_action_update_callback(self, data: dict, response: SerialCommand_Response):
|
||||
"""
|
||||
子节点通知Host物料树更新
|
||||
"""
|
||||
@@ -932,20 +933,29 @@ class HostNode(BaseROS2DeviceNode):
|
||||
|
||||
from unilabos.app.web.client import http_client
|
||||
|
||||
resource_start_time = time.time()
|
||||
uuid_mapping = http_client.resource_tree_update(resource_tree_set, "", False)
|
||||
success = bool(uuid_mapping)
|
||||
resource_end_time = time.time()
|
||||
self.lab_logger().info(
|
||||
f"[Host Node-Resource] 物料更新上传 {round(resource_end_time - resource_start_time, 5) * 1000} ms"
|
||||
)
|
||||
if uuid_mapping:
|
||||
self.lab_logger().info(f"[Host Node-Resource] UUID映射: {len(uuid_mapping)} 个节点")
|
||||
# 还需要加入到资源图中,暂不实现,考虑资源图新的获取方式
|
||||
response.response = json.dumps(uuid_mapping)
|
||||
self.lab_logger().info(f"[Host Node-Resource] Resource tree add completed, success: {success}")
|
||||
uuid_to_trees: Dict[str, List[ResourceTreeInstance]] = collections.defaultdict(list)
|
||||
for tree in resource_tree_set.trees:
|
||||
uuid_to_trees[tree.root_node.res_content.parent_uuid].append(tree)
|
||||
|
||||
def _resource_tree_update_callback(self, request: SerialCommand_Request, response: SerialCommand_Response):
|
||||
for uid, trees in uuid_to_trees.items():
|
||||
new_tree_set = ResourceTreeSet(trees)
|
||||
resource_start_time = time.time()
|
||||
self.lab_logger().info(
|
||||
f"[Host Node-Resource] 物料 {[root_node.res_content.id for root_node in new_tree_set.root_nodes]} {uid} 挂载 {trees[0].root_node.res_content.parent_uuid} 请求更新上传"
|
||||
)
|
||||
uuid_mapping = http_client.resource_tree_add(new_tree_set, uid, False)
|
||||
success = bool(uuid_mapping)
|
||||
resource_end_time = time.time()
|
||||
self.lab_logger().info(
|
||||
f"[Host Node-Resource] 物料更新上传 {round(resource_end_time - resource_start_time, 5) * 1000} ms"
|
||||
)
|
||||
if uuid_mapping:
|
||||
self.lab_logger().info(f"[Host Node-Resource] UUID映射: {len(uuid_mapping)} 个节点")
|
||||
# 还需要加入到资源图中,暂不实现,考虑资源图新的获取方式
|
||||
response.response = json.dumps(uuid_mapping)
|
||||
self.lab_logger().info(f"[Host Node-Resource] Resource tree add completed, success: {success}")
|
||||
|
||||
async def _resource_tree_update_callback(self, request: SerialCommand_Request, response: SerialCommand_Response):
|
||||
"""
|
||||
子节点通知Host物料树更新
|
||||
|
||||
@@ -958,13 +968,13 @@ class HostNode(BaseROS2DeviceNode):
|
||||
action = data["action"]
|
||||
data = data["data"]
|
||||
if action == "add":
|
||||
self._resource_tree_action_add_callback(data, response)
|
||||
await self._resource_tree_action_add_callback(data, response)
|
||||
elif action == "get":
|
||||
self._resource_tree_action_get_callback(data, response)
|
||||
await self._resource_tree_action_get_callback(data, response)
|
||||
elif action == "update":
|
||||
self._resource_tree_action_update_callback(data, response)
|
||||
await self._resource_tree_action_update_callback(data, response)
|
||||
elif action == "remove":
|
||||
self._resource_tree_action_remove_callback(data, response)
|
||||
await self._resource_tree_action_remove_callback(data, response)
|
||||
else:
|
||||
self.lab_logger().error(f"[Host Node-Resource] Invalid action: {action}")
|
||||
response.response = "ERROR"
|
||||
|
||||
@@ -6,13 +6,14 @@ from typing import List, Dict, Any, Optional, TYPE_CHECKING
|
||||
|
||||
import rclpy
|
||||
from rosidl_runtime_py import message_to_ordereddict
|
||||
from unilabos_msgs.msg import Resource
|
||||
from unilabos_msgs.srv import ResourceUpdate
|
||||
|
||||
from unilabos.messages import * # type: ignore # protocol names
|
||||
from rclpy.action import ActionServer, ActionClient
|
||||
from rclpy.action.server import ServerGoalHandle
|
||||
from rclpy.callback_groups import ReentrantCallbackGroup
|
||||
from unilabos_msgs.msg import Resource # type: ignore
|
||||
from unilabos_msgs.srv import ResourceGet, ResourceUpdate # type: ignore
|
||||
from unilabos_msgs.srv._serial_command import SerialCommand_Request, SerialCommand_Response
|
||||
|
||||
from unilabos.compile import action_protocol_generators
|
||||
from unilabos.resources.graphio import list_to_nested_dict, nested_dict_to_list
|
||||
@@ -20,11 +21,11 @@ from unilabos.ros.initialize_device import initialize_device_from_dict
|
||||
from unilabos.ros.msgs.message_converter import (
|
||||
get_action_type,
|
||||
convert_to_ros_msg,
|
||||
convert_from_ros_msg,
|
||||
convert_from_ros_msg_with_mapping,
|
||||
)
|
||||
from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode, DeviceNodeResourceTracker, ROS2DeviceNode
|
||||
from unilabos.utils.type_check import serialize_result_info, get_result_info_str
|
||||
from unilabos.ros.nodes.resource_tracker import ResourceTreeSet
|
||||
from unilabos.utils.type_check import get_result_info_str
|
||||
|
||||
if TYPE_CHECKING:
|
||||
from unilabos.devices.workstation.workstation_base import WorkstationBase
|
||||
@@ -50,6 +51,7 @@ class ROS2WorkstationNode(BaseROS2DeviceNode):
|
||||
*,
|
||||
driver_instance: "WorkstationBase",
|
||||
device_id: str,
|
||||
device_uuid: str,
|
||||
status_types: Dict[str, Any],
|
||||
action_value_mappings: Dict[str, Any],
|
||||
hardware_interface: Dict[str, Any],
|
||||
@@ -64,6 +66,7 @@ class ROS2WorkstationNode(BaseROS2DeviceNode):
|
||||
super().__init__(
|
||||
driver_instance=driver_instance,
|
||||
device_id=device_id,
|
||||
device_uuid=device_uuid,
|
||||
status_types=status_types,
|
||||
action_value_mappings={**action_value_mappings, **self.protocol_action_mappings},
|
||||
hardware_interface=hardware_interface,
|
||||
@@ -222,16 +225,28 @@ class ROS2WorkstationNode(BaseROS2DeviceNode):
|
||||
# 向Host查询物料当前状态
|
||||
for k, v in goal.get_fields_and_field_types().items():
|
||||
if v in ["unilabos_msgs/Resource", "sequence<unilabos_msgs/Resource>"]:
|
||||
r = ResourceGet.Request()
|
||||
resource_id = (
|
||||
protocol_kwargs[k]["id"] if v == "unilabos_msgs/Resource" else protocol_kwargs[k][0]["id"]
|
||||
)
|
||||
r.id = resource_id
|
||||
r.with_children = True
|
||||
response = await self._resource_clients["resource_get"].call_async(r)
|
||||
protocol_kwargs[k] = list_to_nested_dict(
|
||||
[convert_from_ros_msg(rs) for rs in response.resources]
|
||||
)
|
||||
self.lab_logger().info(f"{protocol_name} 查询资源状态: Key: {k} Type: {v}")
|
||||
|
||||
try:
|
||||
# 统一处理单个或多个资源
|
||||
resource_id = (
|
||||
protocol_kwargs[k]["id"] if v == "unilabos_msgs/Resource" else protocol_kwargs[k][0]["id"]
|
||||
)
|
||||
r = SerialCommand_Request()
|
||||
r.command = json.dumps({"id": resource_id, "with_children": True})
|
||||
# 发送请求并等待响应
|
||||
response: SerialCommand_Response = await self._resource_clients[
|
||||
"resource_get"
|
||||
].call_async(
|
||||
r
|
||||
) # type: ignore
|
||||
raw_data = json.loads(response.response)
|
||||
tree_set = ResourceTreeSet.from_raw_list(raw_data)
|
||||
target = tree_set.dump()
|
||||
protocol_kwargs[k] = target[0][0] if v == "unilabos_msgs/Resource" else target
|
||||
except Exception as ex:
|
||||
self.lab_logger().error(f"查询资源失败: {k}, 错误: {ex}\n{traceback.format_exc()}")
|
||||
raise
|
||||
|
||||
self.lab_logger().info(f"🔍 最终的 vessel: {protocol_kwargs.get('vessel', 'NOT_FOUND')}")
|
||||
|
||||
|
||||
@@ -1,3 +1,4 @@
|
||||
import traceback
|
||||
import uuid
|
||||
from pydantic import BaseModel, field_serializer, field_validator
|
||||
from pydantic import Field
|
||||
@@ -140,7 +141,7 @@ class ResourceDictInstance(object):
|
||||
def get_nested_dict(self) -> Dict[str, Any]:
|
||||
"""获取资源实例的嵌套字典表示"""
|
||||
res_dict = self.res_content.model_dump(by_alias=True)
|
||||
res_dict["children"] = {child.res_content.name: child.get_nested_dict() for child in self.children}
|
||||
res_dict["children"] = {child.res_content.id: child.get_nested_dict() for child in self.children}
|
||||
res_dict["parent"] = self.res_content.parent_instance_name
|
||||
res_dict["position"] = self.res_content.position.position.model_dump()
|
||||
return res_dict
|
||||
@@ -213,7 +214,7 @@ class ResourceTreeInstance(object):
|
||||
if node.res_content.uuid:
|
||||
known_uuids.add(node.res_content.uuid)
|
||||
else:
|
||||
print(f"警告: 资源 {node.res_content.id} 没有uuid")
|
||||
logger.warning(f"警告: 资源 {node.res_content.id} 没有uuid")
|
||||
|
||||
# 验证并递归处理子节点
|
||||
for child in node.children:
|
||||
@@ -289,8 +290,6 @@ class ResourceTreeSet(object):
|
||||
elif isinstance(resource_list[0], ResourceTreeInstance):
|
||||
# 已经是ResourceTree列表
|
||||
self.trees = cast(List[ResourceTreeInstance], resource_list)
|
||||
elif isinstance(resource_list[0], list):
|
||||
pass
|
||||
else:
|
||||
raise TypeError(
|
||||
f"不支持的类型: {type(resource_list[0])}。"
|
||||
@@ -307,10 +306,7 @@ class ResourceTreeSet(object):
|
||||
replace_info = {
|
||||
"plate": "plate",
|
||||
"well": "well",
|
||||
"tip_spot": "container",
|
||||
"trash": "container",
|
||||
"deck": "deck",
|
||||
"tip_rack": "container",
|
||||
}
|
||||
if source in replace_info:
|
||||
return replace_info[source]
|
||||
@@ -320,7 +316,12 @@ class ResourceTreeSet(object):
|
||||
|
||||
def build_uuid_mapping(res: "PLRResource", uuid_list: list):
|
||||
"""递归构建uuid映射字典"""
|
||||
uuid_list.append(getattr(res, "unilabos_uuid", ""))
|
||||
uid = getattr(res, "unilabos_uuid", "")
|
||||
if not uid:
|
||||
uid = str(uuid.uuid4())
|
||||
res.unilabos_uuid = uid
|
||||
logger.warning(f"{res}没有uuid,请设置后再传入,默认填充{uid}!\n{traceback.format_exc()}")
|
||||
uuid_list.append(uid)
|
||||
for child in res.children:
|
||||
build_uuid_mapping(child, uuid_list)
|
||||
|
||||
@@ -384,7 +385,7 @@ class ResourceTreeSet(object):
|
||||
import inspect
|
||||
|
||||
# 类型映射
|
||||
TYPE_MAP = {"plate": "plate", "well": "well", "container": "tip_spot", "deck": "deck", "tip_rack": "tip_rack"}
|
||||
TYPE_MAP = {"plate": "Plate", "well": "Well", "deck": "Deck"}
|
||||
|
||||
def collect_node_data(node: ResourceDictInstance, name_to_uuid: dict, all_states: dict):
|
||||
"""一次遍历收集 name_to_uuid 和 all_states"""
|
||||
@@ -396,13 +397,13 @@ class ResourceTreeSet(object):
|
||||
def node_to_plr_dict(node: ResourceDictInstance, has_model: bool):
|
||||
"""转换节点为 PLR 字典格式"""
|
||||
res = node.res_content
|
||||
plr_type = TYPE_MAP.get(res.type, "tip_spot")
|
||||
plr_type = TYPE_MAP.get(res.type, res.type)
|
||||
if res.type not in TYPE_MAP:
|
||||
logger.warning(f"未知类型 {res.type},使用默认类型 tip_spot")
|
||||
logger.warning(f"未知类型 {res.type}")
|
||||
|
||||
d = {
|
||||
"name": res.name,
|
||||
"type": plr_type,
|
||||
"type": res.config.get("type", plr_type),
|
||||
"size_x": res.config.get("size_x", 0),
|
||||
"size_y": res.config.get("size_y", 0),
|
||||
"size_z": res.config.get("size_z", 0),
|
||||
@@ -413,7 +414,7 @@ class ResourceTreeSet(object):
|
||||
"type": "Coordinate",
|
||||
},
|
||||
"rotation": {"x": 0, "y": 0, "z": 0, "type": "Rotation"},
|
||||
"category": plr_type,
|
||||
"category": res.config.get("category", plr_type),
|
||||
"children": [node_to_plr_dict(child, has_model) for child in node.children],
|
||||
"parent_name": res.parent_instance_name,
|
||||
**res.config,
|
||||
@@ -435,7 +436,7 @@ class ResourceTreeSet(object):
|
||||
try:
|
||||
sub_cls = find_subclass(plr_dict["type"], PLRResource)
|
||||
if sub_cls is None:
|
||||
raise ValueError(f"无法找到类型 {plr_dict['type']} 对应的 PLR 资源类")
|
||||
raise ValueError(f"无法找到类型 {plr_dict['type']} 对应的 PLR 资源类。原始信息:{tree.root_node.res_content}")
|
||||
spec = inspect.signature(sub_cls)
|
||||
if "category" not in spec.parameters:
|
||||
plr_dict.pop("category", None)
|
||||
@@ -715,16 +716,9 @@ class ResourceTreeSet(object):
|
||||
Returns:
|
||||
ResourceTreeSet: 反序列化后的资源树集合
|
||||
"""
|
||||
# 将每个字典转换为 ResourceInstanceDict
|
||||
# FIXME: 需要重新确定parent关系
|
||||
nested_lists = []
|
||||
for tree_data in data:
|
||||
flatten_instances = [
|
||||
ResourceDictInstance.get_resource_instance_from_dict(node_dict) for node_dict in tree_data
|
||||
]
|
||||
nested_lists.append(flatten_instances)
|
||||
|
||||
# 使用现有的构造函数创建 ResourceTreeSet
|
||||
nested_lists.extend(ResourceTreeSet.from_raw_list(tree_data).trees)
|
||||
return cls(nested_lists)
|
||||
|
||||
|
||||
@@ -777,7 +771,8 @@ class DeviceNodeResourceTracker(object):
|
||||
else:
|
||||
return getattr(resource, uuid_attr, None)
|
||||
|
||||
def _set_resource_uuid(self, resource, new_uuid: str):
|
||||
@classmethod
|
||||
def set_resource_uuid(cls, resource, new_uuid: str):
|
||||
"""
|
||||
设置资源的 uuid,统一处理 dict 和 instance 两种类型
|
||||
|
||||
@@ -830,7 +825,7 @@ class DeviceNodeResourceTracker(object):
|
||||
resource_name = self._get_resource_attr(res, "name")
|
||||
if resource_name and resource_name in name_to_uuid_map:
|
||||
new_uuid = name_to_uuid_map[resource_name]
|
||||
self._set_resource_uuid(res, new_uuid)
|
||||
self.set_resource_uuid(res, new_uuid)
|
||||
self.uuid_to_resources[new_uuid] = res
|
||||
logger.debug(f"设置资源UUID: {resource_name} -> {new_uuid}")
|
||||
return 1
|
||||
@@ -842,7 +837,7 @@ class DeviceNodeResourceTracker(object):
|
||||
"""
|
||||
递归遍历资源树,更新所有节点的uuid
|
||||
|
||||
Args:
|
||||
Args:0
|
||||
resource: 资源对象(可以是dict或实例)
|
||||
uuid_map: uuid映射字典,{old_uuid: new_uuid}
|
||||
|
||||
@@ -852,17 +847,18 @@ class DeviceNodeResourceTracker(object):
|
||||
|
||||
def process(res):
|
||||
current_uuid = self._get_resource_attr(res, "uuid", "unilabos_uuid")
|
||||
replaced = 0
|
||||
if current_uuid and current_uuid in uuid_map:
|
||||
new_uuid = uuid_map[current_uuid]
|
||||
if current_uuid != new_uuid:
|
||||
self._set_resource_uuid(res, new_uuid)
|
||||
self.set_resource_uuid(res, new_uuid)
|
||||
# 更新uuid_to_resources映射
|
||||
if current_uuid in self.uuid_to_resources:
|
||||
self.uuid_to_resources.pop(current_uuid)
|
||||
self.uuid_to_resources[new_uuid] = res
|
||||
logger.debug(f"更新uuid: {current_uuid} -> {new_uuid}")
|
||||
return 1
|
||||
return 0
|
||||
replaced = 1
|
||||
return replaced
|
||||
|
||||
return self._traverse_and_process(resource, process)
|
||||
|
||||
@@ -877,8 +873,9 @@ class DeviceNodeResourceTracker(object):
|
||||
def process(res):
|
||||
current_uuid = self._get_resource_attr(res, "uuid", "unilabos_uuid")
|
||||
if current_uuid:
|
||||
old = self.uuid_to_resources.get(current_uuid)
|
||||
self.uuid_to_resources[current_uuid] = res
|
||||
logger.debug(f"收集资源UUID映射: {current_uuid} -> {res}")
|
||||
logger.debug(f"收集资源UUID映射: {current_uuid} -> {res} {'' if old is None else f'(覆盖旧值: {old})'}")
|
||||
return 0
|
||||
|
||||
self._traverse_and_process(resource, process)
|
||||
@@ -913,9 +910,23 @@ class DeviceNodeResourceTracker(object):
|
||||
Args:
|
||||
resource: 资源对象(可以是dict或实例)
|
||||
"""
|
||||
root_uuids = {}
|
||||
for r in self.resources:
|
||||
res_uuid = r.get("uuid") if isinstance(r, dict) else getattr(r, "unilabos_uuid", None)
|
||||
if res_uuid:
|
||||
root_uuids[res_uuid] = r
|
||||
if id(r) == id(resource):
|
||||
return
|
||||
|
||||
# 这里只做uuid的根节点比较
|
||||
if isinstance(resource, dict):
|
||||
res_uuid = resource.get("uuid")
|
||||
else:
|
||||
res_uuid = getattr(resource, "unilabos_uuid", None)
|
||||
if res_uuid in root_uuids:
|
||||
old_res = root_uuids[res_uuid]
|
||||
# self.remove_resource(old_res)
|
||||
logger.warning(f"资源{resource}已存在,旧资源: {old_res}")
|
||||
self.resources.append(resource)
|
||||
# 递归收集uuid映射
|
||||
self._collect_uuid_mapping(resource)
|
||||
@@ -1046,13 +1057,19 @@ class DeviceNodeResourceTracker(object):
|
||||
) -> List[Tuple[Any, Any]]:
|
||||
res_list = []
|
||||
# print(resource, target_resource_cls_type, identifier_key, compare_value)
|
||||
children = getattr(resource, "children", [])
|
||||
children = []
|
||||
if not isinstance(resource, dict):
|
||||
children = getattr(resource, "children", [])
|
||||
else:
|
||||
children = resource.get("children")
|
||||
if children is not None:
|
||||
children = list(children.values()) if isinstance(children, dict) else children
|
||||
for child in children:
|
||||
res_list.extend(
|
||||
self.loop_find_resource(child, target_resource_cls_type, identifier_key, compare_value, resource)
|
||||
)
|
||||
if issubclass(type(resource), target_resource_cls_type):
|
||||
if target_resource_cls_type == dict:
|
||||
if type(resource) == dict:
|
||||
# 对于字典类型,直接检查 identifier_key
|
||||
if identifier_key in resource:
|
||||
if resource[identifier_key] == compare_value:
|
||||
|
||||
@@ -336,6 +336,9 @@ class WorkstationNodeCreator(DeviceClassCreator[T]):
|
||||
try:
|
||||
# 创建实例,额外补充一个给protocol node的字段,后面考虑取消
|
||||
data["children"] = self.children
|
||||
for material_id, child in self.children.items():
|
||||
if child["type"] != "device":
|
||||
self.resource_tracker.add_resource(self.children[material_id])
|
||||
deck_dict = data.get("deck")
|
||||
if deck_dict:
|
||||
from pylabrobot.resources import Deck, Resource
|
||||
|
||||
Reference in New Issue
Block a user