Squash merge from dev

Update recipe.yaml

fix: figure_resource

use call_async in all service to avoid deadlock

fix: prcxi import error

临时兼容错误的driver写法

fix protocol node

fix filter protocol

bugfixes on organic protocols

fix and remove redundant info

feat: 新增use_remote_resource参数

fix all protocol_compilers and remove deprecated devices

feat: 优化protocol node节点运行日志

fix pumps and liquid_handler handle

feat: workstation example

add: prcxi res
fix: startup slow

fix: prcxi_res

fix: discard_tips

fix: discard_tips error

fix: drop_tips not using auto resource select

feat: 添加ChinWe设备控制类,支持串口通信和电机控制功能 (#79)

feat: add trace log level

modify default discovery_interval to 15s

fix: working dir error when input config path
feat: report publish topic when error

fix: workstation handlers and vessel_id parsing

Cleanup registry to be easy-understanding (#76)

* delete deprecated mock devices

* rename categories

* combine chromatographic devices

* rename rviz simulation nodes

* organic virtual devices

* parse vessel_id

* run registry completion before merge

---------

Co-authored-by: Xuwznln <18435084+Xuwznln@users.noreply.github.com>
This commit is contained in:
Junhan Chang
2025-08-03 11:21:37 +08:00
committed by Xuwznln
parent a555c59dc2
commit 0bfb52df00
97 changed files with 5033 additions and 164837 deletions

View File

@@ -1,10 +1,11 @@
import collections
import copy
import json
import threading
import time
import traceback
import uuid
from typing import Optional, Dict, Any, List, ClassVar, Set
from typing import Optional, Dict, Any, List, ClassVar, Set, Union
from action_msgs.msg import GoalStatus
from geometry_msgs.msg import Point
@@ -38,6 +39,7 @@ from unilabos.ros.msgs.message_converter import (
from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode, ROS2DeviceNode, DeviceNodeResourceTracker
from unilabos.ros.nodes.presets.controller_node import ControllerNode
from unilabos.utils.exception import DeviceClassInvalid
from unilabos.utils.type_check import serialize_result_info
class HostNode(BaseROS2DeviceNode):
@@ -254,7 +256,7 @@ class HostNode(BaseROS2DeviceNode):
检测ROS2网络中的所有设备节点并为它们创建ActionClient
同时检测设备离线情况
"""
self.lab_logger().debug("[Host Node] Discovering devices in the network...")
self.lab_logger().trace("[Host Node] Discovering devices in the network...")
# 获取当前所有设备
nodes_and_names = self.get_node_names_and_namespaces()
@@ -303,7 +305,7 @@ class HostNode(BaseROS2DeviceNode):
# 更新在线设备列表
self._online_devices = current_devices
self.lab_logger().debug(f"[Host Node] Total online devices: {len(self._online_devices)}")
self.lab_logger().trace(f"[Host Node] Total online devices: {len(self._online_devices)}")
def _discovery_devices_callback(self) -> None:
"""
@@ -335,7 +337,7 @@ class HostNode(BaseROS2DeviceNode):
self._action_clients[action_id] = ActionClient(
self, action_type, action_id, callback_group=self.callback_group
)
self.lab_logger().debug(f"[Host Node] Created ActionClient (Discovery): {action_id}")
self.lab_logger().trace(f"[Host Node] Created ActionClient (Discovery): {action_id}")
action_name = action_id[len(namespace) + 1 :]
edge_device_id = namespace[9:]
# from unilabos.app.mq import mqtt_client
@@ -349,9 +351,9 @@ class HostNode(BaseROS2DeviceNode):
except Exception as e:
self.lab_logger().error(f"[Host Node] Failed to create ActionClient for {action_id}: {str(e)}")
def create_resource_detailed(
async def create_resource_detailed(
self,
resources: list["Resource"],
resources: list[Union[list["Resource"], "Resource"]],
device_ids: list[str],
bind_parent_ids: list[str],
bind_locations: list[Point],
@@ -391,26 +393,28 @@ class HostNode(BaseROS2DeviceNode):
},
ensure_ascii=False,
)
response = sclient.call(request)
response = await sclient.call_async(request)
responses.append(response)
return responses
def create_resource(
async def create_resource(
self,
device_id: str,
res_id: str,
class_name: str,
parent: str,
bind_locations: Point,
liquid_input_slot: list[int],
liquid_type: list[str],
liquid_volume: list[int],
slot_on_deck: str,
liquid_input_slot: list[int] = [],
liquid_type: list[str] = [],
liquid_volume: list[int] = [],
slot_on_deck: str = "",
):
# 暂不支持多对同名父子同时存在
res_creation_input = {
"name": res_id,
"id": res_id.split("/")[-1],
"name": res_id.split("/")[-1],
"class": class_name,
"parent": parent,
"parent": parent.split("/")[-1],
"position": {
"x": bind_locations.x,
"y": bind_locations.y,
@@ -418,16 +422,22 @@ class HostNode(BaseROS2DeviceNode):
},
}
if len(liquid_input_slot) and liquid_input_slot[0] == -1: # 目前container只逐个创建
res_creation_input.update({
"data": {
"liquid_type": liquid_type[0] if liquid_type else None,
"liquid_volume": liquid_volume[0] if liquid_volume else None,
res_creation_input.update(
{
"data": {
"liquids": [{
"liquid_type": liquid_type[0] if liquid_type else None,
"liquid_volume": liquid_volume[0] if liquid_volume else None,
}]
}
}
})
)
init_new_res = initialize_resource(res_creation_input) # flatten的格式
resources = init_new_res # initialize_resource已经返回list[dict]
if len(init_new_res) > 1: # 一个物料,多个子节点
init_new_res = [init_new_res]
resources: List[Resource] | List[List[Resource]] = init_new_res # initialize_resource已经返回list[dict]
device_ids = [device_id]
bind_parent_id = [parent]
bind_parent_id = [res_creation_input["parent"]]
bind_location = [bind_locations]
other_calling_param = [
json.dumps(
@@ -441,7 +451,9 @@ class HostNode(BaseROS2DeviceNode):
)
]
return self.create_resource_detailed(resources, device_ids, bind_parent_id, bind_location, other_calling_param)
response = await self.create_resource_detailed(resources, device_ids, bind_parent_id, bind_location, other_calling_param)
return response
def initialize_device(self, device_id: str, device_config: Dict[str, Any]) -> None:
"""
@@ -476,7 +488,7 @@ class HostNode(BaseROS2DeviceNode):
if action_id not in self._action_clients:
action_type = action_value_mapping["type"]
self._action_clients[action_id] = ActionClient(self, action_type, action_id)
self.lab_logger().debug(
self.lab_logger().trace(
f"[Host Node] Created ActionClient (Local): {action_id}"
) # 子设备再创建用的是Discover发现的
# from unilabos.app.mq import mqtt_client
@@ -521,7 +533,7 @@ class HostNode(BaseROS2DeviceNode):
self.device_status_timestamps[device_id] = {}
# 默认初始化属性值为 None
self.device_status[device_id][property_name] = None
self.device_status[device_id] = collections.defaultdict()
self.device_status_timestamps[device_id][property_name] = 0 # 初始化时间戳
# 动态创建订阅
@@ -539,7 +551,7 @@ class HostNode(BaseROS2DeviceNode):
)
# 标记为已订阅
self._subscribed_topics.add(topic)
self.lab_logger().debug(f"[Host Node] Subscribed to new topic: {topic}")
self.lab_logger().trace(f"[Host Node] Subscribed to new topic: {topic}")
except (NameError, SyntaxError) as e:
self.lab_logger().error(f"[Host Node] Failed to create subscription for topic {topic}: {e}")
@@ -557,10 +569,15 @@ class HostNode(BaseROS2DeviceNode):
# 更新设备状态字典
if hasattr(msg, "data"):
bChange = False
bCreate = False
if isinstance(msg.data, (float, int, str)):
if self.device_status[device_id][property_name] != msg.data:
if property_name not in self.device_status[device_id]:
bCreate = True
bChange = True
self.device_status[device_id][property_name] = msg.data
self.device_status[device_id][property_name] = msg.data
elif self.device_status[device_id][property_name] != msg.data:
bChange = True
self.device_status[device_id][property_name] = msg.data
# 更新时间戳
self.device_status_timestamps[device_id][property_name] = time.time()
else:
@@ -573,9 +590,14 @@ class HostNode(BaseROS2DeviceNode):
for bridge in self.bridges:
if hasattr(bridge, "publish_device_status"):
bridge.publish_device_status(self.device_status, device_id, property_name)
self.lab_logger().debug(
f"[Host Node] Status updated: {device_id}.{property_name} = {msg.data}"
)
if bCreate:
self.lab_logger().trace(
f"Status created: {device_id}.{property_name} = {msg.data}"
)
else:
self.lab_logger().debug(
f"Status updated: {device_id}.{property_name} = {msg.data}"
)
def send_goal(
self,
@@ -667,20 +689,34 @@ class HostNode(BaseROS2DeviceNode):
result_msg = future.result().result
result_data = convert_from_ros_msg(result_msg)
status = "success"
try:
ret = json.loads(result_data.get("return_info", "{}")) # 确保返回信息是有效的JSON
suc = ret.get("suc", False)
if not suc:
return_info_str = result_data.get("return_info")
if return_info_str is not None:
try:
ret = json.loads(return_info_str)
suc = ret.get("suc", False)
if not suc:
status = "failed"
except json.JSONDecodeError:
status = "failed"
except json.JSONDecodeError:
status = "failed"
self.lab_logger().info(f"[Host Node] Result for {action_id} ({uuid_str}): success")
else:
# 无 return_info 字段时,回退到 success 字段(若存在)
suc_field = result_data.get("success")
if isinstance(suc_field, bool):
status = "success" if suc_field else "failed"
return_info_str = serialize_result_info("", suc_field, result_data)
else:
# 最保守的回退标记失败并返回空JSON
status = "failed"
return_info_str = serialize_result_info("缺少return_info", False, result_data)
self.lab_logger().info(f"[Host Node] Result for {action_id} ({uuid_str}): {status}")
self.lab_logger().debug(f"[Host Node] Result data: {result_data}")
if uuid_str:
for bridge in self.bridges:
if hasattr(bridge, "publish_job_status"):
bridge.publish_job_status(result_data, uuid_str, status, result_data.get("return_info", "{}"))
bridge.publish_job_status(result_data, uuid_str, status, return_info_str)
def cancel_goal(self, goal_uuid: str) -> None:
"""取消目标"""
@@ -809,10 +845,19 @@ class HostNode(BaseROS2DeviceNode):
success = bool(r)
response.success = success
if success:
from unilabos.resources.graphio import physical_setup_graph
for resource in resources:
if resource.get("id") not in physical_setup_graph.nodes:
physical_setup_graph.add_node(resource["id"], **resource)
else:
physical_setup_graph.nodes[resource["id"]]["data"].update(resource["data"])
self.lab_logger().info(f"[Host Node-Resource] Add request completed, success: {success}")
return response
def _resource_get_callback(self, request, response):
def _resource_get_callback(self, request: ResourceGet.Request, response: ResourceGet.Response):
"""
获取资源回调

View File

@@ -1,8 +1,12 @@
import json
import time
import traceback
from pprint import pprint, saferepr, pformat
from typing import Union
import rclpy
from rosidl_runtime_py import message_to_ordereddict
from unilabos.messages import * # type: ignore # protocol names
from rclpy.action import ActionServer, ActionClient
from rclpy.action.server import ServerGoalHandle
@@ -88,6 +92,9 @@ class ROS2ProtocolNode(BaseROS2DeviceNode):
if device_config.get("type", "device") != "device":
continue
# 设置硬件接口代理
if device_id not in self.sub_devices:
self.lab_logger().error(f"[Protocol Node] {device_id} 还没有正确初始化,跳过...")
continue
d = self.sub_devices[device_id]
if d:
hardware_interface = d.ros_node_instance._hardware_interface
@@ -139,6 +146,7 @@ class ROS2ProtocolNode(BaseROS2DeviceNode):
# 为子设备的每个动作创建动作客户端
if d is not None and hasattr(d, "ros_node_instance"):
node = d.ros_node_instance
node.resource_tracker = self.resource_tracker # 站内应当共享资源跟踪器
for action_name, action_mapping in node._action_value_mappings.items():
if action_name.startswith("auto-") or str(action_mapping.get("type", "")).startswith("UniLabJsonCommand"):
continue
@@ -151,7 +159,7 @@ class ROS2ProtocolNode(BaseROS2DeviceNode):
except Exception as ex:
self.lab_logger().error(f"创建动作客户端失败: {action_id}, 错误: {ex}")
continue
self.lab_logger().debug(f"为子设备 {device_id} 创建动作客户端: {action_name}")
self.lab_logger().trace(f"为子设备 {device_id} 创建动作客户端: {action_name}")
return d
def create_ros_action_server(self, action_name, action_value_mapping):
@@ -171,7 +179,7 @@ class ROS2ProtocolNode(BaseROS2DeviceNode):
callback_group=ReentrantCallbackGroup(),
)
self.lab_logger().debug(f"发布动作: {action_name}, 类型: {str_action_type}")
self.lab_logger().trace(f"发布动作: {action_name}, 类型: {str_action_type}")
def _create_protocol_execute_callback(self, protocol_name, protocol_steps_generator):
async def execute_protocol(goal_handle: ServerGoalHandle):
@@ -182,6 +190,7 @@ class ROS2ProtocolNode(BaseROS2DeviceNode):
protocol_return_value = None
self.get_logger().info(f"Executing {protocol_name} action...")
action_value_mapping = self._action_value_mappings[protocol_name]
step_results = []
try:
print("+" * 30)
print(protocol_steps_generator)
@@ -209,22 +218,26 @@ class ROS2ProtocolNode(BaseROS2DeviceNode):
[convert_from_ros_msg(rs) for rs in response.resources]
)
self.lab_logger().info(f"🔍 最终传递给协议的 protocol_kwargs: {protocol_kwargs}")
self.lab_logger().info(f"🔍 最终的 vessel: {protocol_kwargs.get('vessel', 'NOT_FOUND')}")
from unilabos.resources.graphio import physical_setup_graph
self.lab_logger().info(f"Working on physical setup: {physical_setup_graph}")
protocol_steps = protocol_steps_generator(G=physical_setup_graph, **protocol_kwargs)
self.lab_logger().info(f"Goal received: {protocol_kwargs}, running steps: \n{protocol_steps}")
logs = []
for step in protocol_steps:
if isinstance(step, dict) and "log_message" in step.get("action_kwargs", {}):
logs.append(step)
elif isinstance(step, list):
logs.append(step)
self.lab_logger().info(f"Goal received: {protocol_kwargs}, running steps: "
f"{json.dumps(logs, indent=4, ensure_ascii=False)}")
time_start = time.time()
time_overall = 100
self._busy = True
# 逐步执行工作流
step_results = []
for i, action in enumerate(protocol_steps):
# self.get_logger().info(f"Running step {i + 1}: {action}")
if isinstance(action, dict):
@@ -235,6 +248,9 @@ class ROS2ProtocolNode(BaseROS2DeviceNode):
else:
result = await self.execute_single_action(**action)
step_results.append({"step": i + 1, "action": action["action_name"], "result": result})
ret_info = json.loads(getattr(result, "return_info", "{}"))
if not ret_info.get("suc", False):
raise RuntimeError(f"Step {i + 1} failed.")
elif isinstance(action, list):
# 如果是并行动作,同时执行
actions = action
@@ -272,11 +288,10 @@ class ROS2ProtocolNode(BaseROS2DeviceNode):
except Exception as e:
# 捕获并记录错误信息
execution_error = traceback.format_exc()
str_step_results = [{k: dict(message_to_ordereddict(v)) if k == "result" and hasattr(v, "SLOT_TYPES") else v for k, v in i.items()} for i in step_results]
execution_error = f"{traceback.format_exc()}\n\nStep Result: {pformat(str_step_results)}"
execution_success = False
error(f"协议 {protocol_name} 执行失败")
error(traceback.format_exc())
self.lab_logger().error(f"协议执行出错: {str(e)}")
self.lab_logger().error(f"协议 {protocol_name} 执行出错: {str(e)} \n{traceback.format_exc()}")
# 设置动作失败
goal_handle.abort()
@@ -302,7 +317,7 @@ class ROS2ProtocolNode(BaseROS2DeviceNode):
serialize_result_info(execution_error, execution_success, protocol_return_value),
)
self.lab_logger().info(f"🤩🤩🤩🤩🤩🤩协议 {protocol_name} 完成并返回结果😎😎😎😎😎😎")
self.lab_logger().info(f"协议 {protocol_name} 完成并返回结果")
return result
return execute_protocol

View File

@@ -0,0 +1,86 @@
import collections
from typing import Union, Dict, Any, Optional
from unilabos_msgs.msg import Resource
from pylabrobot.resources import Resource as PLRResource, Plate, TipRack, Coordinate
from unilabos.ros.nodes.presets.protocol_node import ROS2ProtocolNode
from unilabos.ros.nodes.resource_tracker import DeviceNodeResourceTracker
class WorkStationContainer(Plate, TipRack):
"""
WorkStation 专用 Container 类,继承自 Plate和TipRack
注意这个物料必须通过plr_additional_res_reg.py注册到edge才能正常序列化
"""
def __init__(self, name: str, size_x: float, size_y: float, size_z: float, category: str, ordering: collections.OrderedDict, model: Optional[str] = None,):
"""
这里的初始化入参要和plr的保持一致
"""
super().__init__(name, size_x, size_y, size_z, category=category, ordering=ordering, model=model)
self._unilabos_state = {} # 必须有此行,自己的类描述的是物料的
def load_state(self, state: Dict[str, Any]) -> None:
"""从给定的状态加载工作台信息。"""
super().load_state(state)
self._unilabos_state = state
def serialize_state(self) -> Dict[str, Dict[str, Any]]:
data = super().serialize_state()
data.update(self._unilabos_state) # Container自身的信息云端物料将保存这一data本地也通过这里的data进行读写当前类用来表示这个物料的长宽高大小的属性而datastate用来表示物料的内容细节等
return data
def get_workstation_plate_resource(name: str) -> PLRResource: # 要给定一个返回plr的方法
"""
用于获取一些模板,例如返回一个带有特定信息/子物料的 Plate这里需要到注册表注册例如unilabos/registry/resources/organic/workstation.yaml
可以直接运行该函数或者利用注册表补全机制,来检查是否资源出错
:param name: 资源名称
:return: Resource对象
"""
plate = WorkStationContainer(name, size_x=50, size_y=50, size_z=10, category="plate", ordering=collections.OrderedDict())
tip_rack = WorkStationContainer("tip_rack_inside_plate", size_x=50, size_y=50, size_z=10, category="tip_rack", ordering=collections.OrderedDict())
plate.assign_child_resource(tip_rack, Coordinate.zero())
return plate
class WorkStationExample(ROS2ProtocolNode):
def __init__(self,
# 你可以在这里增加任意的参数对应启动json填写相应的参数内容
device_id: str,
children: dict,
protocol_type: Union[str, list[str]],
resource_tracker: DeviceNodeResourceTracker
):
super().__init__(device_id, children, protocol_type, resource_tracker)
def create_resource(
self,
resource_tracker: DeviceNodeResourceTracker,
resources: list[Resource],
bind_parent_id: str,
bind_location: dict[str, float],
liquid_input_slot: list[int],
liquid_type: list[str],
liquid_volume: list[int],
slot_on_deck: int,
) -> Dict[str, Any]:
return { # edge侧返回给前端的创建物料的结果。云端调用初始化瓶子等。执行该函数时物料已经上报给云端一般不需要继承使用
}
def transfer_bottle(self, tip_rack: PLRResource, base_plate: PLRResource): # 使用自定义物料的举例
"""
将tip_rack assign给base_plate两个入参都得是PLRResourceunilabos会代替当前物料操作自动刷新他们的父子关系等状态
"""
pass
def trigger_resource_update(self, from_plate: PLRResource, to_base_plate: PLRResource):
"""
有些时候物料发生了子设备的迁移一般对该设备的最大一级的物料进行操作例如要将A物料搬移到B物料上他们不共同拥有一个物料
该步骤操作结束后会主动刷新from_plate的父物料与to_base_plate的父物料如没有则刷新自身
"""
to_base_plate.assign_child_resource(from_plate, Coordinate.zero())
pass