mirror of
https://github.com/dptech-corp/Uni-Lab-OS.git
synced 2025-12-17 04:51:10 +00:00
24 high level liquidhandler (#28)
* unify liquid_handler definition * remove default values * Dev Sync (#25) * Update README and MQTTClient for installation instructions and code improvements * feat: 支持local_config启动 add: 增加对crt path的说明,为传入config.py的相对路径 move: web component * add: registry description * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * feat: node_info_update srv fix: OTDeck cant create * close #12 feat: slave node registry * feat: show machine name fix: host node registry not uploaded * feat: add hplc registry * feat: add hplc registry * fix: hplc status typo * fix: devices/ * 完成启动OT并联动rviz * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * 完成启动OT并联动rviz * fix: device.class possible null * fix: HPLC additions with online service * fix: slave mode spin not working * fix: slave mode spin not working * 修复rviz位置问题, 修复rviz位置问题, 在无tf变动时减缓发送频率 在backend中添加物料跟随方法 * feat: 多ProtocolNode 允许子设备ID相同 feat: 上报发现的ActionClient feat: Host重启动,通过discover机制要求slaveNode重新注册,实现信息及时上报 * feat: 支持env设置config * fix: running logic * fix: running logic * fix: missing ot * 在main中直接初始化republisher和物料的mesh节点 * 将joint_republisher和resource_mesh_manager添加进 main_slave_run.py中 * Device visualization (#14) * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * 完成启动OT并联动rviz * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * 完成启动OT并联动rviz * 修复rviz位置问题, 修复rviz位置问题, 在无tf变动时减缓发送频率 在backend中添加物料跟随方法 * fix: running logic * fix: running logic * fix: missing ot * 在main中直接初始化republisher和物料的mesh节点 * 将joint_republisher和resource_mesh_manager添加进 main_slave_run.py中 --------- Co-authored-by: zhangshixiang <@zhangshixiang> Co-authored-by: wznln <18435084+Xuwznln@users.noreply.github.com> * fix: missing hostname in devices_names fix: upload_file for model file * fix: missing paho-mqtt package bump version to 0.9.0 * fix startup add ResourceCreateFromOuter.action * fix type hint * update actions * update actions * host node add_resource_from_outer fix cmake list * pass device config to device class * add: bind_parent_ids to resource create action fix: message convert string * fix: host node should not be re_discovered * feat: resource tracker support dict * feat: add more necessary params * feat: fix boolean null in registry action data * feat: add outer resource * 编写mesh添加action * feat: append resource * add action * feat: vis 2d for plr * fix * fix: browser on rviz * fix: cloud bridge error fallback to local * fix: salve auto run rviz * 初始化两个plate * Device visualization (#22) * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * 完成启动OT并联动rviz * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * 完成启动OT并联动rviz * 修复rviz位置问题, 修复rviz位置问题, 在无tf变动时减缓发送频率 在backend中添加物料跟随方法 * fix: running logic * fix: running logic * fix: missing ot * 在main中直接初始化republisher和物料的mesh节点 * 将joint_republisher和resource_mesh_manager添加进 main_slave_run.py中 * 编写mesh添加action * add action * fix * fix: browser on rviz * fix: cloud bridge error fallback to local * fix: salve auto run rviz * 初始化两个plate --------- Co-authored-by: zhangshixiang <@zhangshixiang> Co-authored-by: wznln <18435084+Xuwznln@users.noreply.github.com> * fix: multi channel * fix: aspirate * fix: aspirate * fix: aspirate * fix: aspirate * 提交 * fix: jobadd * fix: jobadd * fix: msg converter * tijiao * add resource creat easy action * identify debug msg * mq client id --------- Co-authored-by: Harvey Que <Q-Query@outlook.com> Co-authored-by: zhangshixiang <@zhangshixiang> Co-authored-by: q434343 <73513873+q434343@users.noreply.github.com> * remove default behavior for visualization * change liquidhandler name * resource create from outer easy * add easy resource creation * easy resource creation logic * remove wrongly debug msg from others * remove wrongly debug msg from others * add missing action clients * fix device_id * fix slot_on_deck * fix registry typo * complete require packages msg converter support array string implements create resource logic * 修复port输入 * fix: remove dirty actions --------- Co-authored-by: Junhan Chang <changjh@pku.edu.cn> Co-authored-by: Harvey Que <Q-Query@outlook.com> Co-authored-by: q434343 <73513873+q434343@users.noreply.github.com>
This commit is contained in:
@@ -348,10 +348,16 @@ def convert_to_ros_msg(ros_msg_type: Union[Type, Any], obj: Any) -> Any:
|
||||
if isinstance(td, NamespacedType):
|
||||
target_class = msg_converter_manager.get_class(f"{'.'.join(td.namespaces)}.{td.name}")
|
||||
setattr(ros_msg, key, [convert_to_ros_msg(target_class, v) for v in value])
|
||||
elif isinstance(td, UnboundedString):
|
||||
setattr(ros_msg, key, value)
|
||||
else:
|
||||
logger.warning(f"Not Supported type: {td}")
|
||||
setattr(ros_msg, key, []) # FIXME
|
||||
elif "array.array" in str(type(attr)):
|
||||
setattr(ros_msg, key, value)
|
||||
if attr.typecode == "f":
|
||||
setattr(ros_msg, key, [float(i) for i in value])
|
||||
else:
|
||||
setattr(ros_msg, key, value)
|
||||
else:
|
||||
nested_ros_msg = convert_to_ros_msg(type(attr)(), value)
|
||||
setattr(ros_msg, key, nested_ros_msg)
|
||||
@@ -574,6 +580,7 @@ basic_type_map = {
|
||||
'int64': {'type': 'integer'},
|
||||
'uint64': {'type': 'integer', 'minimum': 0},
|
||||
'double': {'type': 'number'},
|
||||
'float': {'type': 'number'},
|
||||
'float32': {'type': 'number'},
|
||||
'float64': {'type': 'number'},
|
||||
'string': {'type': 'string'},
|
||||
|
||||
@@ -1,3 +1,4 @@
|
||||
import copy
|
||||
import functools
|
||||
import json
|
||||
import threading
|
||||
@@ -20,7 +21,7 @@ from unilabos_msgs.action import SendCmd
|
||||
from unilabos_msgs.srv._serial_command import SerialCommand_Request, SerialCommand_Response
|
||||
|
||||
from unilabos.resources.graphio import convert_resources_to_type, convert_resources_from_type, resource_ulab_to_plr, \
|
||||
initialize_resources
|
||||
initialize_resources, list_to_nested_dict, dict_to_tree, resource_plr_to_ulab, tree_to_list
|
||||
from unilabos.ros.msgs.message_converter import (
|
||||
convert_to_ros_msg,
|
||||
convert_from_ros_msg,
|
||||
@@ -312,7 +313,10 @@ class BaseROS2DeviceNode(Node, Generic[T]):
|
||||
# 物料传输到对应的node节点
|
||||
rclient = self.create_client(ResourceAdd, "/resources/add")
|
||||
rclient.wait_for_service()
|
||||
rclient2 = self.create_client(ResourceAdd, "/resources/add")
|
||||
rclient2.wait_for_service()
|
||||
request = ResourceAdd.Request()
|
||||
request2 = ResourceAdd.Request()
|
||||
command_json = json.loads(req.command)
|
||||
namespace = command_json["namespace"]
|
||||
bind_parent_id = command_json["bind_parent_id"]
|
||||
@@ -321,11 +325,23 @@ class BaseROS2DeviceNode(Node, Generic[T]):
|
||||
other_calling_param = command_json["other_calling_param"]
|
||||
resources = command_json["resource"]
|
||||
initialize_full = other_calling_param.pop("initialize_full", False)
|
||||
# 用来增加液体
|
||||
ADD_LIQUID_TYPE = other_calling_param.pop("ADD_LIQUID_TYPE", [])
|
||||
LIQUID_VOLUME = other_calling_param.pop("LIQUID_VOLUME", [])
|
||||
LIQUID_INPUT_SLOT = other_calling_param.pop("LIQUID_INPUT_SLOT", [])
|
||||
slot = other_calling_param.pop("slot", -1)
|
||||
if slot >= 0: # slot为负数的时候采用assign方法
|
||||
other_calling_param["slot"] = slot
|
||||
# 本地拿到这个物料,可能需要先做初始化?
|
||||
if isinstance(resources, list):
|
||||
if initialize_full:
|
||||
if len(resources) == 1 and isinstance(resources[0], list) and not initialize_full: # 取消,不存在的情况
|
||||
# 预先initialize过,以整组的形式传入
|
||||
request.resources = [convert_to_ros_msg(Resource, resource_) for resource_ in resources[0]]
|
||||
elif initialize_full:
|
||||
resources = initialize_resources(resources)
|
||||
request.resources = [convert_to_ros_msg(Resource, resource) for resource in resources]
|
||||
request.resources = [convert_to_ros_msg(Resource, resource) for resource in resources]
|
||||
else:
|
||||
request.resources = [convert_to_ros_msg(Resource, resource) for resource in resources]
|
||||
else:
|
||||
if initialize_full:
|
||||
resources = initialize_resources([resources])
|
||||
@@ -335,20 +351,31 @@ class BaseROS2DeviceNode(Node, Generic[T]):
|
||||
res.response = "OK"
|
||||
# 接下来该根据bind_parent_id进行assign了,目前只有plr可以进行assign,不然没有办法输入到物料系统中
|
||||
resource = self.resource_tracker.figure_resource({"name": bind_parent_id})
|
||||
request.resources = [convert_to_ros_msg(Resource, resources)]
|
||||
# request.resources = [convert_to_ros_msg(Resource, resources)]
|
||||
|
||||
try:
|
||||
from pylabrobot.resources.resource import Resource as ResourcePLR
|
||||
from pylabrobot.resources.deck import Deck
|
||||
from pylabrobot.resources import Coordinate
|
||||
from pylabrobot.resources import OTDeck
|
||||
from pylabrobot.resources import Plate
|
||||
contain_model = not isinstance(resource, Deck)
|
||||
if isinstance(resource, ResourcePLR):
|
||||
# resources.list()
|
||||
plr_instance = resource_ulab_to_plr(resources, contain_model)
|
||||
resources_tree = dict_to_tree(copy.deepcopy({r["id"]: r for r in resources}))
|
||||
plr_instance = resource_ulab_to_plr(resources_tree[0], contain_model)
|
||||
if isinstance(plr_instance, Plate):
|
||||
empty_liquid_info_in = [(None, 0)] * plr_instance.num_items
|
||||
for liquid_type, liquid_volume, liquid_input_slot in zip(ADD_LIQUID_TYPE, LIQUID_VOLUME, LIQUID_INPUT_SLOT):
|
||||
empty_liquid_info_in[liquid_input_slot] = (liquid_type, liquid_volume)
|
||||
plr_instance.set_well_liquids(empty_liquid_info_in)
|
||||
if isinstance(resource, OTDeck) and "slot" in other_calling_param:
|
||||
resource.assign_child_at_slot(plr_instance, **other_calling_param)
|
||||
resource.assign_child_resource(plr_instance, Coordinate(location["x"], location["y"], location["z"]), **other_calling_param)
|
||||
else:
|
||||
_discard_slot = other_calling_param.pop("slot", -1)
|
||||
resource.assign_child_resource(plr_instance, Coordinate(location["x"], location["y"], location["z"]), **other_calling_param)
|
||||
request2.resources = [convert_to_ros_msg(Resource, r) for r in tree_to_list([resource_plr_to_ulab(resource)])]
|
||||
rclient2.call(request2)
|
||||
# 发送给ResourceMeshManager
|
||||
action_client = ActionClient(
|
||||
self, SendCmd, "/devices/resource_mesh_manager/add_resource_mesh", callback_group=self.callback_group
|
||||
@@ -526,7 +553,7 @@ class BaseROS2DeviceNode(Node, Generic[T]):
|
||||
action_kwargs = convert_from_ros_msg_with_mapping(goal, action_value_mapping["goal"])
|
||||
self.lab_logger().debug(f"接收到原始目标: {action_kwargs}")
|
||||
# 向Host查询物料当前状态,如果是host本身的增加物料的请求,则直接跳过
|
||||
if action_name != "add_resource_from_outer":
|
||||
if action_name not in ["create_resource_detailed", "create_resource"]:
|
||||
for k, v in goal.get_fields_and_field_types().items():
|
||||
if v in ["unilabos_msgs/Resource", "sequence<unilabos_msgs/Resource>"]:
|
||||
self.lab_logger().info(f"查询资源状态: Key: {k} Type: {v}")
|
||||
@@ -625,7 +652,7 @@ class BaseROS2DeviceNode(Node, Generic[T]):
|
||||
del future
|
||||
|
||||
# 向Host更新物料当前状态
|
||||
if action_name != "add_resource_from_outer":
|
||||
if action_name not in ["create_resource_detailed", "create_resource"]:
|
||||
for k, v in goal.get_fields_and_field_types().items():
|
||||
if v not in ["unilabos_msgs/Resource", "sequence<unilabos_msgs/Resource>"]:
|
||||
continue
|
||||
@@ -764,7 +791,7 @@ class ROS2DeviceNode:
|
||||
self.resource_tracker = DeviceNodeResourceTracker()
|
||||
|
||||
# use_pylabrobot_creator 使用 cls的包路径检测
|
||||
use_pylabrobot_creator = driver_class.__module__.startswith("pylabrobot") or driver_class.__name__ == "DPLiquidHandler"
|
||||
use_pylabrobot_creator = driver_class.__module__.startswith("pylabrobot") or driver_class.__name__ == "LiquidHandlerAbstract"
|
||||
|
||||
# TODO: 要在创建之前预先请求服务器是否有当前id的物料,放到resource_tracker中,让pylabrobot进行创建
|
||||
# 创建设备类实例
|
||||
|
||||
@@ -17,6 +17,7 @@ from unilabos_msgs.srv import ResourceAdd, ResourceGet, ResourceDelete, Resource
|
||||
from unique_identifier_msgs.msg import UUID
|
||||
|
||||
from unilabos.registry.registry import lab_registry
|
||||
from unilabos.resources.graphio import initialize_resource
|
||||
from unilabos.resources.registry import add_schema
|
||||
from unilabos.ros.initialize_device import initialize_device_from_dict
|
||||
from unilabos.ros.msgs.message_converter import (
|
||||
@@ -100,7 +101,14 @@ class HostNode(BaseROS2DeviceNode):
|
||||
self.devices_names: Dict[str, str] = {device_id: self.namespace} # 存储设备名称和命名空间的映射
|
||||
self.devices_instances: Dict[str, ROS2DeviceNode] = {} # 存储设备实例
|
||||
self.device_machine_names: Dict[str, str] = {device_id: "本地", } # 存储设备ID到机器名称的映射
|
||||
self._action_clients: Dict[str, ActionClient] = {} # 用来存储多个ActionClient实例
|
||||
self._action_clients: Dict[str, ActionClient] = { # 为了方便了解实际的数据类型,host的默认写好
|
||||
"/devices/host_node/create_resource": ActionClient(
|
||||
self, lab_registry.ResourceCreateFromOuterEasy, "/devices/host_node/create_resource", callback_group=self.callback_group
|
||||
),
|
||||
"/devices/host_node/create_resource_detailed": ActionClient(
|
||||
self, lab_registry.ResourceCreateFromOuter, "/devices/host_node/create_resource_detailed", callback_group=self.callback_group
|
||||
)
|
||||
} # 用来存储多个ActionClient实例
|
||||
self._action_value_mappings: Dict[str, Dict] = {} # 用来存储多个ActionClient的type, goal, feedback, result的变量名映射关系
|
||||
self._goals: Dict[str, Any] = {} # 用来存储多个目标的状态
|
||||
self._online_devices: Set[str] = {f"{self.namespace}/{device_id}"} # 用于跟踪在线设备
|
||||
@@ -141,6 +149,21 @@ class HostNode(BaseROS2DeviceNode):
|
||||
].items():
|
||||
controller_config["update_rate"] = update_rate
|
||||
self.initialize_controller(controller_id, controller_config)
|
||||
resources_config.insert(0, {
|
||||
"id": "host_node",
|
||||
"name": "host_node",
|
||||
"parent": None,
|
||||
"type": "device",
|
||||
"class": "host_node",
|
||||
"position": {
|
||||
"x": 0,
|
||||
"y": 0,
|
||||
"z": 0
|
||||
},
|
||||
"config": {},
|
||||
"data": {},
|
||||
"children": []
|
||||
})
|
||||
resource_with_parent_name = []
|
||||
resource_ids_to_instance = {i["id"]: i for i in resources_config}
|
||||
for res in resources_config:
|
||||
@@ -278,7 +301,7 @@ class HostNode(BaseROS2DeviceNode):
|
||||
except Exception as e:
|
||||
self.lab_logger().error(f"[Host Node] Failed to create ActionClient for {action_id}: {str(e)}")
|
||||
|
||||
def add_resource_from_outer(self, resources: list["Resource"], device_ids: list[str], bind_parent_ids: list[str], bind_locations: list[Point], other_calling_params: list[str]):
|
||||
def create_resource_detailed(self, resources: list["Resource"], device_ids: list[str], bind_parent_ids: list[str], bind_locations: list[Point], other_calling_params: list[str]):
|
||||
for resource, device_id, bind_parent_id, bind_location, other_calling_param in zip(resources, device_ids, bind_parent_ids, bind_locations, other_calling_params):
|
||||
# 这里要求device_id传入必须是edge_device_id
|
||||
namespace = "/devices/" + device_id
|
||||
@@ -287,7 +310,7 @@ class HostNode(BaseROS2DeviceNode):
|
||||
sclient.wait_for_service()
|
||||
request = SerialCommand.Request()
|
||||
request.command = json.dumps({
|
||||
"resource": resource,
|
||||
"resource": resource, # 单个/单组 可为 list[list[Resource]]
|
||||
"namespace": namespace,
|
||||
"edge_device_id": device_id,
|
||||
"bind_parent_id": bind_parent_id,
|
||||
@@ -302,6 +325,31 @@ class HostNode(BaseROS2DeviceNode):
|
||||
pass
|
||||
pass
|
||||
|
||||
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: int):
|
||||
init_new_res = initialize_resource({
|
||||
"name": res_id,
|
||||
"class": class_name,
|
||||
"parent": parent,
|
||||
"position": {
|
||||
"x": bind_locations.x,
|
||||
"y": bind_locations.y,
|
||||
"z": bind_locations.z,
|
||||
}
|
||||
}) # flatten的格式
|
||||
resources = [init_new_res]
|
||||
device_id = [device_id]
|
||||
bind_parent_id = [parent]
|
||||
bind_location = [bind_locations]
|
||||
other_calling_param = [json.dumps({
|
||||
"ADD_LIQUID_TYPE": liquid_type,
|
||||
"LIQUID_VOLUME": liquid_volume,
|
||||
"LIQUID_INPUT_SLOT": liquid_input_slot,
|
||||
"initialize_full": False,
|
||||
"slot": slot_on_deck
|
||||
})]
|
||||
|
||||
return self.create_resource_detailed(resources, device_id, bind_parent_id, bind_location, other_calling_param)
|
||||
|
||||
def initialize_device(self, device_id: str, device_config: Dict[str, Any]) -> None:
|
||||
"""
|
||||
根据配置初始化设备,
|
||||
|
||||
Reference in New Issue
Block a user