From 279c5ed5199c23dcb1749b665d8f5cb52754b287 Mon Sep 17 00:00:00 2001 From: zhangshixiang <@zhangshixiang> Date: Thu, 24 Apr 2025 00:59:43 +0800 Subject: [PATCH] =?UTF-8?q?=E5=AE=8C=E6=88=90=E5=9C=A8main=E4=B8=AD?= =?UTF-8?q?=E5=90=AF=E5=8A=A8=E8=AE=BE=E5=A4=87=E5=8F=AF=E8=A7=86=E5=8C=96?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 --- test/experiments/test.json | 2 +- unilabos/app/main.py | 16 +- .../joint_config.json | 0 .../macro_device.xacro | 20 +- .../opentrons_liquid_handler/meshes/ot2-0.fbx | Bin .../opentrons_liquid_handler/meshes/ot2-0.stl | Bin .../opentrons_liquid_handler/meshes/ot2-1.fbx | Bin .../opentrons_liquid_handler/meshes/ot2-1.stl | Bin .../opentrons_liquid_handler/meshes/ot2-2.fbx | Bin .../opentrons_liquid_handler/meshes/ot2-2.stl | Bin .../meshes/ot2-3a.fbx | Bin .../meshes/ot2-3a.stl | Bin .../meshes/ot2-3b.fbx | Bin .../meshes/ot2-3b.stl | Bin .../param_config.json | 0 .../slide_w140/joint_config.json | 0 .../slide_w140/macro_device.xacro | 16 +- .../slide_w140/meshes/base_link.STL | Bin .../slide_w140/meshes/base_link.fbx | Bin .../slide_w140/meshes/length.STL | Bin .../slide_w140/meshes/length.fbx | Bin .../slide_w140/meshes/slide_end.STL | Bin .../slide_w140/meshes/slide_end.fbx | Bin .../slide_w140/meshes/slider.STL | Bin .../slide_w140/meshes/slider.fbx | Bin .../slide_w140/param_config.json | 0 unilabos/device_mesh/resource_visalization.py | 47 +- .../generic_labware_tube_10_75/0_base.png | Bin .../meshes/0_base.glb | Bin .../meshes/0_base.stl | Bin .../generic_labware_tube_10_75/meta.json | 0 .../generic_labware_tube_10_75/modal.xacro | 0 .../tecan_nested_tip_rack/meshes/plate.glb | Bin .../tecan_nested_tip_rack/meshes/plate.stl | Bin .../tecan_nested_tip_rack/meta.json | 0 .../tecan_nested_tip_rack/modal.xacro | 0 .../tecan_nested_tip_rack/plate.png | Bin .../devices/ros_dev/resource_mesh_manager.py | 4612 +++++++++++++++++ unilabos/registry/devices/robot_gripper.yaml | 4 +- .../registry/resources/opentrons/plates.yaml | 4 +- 40 files changed, 4678 insertions(+), 43 deletions(-) rename unilabos/device_mesh/{device => devices}/opentrons_liquid_handler/joint_config.json (100%) rename unilabos/device_mesh/{device => devices}/opentrons_liquid_handler/macro_device.xacro (89%) rename unilabos/device_mesh/{device => devices}/opentrons_liquid_handler/meshes/ot2-0.fbx (100%) rename unilabos/device_mesh/{device => devices}/opentrons_liquid_handler/meshes/ot2-0.stl (100%) rename unilabos/device_mesh/{device => devices}/opentrons_liquid_handler/meshes/ot2-1.fbx (100%) rename unilabos/device_mesh/{device => devices}/opentrons_liquid_handler/meshes/ot2-1.stl (100%) rename unilabos/device_mesh/{device => devices}/opentrons_liquid_handler/meshes/ot2-2.fbx (100%) rename unilabos/device_mesh/{device => devices}/opentrons_liquid_handler/meshes/ot2-2.stl (100%) rename unilabos/device_mesh/{device => devices}/opentrons_liquid_handler/meshes/ot2-3a.fbx (100%) rename unilabos/device_mesh/{device => devices}/opentrons_liquid_handler/meshes/ot2-3a.stl (100%) rename unilabos/device_mesh/{device => devices}/opentrons_liquid_handler/meshes/ot2-3b.fbx (100%) rename unilabos/device_mesh/{device => devices}/opentrons_liquid_handler/meshes/ot2-3b.stl (100%) rename unilabos/device_mesh/{device => devices}/opentrons_liquid_handler/param_config.json (100%) rename unilabos/device_mesh/{device => devices}/slide_w140/joint_config.json (100%) rename unilabos/device_mesh/{device => devices}/slide_w140/macro_device.xacro (86%) rename unilabos/device_mesh/{device => devices}/slide_w140/meshes/base_link.STL (100%) rename unilabos/device_mesh/{device => devices}/slide_w140/meshes/base_link.fbx (100%) rename unilabos/device_mesh/{device => devices}/slide_w140/meshes/length.STL (100%) rename unilabos/device_mesh/{device => devices}/slide_w140/meshes/length.fbx (100%) rename unilabos/device_mesh/{device => devices}/slide_w140/meshes/slide_end.STL (100%) rename unilabos/device_mesh/{device => devices}/slide_w140/meshes/slide_end.fbx (100%) rename unilabos/device_mesh/{device => devices}/slide_w140/meshes/slider.STL (100%) rename unilabos/device_mesh/{device => devices}/slide_w140/meshes/slider.fbx (100%) rename unilabos/device_mesh/{device => devices}/slide_w140/param_config.json (100%) rename unilabos/device_mesh/{resource => resources}/generic_labware_tube_10_75/0_base.png (100%) rename unilabos/device_mesh/{resource => resources}/generic_labware_tube_10_75/meshes/0_base.glb (100%) rename unilabos/device_mesh/{resource => resources}/generic_labware_tube_10_75/meshes/0_base.stl (100%) rename unilabos/device_mesh/{resource => resources}/generic_labware_tube_10_75/meta.json (100%) rename unilabos/device_mesh/{resource => resources}/generic_labware_tube_10_75/modal.xacro (100%) rename unilabos/device_mesh/{resource => resources}/tecan_nested_tip_rack/meshes/plate.glb (100%) rename unilabos/device_mesh/{resource => resources}/tecan_nested_tip_rack/meshes/plate.stl (100%) rename unilabos/device_mesh/{resource => resources}/tecan_nested_tip_rack/meta.json (100%) rename unilabos/device_mesh/{resource => resources}/tecan_nested_tip_rack/modal.xacro (100%) rename unilabos/device_mesh/{resource => resources}/tecan_nested_tip_rack/plate.png (100%) create mode 100644 unilabos/devices/ros_dev/resource_mesh_manager.py diff --git a/test/experiments/test.json b/test/experiments/test.json index 07b802cd..a07592c2 100644 --- a/test/experiments/test.json +++ b/test/experiments/test.json @@ -25,7 +25,7 @@ ], "parent": null, "type": "plate", - "class": "nest_96_wellplate_2ml_deep", + "class": "nest_96_wellplate_100ul_pcr_full_skirt", "position": { "x": 620.6111111111111, "y": 171, diff --git a/unilabos/app/main.py b/unilabos/app/main.py index d418c5c1..8ec45f38 100644 --- a/unilabos/app/main.py +++ b/unilabos/app/main.py @@ -5,6 +5,7 @@ import sys import json import yaml from copy import deepcopy +import threading # 首先添加项目根目录到路径 current_dir = os.path.dirname(os.path.abspath(__file__)) @@ -14,7 +15,7 @@ if ilabos_dir not in sys.path: from unilabos.config.config import load_config, BasicConfig from unilabos.utils.banner_print import print_status, print_unilab_banner - +from unilabos.device_mesh.resource_visalization import ResourceVisualization def parse_args(): """解析命令行参数""" @@ -102,7 +103,8 @@ def main(): print_unilab_banner(args_dict) # 注册表 - build_registry(args_dict["registry_path"]) + registry_dict = build_registry(args_dict["registry_path"]) + if args_dict["graph"] is not None: import unilabos.resources.graphio as graph_res @@ -150,8 +152,16 @@ def main(): signal.signal(signal.SIGTERM, _exit) mqtt_client.start() + resource_visualization = ResourceVisualization(args_dict["devices_config"], args_dict["resources_config"],registry_dict) start_backend(**args_dict) - start_server() + print('-'*100) + print(resource_visualization.resource_model) + print(json.dumps(args_dict["resources_config"], indent=4, ensure_ascii=False)) + print('-'*100) + server_thread = threading.Thread(target=start_server) + server_thread.start() + + resource_visualization.start() if __name__ == "__main__": diff --git a/unilabos/device_mesh/device/opentrons_liquid_handler/joint_config.json b/unilabos/device_mesh/devices/opentrons_liquid_handler/joint_config.json similarity index 100% rename from unilabos/device_mesh/device/opentrons_liquid_handler/joint_config.json rename to unilabos/device_mesh/devices/opentrons_liquid_handler/joint_config.json diff --git a/unilabos/device_mesh/device/opentrons_liquid_handler/macro_device.xacro b/unilabos/device_mesh/devices/opentrons_liquid_handler/macro_device.xacro similarity index 89% rename from unilabos/device_mesh/device/opentrons_liquid_handler/macro_device.xacro rename to unilabos/device_mesh/devices/opentrons_liquid_handler/macro_device.xacro index 7431c20b..5dc945ba 100644 --- a/unilabos/device_mesh/device/opentrons_liquid_handler/macro_device.xacro +++ b/unilabos/device_mesh/devices/opentrons_liquid_handler/macro_device.xacro @@ -24,7 +24,7 @@ - + @@ -33,7 +33,7 @@ - + @@ -41,7 +41,7 @@ - + @@ -50,7 +50,7 @@ - + @@ -58,7 +58,7 @@ - + @@ -67,7 +67,7 @@ - + @@ -75,7 +75,7 @@ - + @@ -84,7 +84,7 @@ - + @@ -92,7 +92,7 @@ - + @@ -101,7 +101,7 @@ - + diff --git a/unilabos/device_mesh/device/opentrons_liquid_handler/meshes/ot2-0.fbx b/unilabos/device_mesh/devices/opentrons_liquid_handler/meshes/ot2-0.fbx similarity index 100% rename from unilabos/device_mesh/device/opentrons_liquid_handler/meshes/ot2-0.fbx rename to unilabos/device_mesh/devices/opentrons_liquid_handler/meshes/ot2-0.fbx diff --git a/unilabos/device_mesh/device/opentrons_liquid_handler/meshes/ot2-0.stl b/unilabos/device_mesh/devices/opentrons_liquid_handler/meshes/ot2-0.stl similarity index 100% rename from unilabos/device_mesh/device/opentrons_liquid_handler/meshes/ot2-0.stl rename to unilabos/device_mesh/devices/opentrons_liquid_handler/meshes/ot2-0.stl diff --git a/unilabos/device_mesh/device/opentrons_liquid_handler/meshes/ot2-1.fbx b/unilabos/device_mesh/devices/opentrons_liquid_handler/meshes/ot2-1.fbx similarity index 100% rename from unilabos/device_mesh/device/opentrons_liquid_handler/meshes/ot2-1.fbx rename to unilabos/device_mesh/devices/opentrons_liquid_handler/meshes/ot2-1.fbx diff --git a/unilabos/device_mesh/device/opentrons_liquid_handler/meshes/ot2-1.stl b/unilabos/device_mesh/devices/opentrons_liquid_handler/meshes/ot2-1.stl similarity index 100% rename from unilabos/device_mesh/device/opentrons_liquid_handler/meshes/ot2-1.stl rename to unilabos/device_mesh/devices/opentrons_liquid_handler/meshes/ot2-1.stl diff --git a/unilabos/device_mesh/device/opentrons_liquid_handler/meshes/ot2-2.fbx b/unilabos/device_mesh/devices/opentrons_liquid_handler/meshes/ot2-2.fbx similarity index 100% rename from unilabos/device_mesh/device/opentrons_liquid_handler/meshes/ot2-2.fbx rename to unilabos/device_mesh/devices/opentrons_liquid_handler/meshes/ot2-2.fbx diff --git a/unilabos/device_mesh/device/opentrons_liquid_handler/meshes/ot2-2.stl b/unilabos/device_mesh/devices/opentrons_liquid_handler/meshes/ot2-2.stl similarity index 100% rename from unilabos/device_mesh/device/opentrons_liquid_handler/meshes/ot2-2.stl rename to unilabos/device_mesh/devices/opentrons_liquid_handler/meshes/ot2-2.stl diff --git a/unilabos/device_mesh/device/opentrons_liquid_handler/meshes/ot2-3a.fbx b/unilabos/device_mesh/devices/opentrons_liquid_handler/meshes/ot2-3a.fbx similarity index 100% rename from unilabos/device_mesh/device/opentrons_liquid_handler/meshes/ot2-3a.fbx rename to unilabos/device_mesh/devices/opentrons_liquid_handler/meshes/ot2-3a.fbx diff --git a/unilabos/device_mesh/device/opentrons_liquid_handler/meshes/ot2-3a.stl b/unilabos/device_mesh/devices/opentrons_liquid_handler/meshes/ot2-3a.stl similarity index 100% rename from unilabos/device_mesh/device/opentrons_liquid_handler/meshes/ot2-3a.stl rename to unilabos/device_mesh/devices/opentrons_liquid_handler/meshes/ot2-3a.stl diff --git a/unilabos/device_mesh/device/opentrons_liquid_handler/meshes/ot2-3b.fbx b/unilabos/device_mesh/devices/opentrons_liquid_handler/meshes/ot2-3b.fbx similarity index 100% rename from unilabos/device_mesh/device/opentrons_liquid_handler/meshes/ot2-3b.fbx rename to unilabos/device_mesh/devices/opentrons_liquid_handler/meshes/ot2-3b.fbx diff --git a/unilabos/device_mesh/device/opentrons_liquid_handler/meshes/ot2-3b.stl b/unilabos/device_mesh/devices/opentrons_liquid_handler/meshes/ot2-3b.stl similarity index 100% rename from unilabos/device_mesh/device/opentrons_liquid_handler/meshes/ot2-3b.stl rename to unilabos/device_mesh/devices/opentrons_liquid_handler/meshes/ot2-3b.stl diff --git a/unilabos/device_mesh/device/opentrons_liquid_handler/param_config.json b/unilabos/device_mesh/devices/opentrons_liquid_handler/param_config.json similarity index 100% rename from unilabos/device_mesh/device/opentrons_liquid_handler/param_config.json rename to unilabos/device_mesh/devices/opentrons_liquid_handler/param_config.json diff --git a/unilabos/device_mesh/device/slide_w140/joint_config.json b/unilabos/device_mesh/devices/slide_w140/joint_config.json similarity index 100% rename from unilabos/device_mesh/device/slide_w140/joint_config.json rename to unilabos/device_mesh/devices/slide_w140/joint_config.json diff --git a/unilabos/device_mesh/device/slide_w140/macro_device.xacro b/unilabos/device_mesh/devices/slide_w140/macro_device.xacro similarity index 86% rename from unilabos/device_mesh/device/slide_w140/macro_device.xacro rename to unilabos/device_mesh/devices/slide_w140/macro_device.xacro index ffbc6f79..7e43242e 100644 --- a/unilabos/device_mesh/device/slide_w140/macro_device.xacro +++ b/unilabos/device_mesh/devices/slide_w140/macro_device.xacro @@ -35,7 +35,7 @@ - + @@ -44,7 +44,7 @@ - + @@ -57,7 +57,7 @@ - + @@ -66,7 +66,7 @@ - + @@ -86,7 +86,7 @@ - + @@ -95,7 +95,7 @@ - + @@ -113,7 +113,7 @@ - + @@ -122,7 +122,7 @@ - + diff --git a/unilabos/device_mesh/device/slide_w140/meshes/base_link.STL b/unilabos/device_mesh/devices/slide_w140/meshes/base_link.STL similarity index 100% rename from unilabos/device_mesh/device/slide_w140/meshes/base_link.STL rename to unilabos/device_mesh/devices/slide_w140/meshes/base_link.STL diff --git a/unilabos/device_mesh/device/slide_w140/meshes/base_link.fbx b/unilabos/device_mesh/devices/slide_w140/meshes/base_link.fbx similarity index 100% rename from unilabos/device_mesh/device/slide_w140/meshes/base_link.fbx rename to unilabos/device_mesh/devices/slide_w140/meshes/base_link.fbx diff --git a/unilabos/device_mesh/device/slide_w140/meshes/length.STL b/unilabos/device_mesh/devices/slide_w140/meshes/length.STL similarity index 100% rename from unilabos/device_mesh/device/slide_w140/meshes/length.STL rename to unilabos/device_mesh/devices/slide_w140/meshes/length.STL diff --git a/unilabos/device_mesh/device/slide_w140/meshes/length.fbx b/unilabos/device_mesh/devices/slide_w140/meshes/length.fbx similarity index 100% rename from unilabos/device_mesh/device/slide_w140/meshes/length.fbx rename to unilabos/device_mesh/devices/slide_w140/meshes/length.fbx diff --git a/unilabos/device_mesh/device/slide_w140/meshes/slide_end.STL b/unilabos/device_mesh/devices/slide_w140/meshes/slide_end.STL similarity index 100% rename from unilabos/device_mesh/device/slide_w140/meshes/slide_end.STL rename to unilabos/device_mesh/devices/slide_w140/meshes/slide_end.STL diff --git a/unilabos/device_mesh/device/slide_w140/meshes/slide_end.fbx b/unilabos/device_mesh/devices/slide_w140/meshes/slide_end.fbx similarity index 100% rename from unilabos/device_mesh/device/slide_w140/meshes/slide_end.fbx rename to unilabos/device_mesh/devices/slide_w140/meshes/slide_end.fbx diff --git a/unilabos/device_mesh/device/slide_w140/meshes/slider.STL b/unilabos/device_mesh/devices/slide_w140/meshes/slider.STL similarity index 100% rename from unilabos/device_mesh/device/slide_w140/meshes/slider.STL rename to unilabos/device_mesh/devices/slide_w140/meshes/slider.STL diff --git a/unilabos/device_mesh/device/slide_w140/meshes/slider.fbx b/unilabos/device_mesh/devices/slide_w140/meshes/slider.fbx similarity index 100% rename from unilabos/device_mesh/device/slide_w140/meshes/slider.fbx rename to unilabos/device_mesh/devices/slide_w140/meshes/slider.fbx diff --git a/unilabos/device_mesh/device/slide_w140/param_config.json b/unilabos/device_mesh/devices/slide_w140/param_config.json similarity index 100% rename from unilabos/device_mesh/device/slide_w140/param_config.json rename to unilabos/device_mesh/devices/slide_w140/param_config.json diff --git a/unilabos/device_mesh/resource_visalization.py b/unilabos/device_mesh/resource_visalization.py index d4a1a712..e73a6807 100644 --- a/unilabos/device_mesh/resource_visalization.py +++ b/unilabos/device_mesh/resource_visalization.py @@ -1,3 +1,5 @@ +import os +from pathlib import Path from launch import LaunchService from launch import LaunchDescription from launch_ros.actions import Node as nd @@ -6,19 +8,26 @@ from lxml import etree class ResourceVisualization: - def __init__(self, device: dict, registry: dict, resource: dict, enable_rviz: bool = False): - + def __init__(self, device: dict, resource: dict, registry: dict, enable_rviz: bool = True): """初始化资源可视化类 + 该类用于将设备和资源的3D模型可视化展示。通过解析设备和资源的配置信息, + 从注册表中获取对应的3D模型文件,并使用ROS2和RViz进行可视化。 + Args: - device: 设备配置字典 - registry: 注册表字典 + device (dict): 设备配置字典,包含设备的类型、位置等信息 + resource (dict): 资源配置字典,包含资源的类型、位置等信息 + registry (dict): 注册表字典,包含设备和资源类型的注册信息 + enable_rviz (bool, optional): 是否启用RViz可视化. Defaults to True. """ self.launch_service = LaunchService() self.launch_description = LaunchDescription() self.resource_dict = resource self.resource_model = {} self.resource_type = ['plate', 'container'] + self.mesh_path = Path(__file__).parent.absolute() + self.enable_rviz = enable_rviz + self.robot_state_str= ''' @@ -28,8 +37,9 @@ class ResourceVisualization: self.root = etree.fromstring(self.robot_state_str) xacro_uri = self.root.nsmap["xacro"] + # 遍历设备节点 - for node in device['nodes']: + for node in device.values(): if node['type'] == 'device': device_class = node['class'] @@ -37,37 +47,40 @@ class ResourceVisualization: if device_class not in registry.device_type_registry.keys(): raise ValueError(f"设备类型 {device_class} 未在注册表中注册") - elif "model" in device_class.keys(): + elif "model" in registry.device_type_registry[device_class].keys(): model_config = registry.device_type_registry[device_class]['model'] if model_config['type'] == 'device': new_include = etree.SubElement(self.root, f"{{{xacro_uri}}}include") - new_include.set("filename", f"{model_config['mesh']}/macro_device.xacro") + new_include.set("filename", f"{str(self.mesh_path)}/devices/{model_config['mesh']}/macro_device.xacro") new_dev = etree.SubElement(self.root, f"{{{xacro_uri}}}{model_config['mesh']}") new_dev.set("parent_link", "world") + new_dev.set("mesh_path", str(self.mesh_path)) elif node['type'] in self.resource_type: + # print(registry.resource_type_registry) resource_class = node['class'] if resource_class not in registry.resource_type_registry.keys(): raise ValueError(f"资源类型 {resource_class} 未在注册表中注册") - if model_config['type'] == 'resource': + elif "model" in registry.resource_type_registry[resource_class].keys(): model_config = registry.resource_type_registry[resource_class]['model'] - self.resource_model[node['id']] = model_config['mesh'] - if model_config['children_mesh'] is not None: - self.resource_model[f"{node['id']}_"] = model_config['children_mesh'] - + if model_config['type'] == 'resource': + self.resource_model[node['id']] = f"{str(self.mesh_path)}/resources/{model_config['mesh']}" + if model_config['children_mesh'] is not None: + self.resource_model[f"{node['id']}_"] = f"{str(self.mesh_path)}/resources/{model_config['children_mesh']}" + re = etree.tostring(self.root, encoding="unicode") doc = xacro.parse(re) xacro.process_doc(doc) + self.urdf_str = doc.toxml() - def create_launch_description(self, urdf_str: str, enable_rviz: bool = False) -> LaunchDescription: + def create_launch_description(self, urdf_str: str) -> LaunchDescription: """ 创建launch描述,包含robot_state_publisher和move_group节点 Args: urdf_str: URDF文本 - enable_rviz: 是否启用RViz可视化 Returns: LaunchDescription: launch描述对象 @@ -109,7 +122,7 @@ class ResourceVisualization: self.launch_description.add_action(move_group) # 如果启用RViz,添加RViz节点 - if enable_rviz: + if self.enable_rviz: rviz_node = nd( package='rviz2', executable='rviz2', @@ -120,13 +133,13 @@ class ResourceVisualization: return self.launch_description - def start(self, urdf_str: str) -> None: + def start(self) -> None: """ 启动可视化服务 Args: urdf_str: URDF文件路径 """ - launch_description = self.create_launch_description(urdf_str) + launch_description = self.create_launch_description(self.urdf_str) self.launch_service.include_launch_description(launch_description) self.launch_service.run() \ No newline at end of file diff --git a/unilabos/device_mesh/resource/generic_labware_tube_10_75/0_base.png b/unilabos/device_mesh/resources/generic_labware_tube_10_75/0_base.png similarity index 100% rename from unilabos/device_mesh/resource/generic_labware_tube_10_75/0_base.png rename to unilabos/device_mesh/resources/generic_labware_tube_10_75/0_base.png diff --git a/unilabos/device_mesh/resource/generic_labware_tube_10_75/meshes/0_base.glb b/unilabos/device_mesh/resources/generic_labware_tube_10_75/meshes/0_base.glb similarity index 100% rename from unilabos/device_mesh/resource/generic_labware_tube_10_75/meshes/0_base.glb rename to unilabos/device_mesh/resources/generic_labware_tube_10_75/meshes/0_base.glb diff --git a/unilabos/device_mesh/resource/generic_labware_tube_10_75/meshes/0_base.stl b/unilabos/device_mesh/resources/generic_labware_tube_10_75/meshes/0_base.stl similarity index 100% rename from unilabos/device_mesh/resource/generic_labware_tube_10_75/meshes/0_base.stl rename to unilabos/device_mesh/resources/generic_labware_tube_10_75/meshes/0_base.stl diff --git a/unilabos/device_mesh/resource/generic_labware_tube_10_75/meta.json b/unilabos/device_mesh/resources/generic_labware_tube_10_75/meta.json similarity index 100% rename from unilabos/device_mesh/resource/generic_labware_tube_10_75/meta.json rename to unilabos/device_mesh/resources/generic_labware_tube_10_75/meta.json diff --git a/unilabos/device_mesh/resource/generic_labware_tube_10_75/modal.xacro b/unilabos/device_mesh/resources/generic_labware_tube_10_75/modal.xacro similarity index 100% rename from unilabos/device_mesh/resource/generic_labware_tube_10_75/modal.xacro rename to unilabos/device_mesh/resources/generic_labware_tube_10_75/modal.xacro diff --git a/unilabos/device_mesh/resource/tecan_nested_tip_rack/meshes/plate.glb b/unilabos/device_mesh/resources/tecan_nested_tip_rack/meshes/plate.glb similarity index 100% rename from unilabos/device_mesh/resource/tecan_nested_tip_rack/meshes/plate.glb rename to unilabos/device_mesh/resources/tecan_nested_tip_rack/meshes/plate.glb diff --git a/unilabos/device_mesh/resource/tecan_nested_tip_rack/meshes/plate.stl b/unilabos/device_mesh/resources/tecan_nested_tip_rack/meshes/plate.stl similarity index 100% rename from unilabos/device_mesh/resource/tecan_nested_tip_rack/meshes/plate.stl rename to unilabos/device_mesh/resources/tecan_nested_tip_rack/meshes/plate.stl diff --git a/unilabos/device_mesh/resource/tecan_nested_tip_rack/meta.json b/unilabos/device_mesh/resources/tecan_nested_tip_rack/meta.json similarity index 100% rename from unilabos/device_mesh/resource/tecan_nested_tip_rack/meta.json rename to unilabos/device_mesh/resources/tecan_nested_tip_rack/meta.json diff --git a/unilabos/device_mesh/resource/tecan_nested_tip_rack/modal.xacro b/unilabos/device_mesh/resources/tecan_nested_tip_rack/modal.xacro similarity index 100% rename from unilabos/device_mesh/resource/tecan_nested_tip_rack/modal.xacro rename to unilabos/device_mesh/resources/tecan_nested_tip_rack/modal.xacro diff --git a/unilabos/device_mesh/resource/tecan_nested_tip_rack/plate.png b/unilabos/device_mesh/resources/tecan_nested_tip_rack/plate.png similarity index 100% rename from unilabos/device_mesh/resource/tecan_nested_tip_rack/plate.png rename to unilabos/device_mesh/resources/tecan_nested_tip_rack/plate.png diff --git a/unilabos/devices/ros_dev/resource_mesh_manager.py b/unilabos/devices/ros_dev/resource_mesh_manager.py new file mode 100644 index 00000000..f7e4232f --- /dev/null +++ b/unilabos/devices/ros_dev/resource_mesh_manager.py @@ -0,0 +1,4612 @@ +import time +import rclpy,json +from rclpy.node import Node +from std_msgs.msg import String,Header +import numpy as np +from moveit_msgs.srv import GetPlanningScene, ApplyPlanningScene +from rclpy.callback_groups import ReentrantCallbackGroup +from rclpy.qos import QoSProfile, QoSDurabilityPolicy, QoSReliabilityPolicy, QoSHistoryPolicy +from moveit_msgs.msg import CollisionObject, AttachedCollisionObject, AllowedCollisionEntry +from shape_msgs.msg import Mesh, MeshTriangle, SolidPrimitive +from geometry_msgs.msg import Pose, PoseStamped, Point, Quaternion +from rclpy.callback_groups import ReentrantCallbackGroup +from rclpy.qos import QoSProfile, QoSDurabilityPolicy, QoSReliabilityPolicy, QoSHistoryPolicy +from rclpy.task import Future +import copy +from typing import Tuple, Optional, Union, Any, List + +class ResourceMeshManager(Node): + def __init__(self, resource_model: dict, resource_config: list, node_name: str): + """初始化资源网格管理器节点 + + Args: + resource_model (dict): 资源模型字典,包含资源的3D模型信息 + resource_config (dict): 资源配置字典,包含资源的配置信息 + node_name (str): 节点名称 + """ + super().__init__(node_name) + + self.resource_model = resource_model + self.resource_config = resource_config + self.resource_config_dict = {item['id']: item for item in self.resource_config} + self.move_group_ready = False + self.resource_tf_dict = {} + callback_group = ReentrantCallbackGroup() + self._get_planning_scene_service = self.create_client( + srv_type=GetPlanningScene, + srv_name="get_planning_scene", + qos_profile=QoSProfile( + durability=QoSDurabilityPolicy.VOLATILE, + reliability=QoSReliabilityPolicy.RELIABLE, + history=QoSHistoryPolicy.KEEP_LAST, + depth=1, + ), + callback_group=callback_group, + ) + self.__planning_scene = None + self.__old_planning_scene = None + self.__old_allowed_collision_matrix = None + + # Create a service for applying the planning scene + self._apply_planning_scene_service = self.create_client( + srv_type=ApplyPlanningScene, + srv_name="apply_planning_scene", + qos_profile=QoSProfile( + durability=QoSDurabilityPolicy.VOLATILE, + reliability=QoSReliabilityPolicy.RELIABLE, + history=QoSHistoryPolicy.KEEP_LAST, + depth=1, + ), + callback_group=callback_group, + ) + + self.__collision_object_publisher = self.create_publisher( + CollisionObject, "/collision_object", 10 + ) + self.__attached_collision_object_publisher = self.create_publisher( + AttachedCollisionObject, "/attached_collision_object", 10 + ) + + + """检查move_group节点是否已初始化完成""" + def check_move_group_ready(self): + while not self.move_group_ready: + # 获取当前可用的节点列表 + if self._get_planning_scene_service.service_is_ready() and self._apply_planning_scene_service.service_is_ready(): + self.resource_mesh_setup() + self.move_group_ready = True + + time.sleep(0.5) + + def resource_mesh_setup(self): + """move_group初始化完成后的设置""" + self.get_logger().info('开始设置资源网格管理器') + + #遍历resource_config中的资源配置,判断panent是否在resource_model中, + + for resource_config in self.resource_config: + if resource_config['parent'] in self.resource_model: + # self.resource_tf_dict[resource_config['id']] = resource_config['parent'] + self.resource_tf_dict.update({resource_config['id']:{"parent":resource_config['parent'], + "position":resource_config['position'], + "rotation":resource_config['config']['rotation']}}) + elif resource_config['parent'] is None and resource_config['id'] in self.resource_model: + self.resource_tf_dict.update({resource_config['id']:{'parent':'world', + "position":resource_config['position'], + "rotation":resource_config['config']['rotation']}}) + elif resource_config['parent'] not in self.resource_model and resource_config['parent'] is not None: + self.resource_tf_dict.update({resource_config['id']:{'parent':f"{self.resource_config_dict[resource_config['parent']]['parent']}{resource_config['parent']}_device_link".replace("None",""), + "position":resource_config['position'], + "rotation":resource_config['config']['rotation']}}) + + + + def add_collision_primitive( + self, + id: str, + primitive_type: int, + dimensions: Tuple[float, float, float], + pose: Optional[Union[PoseStamped, Pose]] = None, + position: Optional[Union[Point, Tuple[float, float, float]]] = None, + quat_xyzw: Optional[ + Union[Quaternion, Tuple[float, float, float, float]] + ] = None, + frame_id: Optional[str] = None, + operation: int = CollisionObject.ADD, + ): + """ + Add collision object with a primitive geometry specified by its dimensions. + + `primitive_type` can be one of the following: + - `SolidPrimitive.BOX` + - `SolidPrimitive.SPHERE` + - `SolidPrimitive.CYLINDER` + - `SolidPrimitive.CONE` + """ + + if (pose is None) and (position is None or quat_xyzw is None): + raise ValueError( + "Either `pose` or `position` and `quat_xyzw` must be specified!" + ) + + if isinstance(pose, PoseStamped): + pose_stamped = pose + elif isinstance(pose, Pose): + pose_stamped = PoseStamped( + header=Header( + stamp=self.get_clock().now().to_msg(), + frame_id=( + frame_id if frame_id is not None else self.__base_link_name + ), + ), + pose=pose, + ) + else: + if not isinstance(position, Point): + position = Point( + x=float(position[0]), y=float(position[1]), z=float(position[2]) + ) + if not isinstance(quat_xyzw, Quaternion): + quat_xyzw = Quaternion( + x=float(quat_xyzw[0]), + y=float(quat_xyzw[1]), + z=float(quat_xyzw[2]), + w=float(quat_xyzw[3]), + ) + pose_stamped = PoseStamped( + header=Header( + stamp=self.get_clock().now().to_msg(), + frame_id=( + frame_id if frame_id is not None else self.__base_link_name + ), + ), + pose=Pose(position=position, orientation=quat_xyzw), + ) + + msg = CollisionObject( + header=pose_stamped.header, + id=id, + operation=operation, + pose=pose_stamped.pose, + ) + + msg.primitives.append( + SolidPrimitive(type=primitive_type, dimensions=dimensions) + ) + + self.__collision_object_publisher.publish(msg) + + def add_collision_box( + self, + id: str, + size: Tuple[float, float, float], + pose: Optional[Union[PoseStamped, Pose]] = None, + position: Optional[Union[Point, Tuple[float, float, float]]] = None, + quat_xyzw: Optional[ + Union[Quaternion, Tuple[float, float, float, float]] + ] = None, + frame_id: Optional[str] = None, + operation: int = CollisionObject.ADD, + ): + """ + Add collision object with a box geometry specified by its size. + """ + + assert len(size) == 3, "Invalid size of the box!" + + self.add_collision_primitive( + id=id, + primitive_type=SolidPrimitive.BOX, + dimensions=size, + pose=pose, + position=position, + quat_xyzw=quat_xyzw, + frame_id=frame_id, + operation=operation, + ) + + def add_collision_sphere( + self, + id: str, + radius: float, + pose: Optional[Union[PoseStamped, Pose]] = None, + position: Optional[Union[Point, Tuple[float, float, float]]] = None, + quat_xyzw: Optional[ + Union[Quaternion, Tuple[float, float, float, float]] + ] = None, + frame_id: Optional[str] = None, + operation: int = CollisionObject.ADD, + ): + """ + Add collision object with a sphere geometry specified by its radius. + """ + + if quat_xyzw is None: + quat_xyzw = Quaternion(x=0.0, y=0.0, z=0.0, w=1.0) + + self.add_collision_primitive( + id=id, + primitive_type=SolidPrimitive.SPHERE, + dimensions=[ + radius, + ], + pose=pose, + position=position, + quat_xyzw=quat_xyzw, + frame_id=frame_id, + operation=operation, + ) + + def add_collision_cylinder( + self, + id: str, + height: float, + radius: float, + pose: Optional[Union[PoseStamped, Pose]] = None, + position: Optional[Union[Point, Tuple[float, float, float]]] = None, + quat_xyzw: Optional[ + Union[Quaternion, Tuple[float, float, float, float]] + ] = None, + frame_id: Optional[str] = None, + operation: int = CollisionObject.ADD, + ): + """ + Add collision object with a cylinder geometry specified by its height and radius. + """ + + self.add_collision_primitive( + id=id, + primitive_type=SolidPrimitive.CYLINDER, + dimensions=[height, radius], + pose=pose, + position=position, + quat_xyzw=quat_xyzw, + frame_id=frame_id, + operation=operation, + ) + + def add_collision_cone( + self, + id: str, + height: float, + radius: float, + pose: Optional[Union[PoseStamped, Pose]] = None, + position: Optional[Union[Point, Tuple[float, float, float]]] = None, + quat_xyzw: Optional[ + Union[Quaternion, Tuple[float, float, float, float]] + ] = None, + frame_id: Optional[str] = None, + operation: int = CollisionObject.ADD, + ): + """ + Add collision object with a cone geometry specified by its height and radius. + """ + + self.add_collision_primitive( + id=id, + primitive_type=SolidPrimitive.CONE, + dimensions=[height, radius], + pose=pose, + position=position, + quat_xyzw=quat_xyzw, + frame_id=frame_id, + operation=operation, + ) + + def add_collision_mesh( + self, + filepath: Optional[str], + id: str, + pose: Optional[Union[PoseStamped, Pose]] = None, + position: Optional[Union[Point, Tuple[float, float, float]]] = None, + quat_xyzw: Optional[ + Union[Quaternion, Tuple[float, float, float, float]] + ] = None, + frame_id: Optional[str] = None, + operation: int = CollisionObject.ADD, + scale: Union[float, Tuple[float, float, float]] = 1.0, + mesh: Optional[Any] = None, + ): + """ + Add collision object with a mesh geometry. Either `filepath` must be + specified or `mesh` must be provided. + Note: This function required 'trimesh' Python module to be installed. + """ + + # Load the mesh + try: + import trimesh + except ImportError as err: + raise ImportError( + "Python module 'trimesh' not found! Please install it manually in order " + "to add collision objects into the MoveIt 2 planning scene." + ) from err + + # Check the parameters + if (pose is None) and (position is None or quat_xyzw is None): + raise ValueError( + "Either `pose` or `position` and `quat_xyzw` must be specified!" + ) + if (filepath is None and mesh is None) or ( + filepath is not None and mesh is not None + ): + raise ValueError("Exactly one of `filepath` or `mesh` must be specified!") + if mesh is not None and not isinstance(mesh, trimesh.Trimesh): + raise ValueError("`mesh` must be an instance of `trimesh.Trimesh`!") + + if isinstance(pose, PoseStamped): + pose_stamped = pose + elif isinstance(pose, Pose): + pose_stamped = PoseStamped( + header=Header( + stamp=self.get_clock().now().to_msg(), + frame_id=( + frame_id if frame_id is not None else self.__base_link_name + ), + ), + pose=pose, + ) + else: + if not isinstance(position, Point): + position = Point( + x=float(position[0]), y=float(position[1]), z=float(position[2]) + ) + if not isinstance(quat_xyzw, Quaternion): + quat_xyzw = Quaternion( + x=float(quat_xyzw[0]), + y=float(quat_xyzw[1]), + z=float(quat_xyzw[2]), + w=float(quat_xyzw[3]), + ) + pose_stamped = PoseStamped( + header=Header( + stamp=self.get_clock().now().to_msg(), + frame_id=( + frame_id if frame_id is not None else self.__base_link_name + ), + ), + pose=Pose(position=position, orientation=quat_xyzw), + ) + + msg = CollisionObject( + header=pose_stamped.header, + id=id, + operation=operation, + pose=pose_stamped.pose, + ) + + if filepath is not None: + mesh = trimesh.load(filepath) + + # Scale the mesh + if isinstance(scale, float): + scale = (scale, scale, scale) + if not (scale[0] == scale[1] == scale[2] == 1.0): + # If the mesh was passed in as a parameter, make a copy of it to + # avoid transforming the original. + if filepath is not None: + mesh = mesh.copy() + # Transform the mesh + transform = np.eye(4) + np.fill_diagonal(transform, scale) + mesh.apply_transform(transform) + + msg.meshes.append( + Mesh( + triangles=[MeshTriangle(vertex_indices=face) for face in mesh.faces], + vertices=[ + Point(x=vert[0], y=vert[1], z=vert[2]) for vert in mesh.vertices + ], + ) + ) + + self.__collision_object_publisher.publish(msg) + + def remove_collision_object(self, id: str): + """ + Remove collision object specified by its `id`. + """ + + msg = CollisionObject() + msg.id = id + msg.operation = CollisionObject.REMOVE + msg.header.stamp = self.get_clock().now().to_msg() + self.__collision_object_publisher.publish(msg) + + def remove_collision_mesh(self, id: str): + """ + Remove collision mesh specified by its `id`. + Identical to `remove_collision_object()`. + """ + + self.remove_collision_object(id) + + def attach_collision_object( + self, + id: str, + link_name: Optional[str] = None, + touch_links: List[str] = [], + weight: float = 0.0, + ): + """ + Attach collision object to the robot. + """ + + if link_name is None: + link_name = self.__end_effector_name + + msg = AttachedCollisionObject( + object=CollisionObject(id=id, operation=CollisionObject.ADD) + ) + msg.link_name = link_name + msg.touch_links = touch_links + msg.weight = weight + + self.__attached_collision_object_publisher.publish(msg) + + def detach_collision_object(self, id: int): + """ + Detach collision object from the robot. + """ + + msg = AttachedCollisionObject( + object=CollisionObject(id=id, operation=CollisionObject.REMOVE) + ) + self.__attached_collision_object_publisher.publish(msg) + + def detach_all_collision_objects(self): + """ + Detach collision object from the robot. + """ + + msg = AttachedCollisionObject( + object=CollisionObject(operation=CollisionObject.REMOVE) + ) + self.__attached_collision_object_publisher.publish(msg) + + def move_collision( + self, + id: str, + position: Union[Point, Tuple[float, float, float]], + quat_xyzw: Union[Quaternion, Tuple[float, float, float, float]], + frame_id: Optional[str] = None, + ): + """ + Move collision object specified by its `id`. + """ + + msg = CollisionObject() + + if not isinstance(position, Point): + position = Point( + x=float(position[0]), y=float(position[1]), z=float(position[2]) + ) + if not isinstance(quat_xyzw, Quaternion): + quat_xyzw = Quaternion( + x=float(quat_xyzw[0]), + y=float(quat_xyzw[1]), + z=float(quat_xyzw[2]), + w=float(quat_xyzw[3]), + ) + + pose = Pose() + pose.position = position + pose.orientation = quat_xyzw + msg.pose = pose + msg.id = id + msg.operation = CollisionObject.MOVE + msg.header.frame_id = ( + frame_id if frame_id is not None else self.__base_link_name + ) + msg.header.stamp = self.get_clock().now().to_msg() + + self.__collision_object_publisher.publish(msg) + + def update_planning_scene(self) -> bool: + """ + Gets the current planning scene. Returns whether the service call was + successful. + """ + + if not self._get_planning_scene_service.service_is_ready(): + self.get_logger().warn( + f"Service '{self._get_planning_scene_service.srv_name}' is not yet available. Better luck next time!" + ) + return False + self.__planning_scene = self._get_planning_scene_service.call( + GetPlanningScene.Request() + ).scene + return True + + def allow_collisions(self, id: str, allow: bool) -> Optional[Future]: + """ + Takes in the ID of an element in the planning scene. Modifies the allowed + collision matrix to (dis)allow collisions between that object and all other + object. + + If `allow` is True, a plan will succeed even if the robot collides with that object. + If `allow` is False, a plan will fail if the robot collides with that object. + Returns whether it successfully updated the allowed collision matrix. + + Returns the future of the service call. + """ + # Update the planning scene + if not self.update_planning_scene(): + return None + allowed_collision_matrix = self.__planning_scene.allowed_collision_matrix + self.__old_allowed_collision_matrix = copy.deepcopy(allowed_collision_matrix) + + # Get the location in the allowed collision matrix of the object + j = None + if id not in allowed_collision_matrix.entry_names: + allowed_collision_matrix.entry_names.append(id) + else: + j = allowed_collision_matrix.entry_names.index(id) + # For all other objects, (dis)allow collisions with the object with `id` + for i in range(len(allowed_collision_matrix.entry_values)): + if j is None: + allowed_collision_matrix.entry_values[i].enabled.append(allow) + elif i != j: + allowed_collision_matrix.entry_values[i].enabled[j] = allow + # For the object with `id`, (dis)allow collisions with all other objects + allowed_collision_entry = AllowedCollisionEntry( + enabled=[allow for _ in range(len(allowed_collision_matrix.entry_names))] + ) + if j is None: + allowed_collision_matrix.entry_values.append(allowed_collision_entry) + else: + allowed_collision_matrix.entry_values[j] = allowed_collision_entry + + # Apply the new planning scene + if not self._apply_planning_scene_service.service_is_ready(): + self.get_logger().warn( + f"Service '{self._apply_planning_scene_service.srv_name}' is not yet available. Better luck next time!" + ) + return None + return self._apply_planning_scene_service.call_async( + ApplyPlanningScene.Request(scene=self.__planning_scene) + ) + + def process_allow_collision_future(self, future: Future) -> bool: + """ + Return whether the allow collision service call is done and has succeeded + or not. If it failed, reset the allowed collision matrix to the old one. + """ + if not future.done(): + return False + + # Get response + resp = future.result() + + # If it failed, restore the old planning scene + if not resp.success: + self.__planning_scene.allowed_collision_matrix = ( + self.__old_allowed_collision_matrix + ) + + return resp.success + + def clear_all_collision_objects(self) -> Optional[Future]: + """ + Removes all attached and un-attached collision objects from the planning scene. + + Returns a future for the ApplyPlanningScene service call. + """ + # Update the planning scene + if not self.update_planning_scene(): + return None + self.__old_planning_scene = copy.deepcopy(self.__planning_scene) + + # Remove all collision objects from the planning scene + self.__planning_scene.world.collision_objects = [] + self.__planning_scene.robot_state.attached_collision_objects = [] + + # Apply the new planning scene + if not self._apply_planning_scene_service.service_is_ready(): + self.get_logger().warn( + f"Service '{self._apply_planning_scene_service.srv_name}' is not yet available. Better luck next time!" + ) + return None + return self._apply_planning_scene_service.call_async( + ApplyPlanningScene.Request(scene=self.__planning_scene) + ) + +if __name__ == '__main__': + model_s = ''' +{'Plate1': '/home/z43/git_pj/Uni-Lab-OS/unilabos/device_mesh/resources/tecan_nested_tip_rack/meshes/plate.stl', 'Plate1_': '/home/z43/git_pj/Uni-Lab-OS/unilabos/device_mesh/resources/generic_labware_tube_10_75/meshes/0_base.stl'} +''' + resource_model = json.loads(model_s.replace("'",'"')) + + config_s = ''' +[ + { + "id": "Gripper1", + "name": "假夹爪", + "children": [], + "parent": null, + "type": "device", + "class": "gripper.mock", + "position": { + "x": 620.6111111111111, + "y": 171, + "z": 0 + }, + "config": {}, + "data": {} + }, + { + "id": "Plate1", + "name": "Plate1", + "sample_id": null, + "children": [ + "Plate1_A1", + "Plate1_B1", + "Plate1_C1", + "Plate1_D1", + "Plate1_E1", + "Plate1_F1", + "Plate1_G1", + "Plate1_H1", + "Plate1_A2", + "Plate1_B2", + "Plate1_C2", + "Plate1_D2", + "Plate1_E2", + "Plate1_F2", + "Plate1_G2", + "Plate1_H2", + "Plate1_A3", + "Plate1_B3", + "Plate1_C3", + "Plate1_D3", + "Plate1_E3", + "Plate1_F3", + "Plate1_G3", + "Plate1_H3", + "Plate1_A4", + "Plate1_B4", + "Plate1_C4", + "Plate1_D4", + "Plate1_E4", + "Plate1_F4", + "Plate1_G4", + "Plate1_H4", + "Plate1_A5", + "Plate1_B5", + "Plate1_C5", + "Plate1_D5", + "Plate1_E5", + "Plate1_F5", + "Plate1_G5", + "Plate1_H5", + "Plate1_A6", + "Plate1_B6", + "Plate1_C6", + "Plate1_D6", + "Plate1_E6", + "Plate1_F6", + "Plate1_G6", + "Plate1_H6", + "Plate1_A7", + "Plate1_B7", + "Plate1_C7", + "Plate1_D7", + "Plate1_E7", + "Plate1_F7", + "Plate1_G7", + "Plate1_H7", + "Plate1_A8", + "Plate1_B8", + "Plate1_C8", + "Plate1_D8", + "Plate1_E8", + "Plate1_F8", + "Plate1_G8", + "Plate1_H8", + "Plate1_A9", + "Plate1_B9", + "Plate1_C9", + "Plate1_D9", + "Plate1_E9", + "Plate1_F9", + "Plate1_G9", + "Plate1_H9", + "Plate1_A10", + "Plate1_B10", + "Plate1_C10", + "Plate1_D10", + "Plate1_E10", + "Plate1_F10", + "Plate1_G10", + "Plate1_H10", + "Plate1_A11", + "Plate1_B11", + "Plate1_C11", + "Plate1_D11", + "Plate1_E11", + "Plate1_F11", + "Plate1_G11", + "Plate1_H11", + "Plate1_A12", + "Plate1_B12", + "Plate1_C12", + "Plate1_D12", + "Plate1_E12", + "Plate1_F12", + "Plate1_G12", + "Plate1_H12" + ], + "parent": "Gripper1", + "type": "device", + "class": "", + "position": { + "x": 620.6111111111111, + "y": 171, + "z": 0 + }, + "config": { + "type": "Plate", + "size_x": 127.76, + "size_y": 85.48, + "size_z": 15.7, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "plate", + "model": "NEST 96 Well Plate 100 µL PCR Full Skirt", + "ordering": [ + "A1", + "B1", + "C1", + "D1", + "E1", + "F1", + "G1", + "H1", + "A2", + "B2", + "C2", + "D2", + "E2", + "F2", + "G2", + "H2", + "A3", + "B3", + "C3", + "D3", + "E3", + "F3", + "G3", + "H3", + "A4", + "B4", + "C4", + "D4", + "E4", + "F4", + "G4", + "H4", + "A5", + "B5", + "C5", + "D5", + "E5", + "F5", + "G5", + "H5", + "A6", + "B6", + "C6", + "D6", + "E6", + "F6", + "G6", + "H6", + "A7", + "B7", + "C7", + "D7", + "E7", + "F7", + "G7", + "H7", + "A8", + "B8", + "C8", + "D8", + "E8", + "F8", + "G8", + "H8", + "A9", + "B9", + "C9", + "D9", + "E9", + "F9", + "G9", + "H9", + "A10", + "B10", + "C10", + "D10", + "E10", + "F10", + "G10", + "H10", + "A11", + "B11", + "C11", + "D11", + "E11", + "F11", + "G11", + "H11", + "A12", + "B12", + "C12", + "D12", + "E12", + "F12", + "G12", + "H12" + ] + }, + "data": {} + }, + { + "id": "Plate1_A1", + "name": "Plate1_A1", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 12.492, + "y": 72.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_B1", + "name": "Plate1_B1", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 12.492, + "y": 63.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_C1", + "name": "Plate1_C1", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 12.492, + "y": 54.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_D1", + "name": "Plate1_D1", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 12.492, + "y": 45.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_E1", + "name": "Plate1_E1", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 12.492, + "y": 36.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_F1", + "name": "Plate1_F1", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 12.492, + "y": 27.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_G1", + "name": "Plate1_G1", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 12.492, + "y": 18.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_H1", + "name": "Plate1_H1", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 12.492, + "y": 9.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_A2", + "name": "Plate1_A2", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 21.492, + "y": 72.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_B2", + "name": "Plate1_B2", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 21.492, + "y": 63.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_C2", + "name": "Plate1_C2", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 21.492, + "y": 54.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_D2", + "name": "Plate1_D2", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 21.492, + "y": 45.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_E2", + "name": "Plate1_E2", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 21.492, + "y": 36.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_F2", + "name": "Plate1_F2", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 21.492, + "y": 27.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_G2", + "name": "Plate1_G2", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 21.492, + "y": 18.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_H2", + "name": "Plate1_H2", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 21.492, + "y": 9.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_A3", + "name": "Plate1_A3", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 30.492, + "y": 72.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_B3", + "name": "Plate1_B3", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 30.492, + "y": 63.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_C3", + "name": "Plate1_C3", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 30.492, + "y": 54.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_D3", + "name": "Plate1_D3", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 30.492, + "y": 45.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_E3", + "name": "Plate1_E3", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 30.492, + "y": 36.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_F3", + "name": "Plate1_F3", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 30.492, + "y": 27.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_G3", + "name": "Plate1_G3", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 30.492, + "y": 18.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_H3", + "name": "Plate1_H3", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 30.492, + "y": 9.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_A4", + "name": "Plate1_A4", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 39.492, + "y": 72.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_B4", + "name": "Plate1_B4", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 39.492, + "y": 63.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_C4", + "name": "Plate1_C4", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 39.492, + "y": 54.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_D4", + "name": "Plate1_D4", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 39.492, + "y": 45.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_E4", + "name": "Plate1_E4", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 39.492, + "y": 36.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_F4", + "name": "Plate1_F4", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 39.492, + "y": 27.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_G4", + "name": "Plate1_G4", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 39.492, + "y": 18.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_H4", + "name": "Plate1_H4", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 39.492, + "y": 9.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_A5", + "name": "Plate1_A5", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 48.492, + "y": 72.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_B5", + "name": "Plate1_B5", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 48.492, + "y": 63.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_C5", + "name": "Plate1_C5", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 48.492, + "y": 54.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_D5", + "name": "Plate1_D5", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 48.492, + "y": 45.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_E5", + "name": "Plate1_E5", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 48.492, + "y": 36.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_F5", + "name": "Plate1_F5", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 48.492, + "y": 27.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_G5", + "name": "Plate1_G5", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 48.492, + "y": 18.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_H5", + "name": "Plate1_H5", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 48.492, + "y": 9.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_A6", + "name": "Plate1_A6", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 57.492, + "y": 72.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_B6", + "name": "Plate1_B6", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 57.492, + "y": 63.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_C6", + "name": "Plate1_C6", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 57.492, + "y": 54.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_D6", + "name": "Plate1_D6", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 57.492, + "y": 45.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_E6", + "name": "Plate1_E6", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 57.492, + "y": 36.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_F6", + "name": "Plate1_F6", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 57.492, + "y": 27.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_G6", + "name": "Plate1_G6", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 57.492, + "y": 18.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_H6", + "name": "Plate1_H6", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 57.492, + "y": 9.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_A7", + "name": "Plate1_A7", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 66.492, + "y": 72.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_B7", + "name": "Plate1_B7", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 66.492, + "y": 63.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_C7", + "name": "Plate1_C7", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 66.492, + "y": 54.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_D7", + "name": "Plate1_D7", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 66.492, + "y": 45.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_E7", + "name": "Plate1_E7", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 66.492, + "y": 36.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_F7", + "name": "Plate1_F7", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 66.492, + "y": 27.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_G7", + "name": "Plate1_G7", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 66.492, + "y": 18.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_H7", + "name": "Plate1_H7", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 66.492, + "y": 9.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_A8", + "name": "Plate1_A8", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 75.492, + "y": 72.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_B8", + "name": "Plate1_B8", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 75.492, + "y": 63.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_C8", + "name": "Plate1_C8", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 75.492, + "y": 54.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_D8", + "name": "Plate1_D8", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 75.492, + "y": 45.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_E8", + "name": "Plate1_E8", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 75.492, + "y": 36.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_F8", + "name": "Plate1_F8", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 75.492, + "y": 27.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_G8", + "name": "Plate1_G8", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 75.492, + "y": 18.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_H8", + "name": "Plate1_H8", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 75.492, + "y": 9.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_A9", + "name": "Plate1_A9", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 84.492, + "y": 72.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_B9", + "name": "Plate1_B9", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 84.492, + "y": 63.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_C9", + "name": "Plate1_C9", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 84.492, + "y": 54.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_D9", + "name": "Plate1_D9", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 84.492, + "y": 45.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_E9", + "name": "Plate1_E9", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 84.492, + "y": 36.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_F9", + "name": "Plate1_F9", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 84.492, + "y": 27.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_G9", + "name": "Plate1_G9", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 84.492, + "y": 18.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_H9", + "name": "Plate1_H9", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 84.492, + "y": 9.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_A10", + "name": "Plate1_A10", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 93.492, + "y": 72.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_B10", + "name": "Plate1_B10", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 93.492, + "y": 63.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_C10", + "name": "Plate1_C10", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 93.492, + "y": 54.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_D10", + "name": "Plate1_D10", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 93.492, + "y": 45.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_E10", + "name": "Plate1_E10", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 93.492, + "y": 36.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_F10", + "name": "Plate1_F10", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 93.492, + "y": 27.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_G10", + "name": "Plate1_G10", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 93.492, + "y": 18.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_H10", + "name": "Plate1_H10", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 93.492, + "y": 9.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_A11", + "name": "Plate1_A11", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 102.492, + "y": 72.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_B11", + "name": "Plate1_B11", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 102.492, + "y": 63.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_C11", + "name": "Plate1_C11", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 102.492, + "y": 54.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_D11", + "name": "Plate1_D11", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 102.492, + "y": 45.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_E11", + "name": "Plate1_E11", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 102.492, + "y": 36.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_F11", + "name": "Plate1_F11", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 102.492, + "y": 27.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_G11", + "name": "Plate1_G11", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 102.492, + "y": 18.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_H11", + "name": "Plate1_H11", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 102.492, + "y": 9.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_A12", + "name": "Plate1_A12", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 111.492, + "y": 72.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_B12", + "name": "Plate1_B12", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 111.492, + "y": 63.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_C12", + "name": "Plate1_C12", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 111.492, + "y": 54.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_D12", + "name": "Plate1_D12", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 111.492, + "y": 45.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_E12", + "name": "Plate1_E12", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 111.492, + "y": 36.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_F12", + "name": "Plate1_F12", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 111.492, + "y": 27.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_G12", + "name": "Plate1_G12", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 111.492, + "y": 18.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + }, + { + "id": "Plate1_H12", + "name": "Plate1_H12", + "sample_id": null, + "children": [], + "parent": "Plate1", + "type": "device", + "class": "", + "position": { + "x": 111.492, + "y": 9.352, + "z": 0.92 + }, + "config": { + "type": "Well", + "size_x": 3.776, + "size_y": 3.776, + "size_z": 14.78, + "rotation": { + "x": 0, + "y": 0, + "z": 0, + "type": "Rotation" + }, + "category": "well", + "model": null, + "max_volume": 100, + "material_z_thickness": null, + "compute_volume_from_height": null, + "compute_height_from_volume": null, + "bottom_type": "unknown", + "cross_section_type": "circle" + }, + "data": { + "liquids": [], + "pending_liquids": [], + "liquid_history": [] + } + } +] + + ''' + resource_config = json.loads(config_s.replace("'",'"')) + rclpy.init() + resource_mesh_manager = ResourceMeshManager(resource_model, resource_config, 'resource_mesh_manager') + resource_mesh_manager.resource_mesh_setup() + print(json.dumps(resource_mesh_manager.resource_tf_dict, indent=4, ensure_ascii=False)) \ No newline at end of file diff --git a/unilabos/registry/devices/robot_gripper.yaml b/unilabos/registry/devices/robot_gripper.yaml index 15881df1..3cb86fed 100644 --- a/unilabos/registry/devices/robot_gripper.yaml +++ b/unilabos/registry/devices/robot_gripper.yaml @@ -20,8 +20,8 @@ gripper.mock: position: position effort: torque model: - tpye: device - mesh: slide_w140 + type: device + mesh: opentrons_liquid_handler gripper.misumi_rz: description: Misumi RZ gripper diff --git a/unilabos/registry/resources/opentrons/plates.yaml b/unilabos/registry/resources/opentrons/plates.yaml index efc65650..0a7c4b84 100644 --- a/unilabos/registry/resources/opentrons/plates.yaml +++ b/unilabos/registry/resources/opentrons/plates.yaml @@ -53,8 +53,8 @@ nest_96_wellplate_100ul_pcr_full_skirt: type: pylabrobot model: type: resource - mesh: /home/z43/git_pj/uni-lab-assets/device_models/tecan_nested_tip_rack/meshes/plate.stl - children_mesh: /home/z43/git_pj/uni-lab-assets/device_models/generic_labware_tube_10_75/meshes/0_base.stl + mesh: tecan_nested_tip_rack/meshes/plate.stl + children_mesh: generic_labware_tube_10_75/meshes/0_base.stl appliedbiosystemsmicroamp_384_wellplate_40ul: description: Applied Biosystems microamp 384 wellplate 40ul