mirror of
https://github.com/dptech-corp/Uni-Lab-OS.git
synced 2025-12-17 04:51:10 +00:00
Merge branch 'workstation_dev' into dev
# Conflicts: # .conda/recipe.yaml # recipes/msgs/recipe.yaml # recipes/unilabos/recipe.yaml # setup.py # unilabos/registry/devices/work_station.yaml # unilabos/ros/nodes/base_device_node.py # unilabos/ros/nodes/presets/protocol_node.py # unilabos_msgs/package.xml
This commit is contained in:
@@ -518,6 +518,17 @@ class BaseROS2DeviceNode(Node, Generic[T]):
|
||||
rclpy.get_global_executor().add_node(self)
|
||||
self.lab_logger().debug(f"ROS节点初始化完成")
|
||||
|
||||
async def update_resource(self, resources: List[Any]):
|
||||
r = ResourceUpdate.Request()
|
||||
unique_resources = []
|
||||
for resource in resources: # resource是list[ResourcePLR]
|
||||
# 目前更新资源只支持传入plr的对象,后面要更新convert_resources_from_type函数
|
||||
converted_list = convert_resources_from_type([resource], resource_type=[object], is_plr=True)
|
||||
unique_resources.extend([convert_to_ros_msg(Resource, converted) for converted in converted_list])
|
||||
r.resources = unique_resources
|
||||
response = await self._resource_clients["resource_update"].call_async(r)
|
||||
self.lab_logger().debug(f"资源更新结果: {response}")
|
||||
|
||||
def register_device(self):
|
||||
"""向注册表中注册设备信息"""
|
||||
topics_info = self._property_publishers.copy()
|
||||
@@ -947,6 +958,7 @@ class ROS2DeviceNode:
|
||||
self._driver_class = driver_class
|
||||
self.device_config = device_config
|
||||
self.driver_is_ros = driver_is_ros
|
||||
self.driver_is_workstation = False
|
||||
self.resource_tracker = DeviceNodeResourceTracker()
|
||||
|
||||
# use_pylabrobot_creator 使用 cls的包路径检测
|
||||
@@ -967,10 +979,11 @@ class ROS2DeviceNode:
|
||||
driver_class, children=children, resource_tracker=self.resource_tracker
|
||||
)
|
||||
else:
|
||||
from unilabos.ros.nodes.presets.protocol_node import ROS2ProtocolNode
|
||||
from unilabos.devices.workstation.workstation_base import WorkstationBase
|
||||
|
||||
if issubclass(self._driver_class, ROS2ProtocolNode): # 是ProtocolNode的子节点,就要调用ProtocolNodeCreator
|
||||
self._driver_creator = ProtocolNodeCreator(driver_class, children=children, resource_tracker=self.resource_tracker)
|
||||
if issubclass(self._driver_class, WorkstationBase): # 是WorkstationNode的子节点,就要调用WorkstationNodeCreator
|
||||
self.driver_is_workstation = True
|
||||
self._driver_creator = WorkstationNodeCreator(driver_class, children=children, resource_tracker=self.resource_tracker)
|
||||
else:
|
||||
self._driver_creator = DeviceClassCreator(driver_class, children=children, resource_tracker=self.resource_tracker)
|
||||
|
||||
@@ -985,6 +998,19 @@ class ROS2DeviceNode:
|
||||
# 创建ROS2节点
|
||||
if driver_is_ros:
|
||||
self._ros_node = self._driver_instance # type: ignore
|
||||
elif self.driver_is_workstation:
|
||||
from unilabos.ros.nodes.presets.workstation import ROS2WorkstationNode
|
||||
self._ros_node = ROS2WorkstationNode(
|
||||
protocol_type=driver_params["protocol_type"],
|
||||
children=children,
|
||||
driver_instance=self._driver_instance, # type: ignore
|
||||
device_id=device_id,
|
||||
status_types=status_types,
|
||||
action_value_mappings=action_value_mappings,
|
||||
hardware_interface=hardware_interface,
|
||||
print_publish=print_publish,
|
||||
resource_tracker=self.resource_tracker,
|
||||
)
|
||||
else:
|
||||
self._ros_node = BaseROS2DeviceNode(
|
||||
driver_instance=self._driver_instance,
|
||||
|
||||
@@ -553,7 +553,7 @@ class HostNode(BaseROS2DeviceNode):
|
||||
|
||||
# 解析设备名和属性名
|
||||
parts = topic.split("/")
|
||||
if len(parts) >= 4: # 可能有ProtocolNode,创建更长的设备
|
||||
if len(parts) >= 4: # 可能有WorkstationNode,创建更长的设备
|
||||
device_id = "/".join(parts[2:-1])
|
||||
property_name = parts[-1]
|
||||
|
||||
|
||||
@@ -1,86 +1,413 @@
|
||||
import collections
|
||||
from typing import Union, Dict, Any, Optional
|
||||
import json
|
||||
import time
|
||||
import traceback
|
||||
from pprint import pformat
|
||||
from typing import List, Dict, Any, Optional, TYPE_CHECKING
|
||||
|
||||
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
|
||||
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
|
||||
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.compile import action_protocol_generators
|
||||
from unilabos.resources.graphio import list_to_nested_dict, nested_dict_to_list
|
||||
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
|
||||
|
||||
if TYPE_CHECKING:
|
||||
from unilabos.devices.workstation.workstation_base import WorkstationBase
|
||||
|
||||
|
||||
class WorkStationContainer(Plate, TipRack):
|
||||
class ROS2WorkstationNode(BaseROS2DeviceNode):
|
||||
"""
|
||||
WorkStation 专用 Container 类,继承自 Plate和TipRack
|
||||
注意这个物料必须通过plr_additional_res_reg.py注册到edge,才能正常序列化
|
||||
ROS2WorkstationNode代表管理ROS2环境中设备通信和动作的协议节点。
|
||||
它初始化设备节点,处理动作客户端,并基于指定的协议执行工作流。
|
||||
它还物理上代表一组协同工作的设备,如带夹持器的机械臂,带传送带的CNC机器等。
|
||||
"""
|
||||
|
||||
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 = {} # 必须有此行,自己的类描述的是物料的
|
||||
driver_instance: "WorkstationBase"
|
||||
|
||||
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进行读写,当前类用来表示这个物料的长宽高大小的属性,而data(state用来表示物料的内容,细节等)
|
||||
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(
|
||||
def __init__(
|
||||
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侧返回给前端的创建物料的结果。云端调用初始化瓶子等。执行该函数时,物料已经上报给云端,一般不需要继承使用
|
||||
protocol_type: List[str],
|
||||
children: Dict[str, Any],
|
||||
*,
|
||||
driver_instance: "WorkstationBase",
|
||||
device_id: str,
|
||||
status_types: Dict[str, Any],
|
||||
action_value_mappings: Dict[str, Any],
|
||||
hardware_interface: Dict[str, Any],
|
||||
print_publish=True,
|
||||
resource_tracker: Optional["DeviceNodeResourceTracker"] = None,
|
||||
):
|
||||
self._setup_protocol_names(protocol_type)
|
||||
|
||||
}
|
||||
# 初始化非BaseROSNode的属性
|
||||
self.children = children
|
||||
# 初始化基类,让基类处理常规动作
|
||||
super().__init__(
|
||||
driver_instance=driver_instance,
|
||||
device_id=device_id,
|
||||
status_types=status_types,
|
||||
action_value_mappings={
|
||||
**action_value_mappings,
|
||||
**self.protocol_action_mappings
|
||||
},
|
||||
hardware_interface=hardware_interface,
|
||||
print_publish=print_publish,
|
||||
resource_tracker=resource_tracker,
|
||||
)
|
||||
|
||||
def transfer_bottle(self, tip_rack: PLRResource, base_plate: PLRResource): # 使用自定义物料的举例
|
||||
"""
|
||||
将tip_rack assign给base_plate,两个入参都得是PLRResource,unilabos会代替当前物料操作,自动刷新他们的父子关系等状态
|
||||
"""
|
||||
pass
|
||||
self._busy = False
|
||||
self.sub_devices = {}
|
||||
self._action_clients = {}
|
||||
|
||||
def trigger_resource_update(self, from_plate: PLRResource, to_base_plate: PLRResource):
|
||||
"""
|
||||
有些时候物料发生了子设备的迁移,一般对该设备的最大一级的物料进行操作,例如要将A物料搬移到B物料上,他们不共同拥有一个物料
|
||||
该步骤操作结束后,会主动刷新from_plate的父物料,与to_base_plate的父物料(如没有则刷新自身)
|
||||
# 初始化子设备
|
||||
self.communication_node_id_to_instance = {}
|
||||
|
||||
"""
|
||||
to_base_plate.assign_child_resource(from_plate, Coordinate.zero())
|
||||
pass
|
||||
for device_id, device_config in self.children.items():
|
||||
if device_config.get("type", "device") != "device":
|
||||
self.lab_logger().debug(
|
||||
f"[Protocol Node] Skipping type {device_config['type']} {device_id} already existed, skipping."
|
||||
)
|
||||
continue
|
||||
try:
|
||||
d = self.initialize_device(device_id, device_config)
|
||||
except Exception as ex:
|
||||
self.lab_logger().error(
|
||||
f"[Protocol Node] Failed to initialize device {device_id}: {ex}\n{traceback.format_exc()}")
|
||||
d = None
|
||||
if d is None:
|
||||
continue
|
||||
|
||||
if "serial_" in device_id or "io_" in device_id:
|
||||
self.communication_node_id_to_instance[device_id] = d
|
||||
continue
|
||||
|
||||
for device_id, device_config in self.children.items():
|
||||
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
|
||||
if (
|
||||
hasattr(d.driver_instance, hardware_interface["name"])
|
||||
and hasattr(d.driver_instance, hardware_interface["write"])
|
||||
and (
|
||||
hardware_interface["read"] is None or hasattr(d.driver_instance, hardware_interface["read"]))
|
||||
):
|
||||
|
||||
name = getattr(d.driver_instance, hardware_interface["name"])
|
||||
read = hardware_interface.get("read", None)
|
||||
write = hardware_interface.get("write", None)
|
||||
|
||||
# 如果硬件接口是字符串,通过通信设备提供
|
||||
if isinstance(name, str) and name in self.sub_devices:
|
||||
communicate_device = self.sub_devices[name]
|
||||
communicate_hardware_info = communicate_device.ros_node_instance._hardware_interface
|
||||
self._setup_hardware_proxy(d, self.sub_devices[name], read, write)
|
||||
self.lab_logger().info(
|
||||
f"\n通信代理:为子设备{device_id}\n "
|
||||
f"添加了{read}方法(来源:{name} {communicate_hardware_info['write']}) \n "
|
||||
f"添加了{write}方法(来源:{name} {communicate_hardware_info['read']})"
|
||||
)
|
||||
|
||||
self.lab_logger().info(f"ROS2ProtocolNode {device_id} initialized with protocols: {self.protocol_names}")
|
||||
|
||||
def _setup_protocol_names(self, protocol_type):
|
||||
# 处理协议类型
|
||||
if isinstance(protocol_type, str):
|
||||
if "," not in protocol_type:
|
||||
self.protocol_names = [protocol_type]
|
||||
else:
|
||||
self.protocol_names = [protocol.strip() for protocol in protocol_type.split(",")]
|
||||
else:
|
||||
self.protocol_names = protocol_type
|
||||
# 准备协议相关的动作值映射
|
||||
self.protocol_action_mappings = {}
|
||||
for protocol_name in self.protocol_names:
|
||||
protocol_type = globals()[protocol_name]
|
||||
self.protocol_action_mappings[protocol_name] = get_action_type(protocol_type)
|
||||
|
||||
def initialize_device(self, device_id, device_config):
|
||||
"""初始化设备并创建相应的动作客户端"""
|
||||
# device_id_abs = f"{self.device_id}/{device_id}"
|
||||
device_id_abs = f"{device_id}"
|
||||
self.lab_logger().info(f"初始化子设备: {device_id_abs}")
|
||||
d = self.sub_devices[device_id] = initialize_device_from_dict(device_id_abs, device_config)
|
||||
|
||||
# 为子设备的每个动作创建动作客户端
|
||||
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
|
||||
action_id = f"/devices/{device_id_abs}/{action_name}"
|
||||
if action_id not in self._action_clients:
|
||||
try:
|
||||
self._action_clients[action_id] = ActionClient(
|
||||
self, action_mapping["type"], action_id, callback_group=self.callback_group
|
||||
)
|
||||
except Exception as ex:
|
||||
self.lab_logger().error(f"创建动作客户端失败: {action_id}, 错误: {ex}")
|
||||
continue
|
||||
self.lab_logger().trace(f"为子设备 {device_id} 创建动作客户端: {action_name}")
|
||||
return d
|
||||
|
||||
def create_ros_action_server(self, action_name, action_value_mapping):
|
||||
"""创建ROS动作服务器"""
|
||||
if action_name not in self.protocol_names:
|
||||
# 非protocol方法调用父类注册
|
||||
return super().create_ros_action_server(action_name, action_value_mapping)
|
||||
# 和Base创建的路径是一致的
|
||||
protocol_name = action_name
|
||||
action_type = action_value_mapping["type"]
|
||||
str_action_type = str(action_type)[8:-2]
|
||||
protocol_type = globals()[protocol_name]
|
||||
protocol_steps_generator = action_protocol_generators[protocol_type]
|
||||
|
||||
self._action_servers[action_name] = ActionServer(
|
||||
self,
|
||||
action_type,
|
||||
action_name,
|
||||
execute_callback=self._create_protocol_execute_callback(action_name, protocol_steps_generator),
|
||||
callback_group=ReentrantCallbackGroup(),
|
||||
)
|
||||
self.lab_logger().trace(f"发布动作: {action_name}, 类型: {str_action_type}")
|
||||
return
|
||||
|
||||
def _create_protocol_execute_callback(self, protocol_name, protocol_steps_generator):
|
||||
async def execute_protocol(goal_handle: ServerGoalHandle):
|
||||
"""执行完整的工作流"""
|
||||
# 初始化结果信息变量
|
||||
execution_error = ""
|
||||
execution_success = False
|
||||
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)
|
||||
# 从目标消息中提取参数, 并调用Protocol生成器(根据设备连接图)生成action步骤
|
||||
goal = goal_handle.request
|
||||
protocol_kwargs = convert_from_ros_msg_with_mapping(goal, action_value_mapping["goal"])
|
||||
|
||||
# # 🔧 添加调试信息
|
||||
# print(f"🔍 转换后的 protocol_kwargs: {protocol_kwargs}")
|
||||
# print(f"🔍 vessel 在转换后: {protocol_kwargs.get('vessel', 'NOT_FOUND')}")
|
||||
|
||||
# # 🔧 完全禁用Host查询,直接使用转换后的数据
|
||||
# print(f"🔧 跳过Host查询,直接使用转换后的数据")
|
||||
# 向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"🔍 最终的 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)
|
||||
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
|
||||
|
||||
# 逐步执行工作流
|
||||
for i, action in enumerate(protocol_steps):
|
||||
# self.get_logger().info(f"Running step {i + 1}: {action}")
|
||||
if isinstance(action, dict):
|
||||
# 如果是单个动作,直接执行
|
||||
if action["action_name"] == "wait":
|
||||
time.sleep(action["action_kwargs"]["time"])
|
||||
step_results.append({"step": i + 1, "action": "wait", "result": "completed"})
|
||||
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
|
||||
futures = [
|
||||
rclpy.get_global_executor().create_task(self.execute_single_action(**a)) for a in actions
|
||||
]
|
||||
results = [await f for f in futures]
|
||||
step_results.append(
|
||||
{
|
||||
"step": i + 1,
|
||||
"parallel_actions": [a["action_name"] for a in actions],
|
||||
"results": results,
|
||||
}
|
||||
)
|
||||
|
||||
# 向Host更新物料当前状态
|
||||
for k, v in goal.get_fields_and_field_types().items():
|
||||
if v in ["unilabos_msgs/Resource", "sequence<unilabos_msgs/Resource>"]:
|
||||
r = ResourceUpdate.Request()
|
||||
r.resources = [
|
||||
convert_to_ros_msg(Resource, rs) for rs in nested_dict_to_list(protocol_kwargs[k])
|
||||
]
|
||||
response = await self._resource_clients["resource_update"].call_async(r)
|
||||
|
||||
# 设置成功状态和返回值
|
||||
execution_success = True
|
||||
protocol_return_value = {
|
||||
"protocol_name": protocol_name,
|
||||
"steps_executed": len(protocol_steps),
|
||||
"step_results": step_results,
|
||||
"total_time": time.time() - time_start,
|
||||
}
|
||||
|
||||
goal_handle.succeed()
|
||||
|
||||
except Exception as e:
|
||||
# 捕获并记录错误信息
|
||||
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
|
||||
self.lab_logger().error(f"协议 {protocol_name} 执行出错: {str(e)} \n{traceback.format_exc()}")
|
||||
|
||||
# 设置动作失败
|
||||
goal_handle.abort()
|
||||
|
||||
finally:
|
||||
self._busy = False
|
||||
|
||||
# 创建结果消息
|
||||
result = action_value_mapping["type"].Result()
|
||||
result.success = execution_success
|
||||
|
||||
# 获取结果消息类型信息,检查是否有return_info字段
|
||||
result_msg_types = action_value_mapping["type"].Result.get_fields_and_field_types()
|
||||
|
||||
# 设置return_info字段(如果存在)
|
||||
for attr_name in result_msg_types.keys():
|
||||
if attr_name in ["success", "reached_goal"]:
|
||||
setattr(result, attr_name, execution_success)
|
||||
elif attr_name == "return_info":
|
||||
setattr(
|
||||
result,
|
||||
attr_name,
|
||||
serialize_result_info(execution_error, execution_success, protocol_return_value),
|
||||
)
|
||||
|
||||
self.lab_logger().info(f"协议 {protocol_name} 完成并返回结果")
|
||||
return result
|
||||
|
||||
return execute_protocol
|
||||
|
||||
async def execute_single_action(self, device_id, action_name, action_kwargs):
|
||||
"""执行单个动作"""
|
||||
# 构建动作ID
|
||||
if device_id in ["", None, "self"]:
|
||||
action_id = f"/devices/{self.device_id}/{action_name}"
|
||||
else:
|
||||
action_id = f"/devices/{device_id}/{action_name}" # 执行时取消了主节点信息 /{self.device_id}
|
||||
|
||||
# 检查动作客户端是否存在
|
||||
if action_id not in self._action_clients:
|
||||
self.lab_logger().error(f"找不到动作客户端: {action_id}")
|
||||
return None
|
||||
|
||||
# 发送动作请求
|
||||
action_client = self._action_clients[action_id]
|
||||
goal_msg = convert_to_ros_msg(action_client._action_type.Goal(), action_kwargs)
|
||||
|
||||
##### self.lab_logger().info(f"发送动作请求到: {action_id}")
|
||||
action_client.wait_for_server()
|
||||
|
||||
# 等待动作完成
|
||||
request_future = action_client.send_goal_async(goal_msg)
|
||||
handle = await request_future
|
||||
|
||||
if not handle.accepted:
|
||||
self.lab_logger().error(f"动作请求被拒绝: {action_name}")
|
||||
return None
|
||||
|
||||
result_future = await handle.get_result_async()
|
||||
##### self.lab_logger().info(f"动作完成: {action_name}")
|
||||
|
||||
return result_future.result
|
||||
|
||||
"""还没有改过的部分"""
|
||||
|
||||
def _setup_hardware_proxy(
|
||||
self, device: ROS2DeviceNode, communication_device: ROS2DeviceNode, read_method, write_method
|
||||
):
|
||||
"""为设备设置硬件接口代理"""
|
||||
# extra_info = [getattr(device.driver_instance, info) for info in communication_device.ros_node_instance._hardware_interface.get("extra_info", [])]
|
||||
write_func = getattr(
|
||||
communication_device.driver_instance, communication_device.ros_node_instance._hardware_interface["write"]
|
||||
)
|
||||
read_func = getattr(
|
||||
communication_device.driver_instance, communication_device.ros_node_instance._hardware_interface["read"]
|
||||
)
|
||||
|
||||
def _read(*args, **kwargs):
|
||||
return read_func(*args, **kwargs)
|
||||
|
||||
def _write(*args, **kwargs):
|
||||
return write_func(*args, **kwargs)
|
||||
|
||||
if read_method:
|
||||
# bound_read = MethodType(_read, device.driver_instance)
|
||||
setattr(device.driver_instance, read_method, _read)
|
||||
|
||||
if write_method:
|
||||
# bound_write = MethodType(_write, device.driver_instance)
|
||||
setattr(device.driver_instance, write_method, _write)
|
||||
|
||||
async def _update_resources(self, goal, protocol_kwargs):
|
||||
"""更新资源状态"""
|
||||
for k, v in goal.get_fields_and_field_types().items():
|
||||
if v in ["unilabos_msgs/Resource", "sequence<unilabos_msgs/Resource>"]:
|
||||
if protocol_kwargs[k] is not None:
|
||||
try:
|
||||
r = ResourceUpdate.Request()
|
||||
r.resources = [
|
||||
convert_to_ros_msg(Resource, rs) for rs in nested_dict_to_list(protocol_kwargs[k])
|
||||
]
|
||||
await self._resource_clients["resource_update"].call_async(r)
|
||||
except Exception as e:
|
||||
self.lab_logger().error(f"更新资源失败: {e}")
|
||||
@@ -1,7 +1,12 @@
|
||||
from typing import List, Tuple, Any
|
||||
from typing import List, Tuple, Any, Dict, TYPE_CHECKING
|
||||
from abc import ABC, abstractmethod
|
||||
|
||||
from unilabos.utils.log import logger
|
||||
|
||||
if TYPE_CHECKING:
|
||||
from unilabos.devices.workstation.workstation_base import WorkstationBase
|
||||
from pylabrobot.resources import Resource as PLRResource
|
||||
|
||||
|
||||
class DeviceNodeResourceTracker(object):
|
||||
|
||||
@@ -37,10 +42,20 @@ class DeviceNodeResourceTracker(object):
|
||||
def figure_resource(self, query_resource, try_mode=False):
|
||||
if isinstance(query_resource, list):
|
||||
return [self.figure_resource(r, try_mode) for r in query_resource]
|
||||
elif isinstance(query_resource, dict) and "id" not in query_resource and "name" not in query_resource: # 临时处理,要删除的,driver有太多类型错误标注
|
||||
elif (
|
||||
isinstance(query_resource, dict) and "id" not in query_resource and "name" not in query_resource
|
||||
): # 临时处理,要删除的,driver有太多类型错误标注
|
||||
return [self.figure_resource(r, try_mode) for r in query_resource.values()]
|
||||
res_id = query_resource.id if hasattr(query_resource, "id") else (query_resource.get("id") if isinstance(query_resource, dict) else None)
|
||||
res_name = query_resource.name if hasattr(query_resource, "name") else (query_resource.get("name") if isinstance(query_resource, dict) else None)
|
||||
res_id = (
|
||||
query_resource.id
|
||||
if hasattr(query_resource, "id")
|
||||
else (query_resource.get("id") if isinstance(query_resource, dict) else None)
|
||||
)
|
||||
res_name = (
|
||||
query_resource.name
|
||||
if hasattr(query_resource, "name")
|
||||
else (query_resource.get("name") if isinstance(query_resource, dict) else None)
|
||||
)
|
||||
res_identifier = res_id if res_id else res_name
|
||||
identifier_key = "id" if res_id else "name"
|
||||
resource_cls_type = type(query_resource)
|
||||
@@ -54,7 +69,9 @@ class DeviceNodeResourceTracker(object):
|
||||
)
|
||||
else:
|
||||
res_list.extend(
|
||||
self.loop_find_resource(r, resource_cls_type, identifier_key, getattr(query_resource, identifier_key))
|
||||
self.loop_find_resource(
|
||||
r, resource_cls_type, identifier_key, getattr(query_resource, identifier_key)
|
||||
)
|
||||
)
|
||||
if not try_mode:
|
||||
assert len(res_list) > 0, f"没有找到资源 {query_resource},请检查资源是否存在"
|
||||
@@ -66,12 +83,16 @@ class DeviceNodeResourceTracker(object):
|
||||
self.resource2parent_resource[id(res_list[0][1])] = res_list[0][0]
|
||||
return res_list[0][1]
|
||||
|
||||
def loop_find_resource(self, resource, target_resource_cls_type, identifier_key, compare_value, parent_res=None) -> List[Tuple[Any, Any]]:
|
||||
def loop_find_resource(
|
||||
self, resource, target_resource_cls_type, identifier_key, compare_value, parent_res=None
|
||||
) -> List[Tuple[Any, Any]]:
|
||||
res_list = []
|
||||
# print(resource, target_resource_cls_type, identifier_key, compare_value)
|
||||
children = getattr(resource, "children", [])
|
||||
for child in children:
|
||||
res_list.extend(self.loop_find_resource(child, target_resource_cls_type, identifier_key, compare_value, resource))
|
||||
res_list.extend(
|
||||
self.loop_find_resource(child, target_resource_cls_type, identifier_key, compare_value, resource)
|
||||
)
|
||||
if target_resource_cls_type == type(resource):
|
||||
if target_resource_cls_type == dict:
|
||||
if identifier_key in resource:
|
||||
|
||||
Reference in New Issue
Block a user