From 5212d2d8eb03bb1dbdefe32ec6e3b350f02fa35b Mon Sep 17 00:00:00 2001 From: zhangshixiang <@zhangshixiang> Date: Wed, 30 Apr 2025 22:18:29 +0800 Subject: [PATCH] =?UTF-8?q?=E4=BF=AE=E5=A4=8Drviz=E4=BD=8D=E7=BD=AE?= =?UTF-8?q?=E9=97=AE=E9=A2=98,?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit 修复rviz位置问题, 在无tf变动时减缓发送频率 在backend中添加物料跟随方法 --- test/experiments/test.json | 102 + test/experiments/test_copy.json | 6 +- unilabos/device_mesh/view_robot.rviz | 8 +- .../ros_dev/liquid_handler_joint_publisher.py | 173 +- .../devices/ros_dev/resource_mesh_manager.py | 79 +- unilabos/registry/devices/sim_nodes.yaml | 4 + .../ros/nodes/presets/joint_republisher.py | 60 + .../nodes/presets/resource_mesh_manager.py | 4991 +++++++++++++++++ 8 files changed, 5323 insertions(+), 100 deletions(-) create mode 100644 unilabos/ros/nodes/presets/joint_republisher.py create mode 100644 unilabos/ros/nodes/presets/resource_mesh_manager.py diff --git a/test/experiments/test.json b/test/experiments/test.json index 8b92c9af..ac5e5043 100644 --- a/test/experiments/test.json +++ b/test/experiments/test.json @@ -36,6 +36,108 @@ }, "data": { } + }, + { + "id": "ot_joint_publisher", + "name": "ot_joint_publisher", + "sample_id": null, + "children": [ + + ], + "parent": null, + "type": "device", + "class": "lh_joint_publisher", + "position": { + "x": 0, + "y": 0, + "z": 0 + }, + "config": { + "lh_id":"deck", + "joint_config": + { + "joint_names":[ + "first_joint", + "second_joint", + "third_joint", + "fourth_joint" + ], + "y":{ + "first_joint":{ + "factor":-1, + "offset":0.0 + } + }, + "x":{ + "second_joint":{ + "factor":-1, + "offset":0.0 + } + }, + "z":{ + "third_joint":{ + "factor":1, + "offset":0.0 + }, + "fourth_joint":{ + "factor":1, + "offset":0.0 + } + } + } + }, + "data": {} + }, + { + "id": "ot_joint_publisher", + "name": "ot_joint_publisher", + "sample_id": null, + "children": [ + + ], + "parent": null, + "type": "device", + "class": "lh_joint_publisher", + "position": { + "x": 0, + "y": 0, + "z": 0 + }, + "config": { + "lh_id":"deck", + "joint_config": + { + "joint_names":[ + "first_joint", + "second_joint", + "third_joint", + "fourth_joint" + ], + "y":{ + "first_joint":{ + "factor":-1, + "offset":0.0 + } + }, + "x":{ + "second_joint":{ + "factor":-1, + "offset":0.0 + } + }, + "z":{ + "third_joint":{ + "factor":1, + "offset":0.0 + }, + "fourth_joint":{ + "factor":1, + "offset":0.0 + } + } + } + }, + "data": {} } ], "links": [ diff --git a/test/experiments/test_copy.json b/test/experiments/test_copy.json index d6b861b4..56127a24 100644 --- a/test/experiments/test_copy.json +++ b/test/experiments/test_copy.json @@ -68,8 +68,8 @@ "type": "plate", "class": "opentrons_96_filtertiprack_1000ul", "position": { - "x": 132.5, - "y": 271.5, + "x": 0, + "y": 0, "z": 69 }, "config": { @@ -99,7 +99,7 @@ "position": { "x": 10.87, "y": 70.77, - "z": 3.03 + "z": 10 }, "config": { "type": "TipSpot", diff --git a/unilabos/device_mesh/view_robot.rviz b/unilabos/device_mesh/view_robot.rviz index df19a69e..bf32efc3 100644 --- a/unilabos/device_mesh/view_robot.rviz +++ b/unilabos/device_mesh/view_robot.rviz @@ -360,10 +360,10 @@ Visualization Manager: Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.4347957372665405 + Pitch: 0.40479573607444763 Target Frame: Value: Orbit (rviz) - Yaw: 6.020748138427734 + Yaw: 6.090748310089111 Saved: ~ Window Geometry: Displays: @@ -383,5 +383,5 @@ Window Geometry: Views: collapsed: true Width: 2518 - X: 140 - Y: 145 + X: 385 + Y: 120 diff --git a/unilabos/devices/ros_dev/liquid_handler_joint_publisher.py b/unilabos/devices/ros_dev/liquid_handler_joint_publisher.py index 15adde08..7933f8df 100644 --- a/unilabos/devices/ros_dev/liquid_handler_joint_publisher.py +++ b/unilabos/devices/ros_dev/liquid_handler_joint_publisher.py @@ -1,3 +1,4 @@ +import copy import rclpy import json import time @@ -12,7 +13,7 @@ from tf2_ros import TransformBroadcaster, Buffer, TransformListener class LiquidHandlerJointPublisher(BaseROS2DeviceNode): - def __init__(self,device_id:str, joint_config:dict,resource_tracker): + def __init__(self,device_id:str, joint_config:dict, lh_id:str,resource_tracker, rate=50): super().__init__( driver_instance=self, device_id=device_id, @@ -22,26 +23,61 @@ class LiquidHandlerJointPublisher(BaseROS2DeviceNode): print_publish=False, resource_tracker=resource_tracker, ) - # self.station_name = station_name - # self.dev_name = dev_name + + # joint_config_dict = { + # "joint_names":[ + # "first_joint", + # "second_joint", + # "third_joint", + # "fourth_joint" + # ], + # "y":{ + # "first_joint":{ + # "factor":-1, + # "offset":0.0 + # } + # }, + # "x":{ + # "second_joint":{ + # "factor":-1, + # "offset":0.0 + # } + # }, + # "z":{ + # "third_joint":{ + # "factor":1, + # "offset":0.0 + # }, + # "fourth_joint":{ + # "factor":1, + # "offset":0.0 + # } + # } + # } + self.j_msg = JointState() + self.lh_id = lh_id # self.j_msg.name = joint_names - self.j_msg.name = [device_id+x for x in joint_config.keys()] - self.rate = 50 - self.j_msg.position = [0.0 for i in range(len(joint_config.keys()))] + self.joint_config = joint_config + self.j_msg.position = [0.0 for i in range(len(joint_config['joint_names']))] + self.j_msg.name = [f"{self.lh_id}_{x}" for x in joint_config['joint_names']] + # self.joint_config = joint_config_dict + # self.j_msg.position = [0.0 for i in range(len(joint_config_dict['joint_names']))] + # self.j_msg.name = [f"{self.lh_id}_{x}" for x in joint_config_dict['joint_names']] + self.rate = rate self.tf_buffer = Buffer() self.tf_listener = TransformListener(self.tf_buffer, self) self.j_pub = self.create_publisher(JointState,'/joint_states',10) - self.create_timer(0.02,self.sim_joint_pub_callback) + self.create_timer(0.02,self.lh_joint_pub_callback) self.j_action = ActionServer( self, SendCmd, "joint", - self.sim_joint_action_callback, + self.lh_joint_action_callback, result_timeout=5000 ) - def sim_joint_action_callback(self,goal_handle: ServerGoalHandle): + def lh_joint_action_callback(self,goal_handle: ServerGoalHandle): """Move a single joint Args: @@ -60,7 +96,7 @@ class LiquidHandlerJointPublisher(BaseROS2DeviceNode): try: cmd_dict = json.loads(cmd_str) - self.move_joint(**cmd_dict) + self.move_joints(**cmd_dict) result.success = True goal_handle.succeed() @@ -70,44 +106,103 @@ class LiquidHandlerJointPublisher(BaseROS2DeviceNode): result.success = False return result - - - def move_joint(self, joint_name, speed, position): + def inverse_kinematics(self, x, y, z, + x_joint:dict, + y_joint:dict, + z_joint:dict ): + """ + 将x、y、z坐标转换为对应关节的位置 - # joint_index = self.j_msg.name.index(self.station_name+self.dev_name+joint_name) - joint_index = self.j_msg.name.index(joint_name) - distance = position - self.j_msg.position[joint_index] - if distance == 0: - return - flag = abs(distance)/distance - - while abs(distance)>speed/self.rate: + Args: + x (float): x坐标 + y (float): y坐标 + z (float): z坐标 + x_joint (dict): x轴关节配置,包含plus和offset + y_joint (dict): y轴关节配置,包含plus和offset + z_joint (dict): z轴关节配置,包含plus和offset - self.j_msg.position[joint_index] += flag*speed/self.rate - self.sim_joint_pub_callback() - time.sleep(0.02) - distance = position - self.j_msg.position[joint_index] - - self.j_msg.position[joint_index] = position - self.sim_joint_pub_callback() + Returns: + dict: 关节名称和对应位置的字典 + """ + joint_positions = copy.deepcopy(self.j_msg.position) + + # 处理x轴关节 + for joint_name, config in x_joint.items(): + index = self.j_msg.name.index(f"{self.lh_id}_{joint_name}") + joint_positions[index] = x * config["factor"] + config["offset"] + + # 处理y轴关节 + for joint_name, config in y_joint.items(): + index = self.j_msg.name.index(f"{self.lh_id}_{joint_name}") + joint_positions[index] = y * config["factor"] + config["offset"] + + # 处理z轴关节 + for joint_name, config in z_joint.items(): + index = self.j_msg.name.index(f"{self.lh_id}_{joint_name}") + joint_positions[index] = z * config["factor"] + config["offset"] + + + return joint_positions - def sim_joint_pub_callback(self): + def move_joints(self, resource_name, link_name, speed, x_joint=None, y_joint=None, z_joint=None): + + transform = self.tf_buffer.lookup_transform( + link_name, + resource_name, + rclpy.time.Time() + ) + x,y,z = transform.transform.translation.x, transform.transform.translation.y, transform.transform.translation.z + if x_joint is None: + x_joint_config = next(iter(self.joint_config['x'].items())) + elif x_joint in self.joint_config['x']: + x_joint_config = self.joint_config['x'][x_joint] + else: + raise ValueError(f"x_joint {x_joint} not in joint_config['x']") + if y_joint is None: + y_joint_config = next(iter(self.joint_config['y'].items())) + elif y_joint in self.joint_config['y']: + y_joint_config = self.joint_config['y'][y_joint] + else: + raise ValueError(f"y_joint {y_joint} not in joint_config['y']") + if z_joint is None: + z_joint_config = next(iter(self.joint_config['z'].items())) + elif z_joint in self.joint_config['z']: + z_joint_config = self.joint_config['z'][z_joint] + else: + raise ValueError(f"z_joint {z_joint} not in joint_config['z']") + joint_positions_target = self.inverse_kinematics(x,y,z,x_joint_config,y_joint_config,z_joint_config) + + loop_flag = 0 + + + while loop_flag < len(self.joint_config['joint_names']): + loop_flag = 0 + for i in range(len(self.joint_config['joint_names'])): + distance = joint_positions_target[i] - self.j_msg.position[i] + if distance == 0: + loop_flag += 1 + continue + minus_flag = distance/abs(distance) + if abs(distance) > speed/self.rate: + self.j_msg.position[i] += minus_flag * speed/self.rate + else : + self.j_msg.position[i] = joint_positions_target[i] + loop_flag += 1 + + + # 发布关节状态 + self.lh_joint_pub_callback() + time.sleep(1/self.rate) + + + def lh_joint_pub_callback(self): self.j_msg.header.stamp = self.get_clock().now().to_msg() self.j_pub.publish(self.j_msg) def main(): - joint_json:dict = json.load(open("device_data.json", encoding='utf-8')) - joint_action_list = {} - rclpy.init() - executor = MultiThreadedExecutor() - for station_name,dev_dict in joint_json.items(): - for dev_name,joint_names in dev_dict.items(): - joint_action_list[station_name+'_'+dev_name] = SimJointPublisher(station_name,dev_name,joint_names) - executor.add_node(joint_action_list[station_name+'_'+dev_name]) - - executor.spin() + pass if __name__ == '__main__': main() \ No newline at end of file diff --git a/unilabos/devices/ros_dev/resource_mesh_manager.py b/unilabos/devices/ros_dev/resource_mesh_manager.py index cf43b804..5f04e1a1 100644 --- a/unilabos/devices/ros_dev/resource_mesh_manager.py +++ b/unilabos/devices/ros_dev/resource_mesh_manager.py @@ -22,7 +22,7 @@ from rclpy.action.server import ServerGoalHandle from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode,DeviceNodeResourceTracker class ResourceMeshManager(BaseROS2DeviceNode): - def __init__(self, resource_model: dict, resource_config: list,resource_tracker, device_id: str = "resource_mesh_manager"): + def __init__(self, resource_model: dict, resource_config: list,resource_tracker, device_id: str = "resource_mesh_manager", rate=50): """初始化资源网格管理器节点 Args: @@ -47,7 +47,8 @@ class ResourceMeshManager(BaseROS2DeviceNode): self.tf_broadcaster = TransformBroadcaster(self) self.tf_buffer = Buffer() self.tf_listener = TransformListener(self.tf_buffer, self) - + self.rate = rate + self.zero_count = 0 self.old_resource_pose = {} self.__planning_scene = None @@ -101,8 +102,8 @@ class ResourceMeshManager(BaseROS2DeviceNode): ) self.resource_mesh_setup() - self.create_timer(0.02, self.publish_resource_tf) - self.create_timer(1, self.check_resource_pose_changes) + self.create_timer(1/self.rate, self.publish_resource_tf) + self.create_timer(1/self.rate, self.check_resource_pose_changes) @@ -116,6 +117,7 @@ class ResourceMeshManager(BaseROS2DeviceNode): # if tf_ready: if self._get_planning_scene_service.service_is_ready() and self._apply_planning_scene_service.service_is_ready() and tf_ready: self.move_group_ready = True + self.publish_resource_tf() self.add_resource_collision_meshes() # time.sleep(1) @@ -246,7 +248,7 @@ class ResourceMeshManager(BaseROS2DeviceNode): transform = self.tf_buffer.lookup_transform( "world", resource_id, - rclpy.time.Time(), + rclpy.time.Time(seconds=0), rclpy.duration.Duration(seconds=5) ) @@ -280,13 +282,24 @@ class ResourceMeshManager(BaseROS2DeviceNode): except Exception as e: self.get_logger().warning(f"获取资源 {resource_id} 的世界坐标变换失败: {e}") - - changed_poses_msg = String() - changed_poses_msg.data = json.dumps(changed_poses) - self.resource_pose_publisher.publish(changed_poses_msg) + + if changed_poses != {}: + self.zero_count = 0 + changed_poses_msg = String() + changed_poses_msg.data = json.dumps(changed_poses) + self.resource_pose_publisher.publish(changed_poses_msg) + else: + if self.zero_count > self.rate: + self.zero_count = 0 + changed_poses_msg = String() + changed_poses_msg.data = json.dumps(changed_poses) + self.resource_pose_publisher.publish(changed_poses_msg) + self.zero_count += 1 + + - def _is_pose_equal(self, pose1, pose2, tolerance=1e-5): + def _is_pose_equal(self, pose1, pose2, tolerance=1e-7): """ 比较两个位姿是否相等(考虑浮点数精度) @@ -328,7 +341,7 @@ class ResourceMeshManager(BaseROS2DeviceNode): transform = self.tf_buffer.lookup_transform( target_parent, resource_id, - rclpy.time.Time() + rclpy.time.Time(seconds=0) ) # 提取转换中的位置和旋转信息 @@ -350,7 +363,7 @@ class ResourceMeshManager(BaseROS2DeviceNode): "position": position, "rotation": rotation } - + self.attach_collision_object(id=resource_id,link_name=target_parent) self.publish_resource_tf() @@ -362,48 +375,6 @@ class ResourceMeshManager(BaseROS2DeviceNode): goal_handle.succeed() return SendCmd.Result(success=True) - def publish_resource_tf(self): - """ - 发布资源之间的TF关系 - - 遍历self.resource_tf_dict中的每个元素,根据key,parent,以及position和rotation, - 发布key和parent之间的tf关系 - """ - - transforms = [] - - # 遍历资源TF字典 - resource_tf_dict = copy.deepcopy(self.resource_tf_dict) - for resource_id, tf_info in resource_tf_dict.items(): - parent = tf_info['parent'] - position = tf_info['position'] - rotation = tf_info['rotation'] - - # 创建静态变换消息 - - transform = TransformStamped() - transform.header.stamp = self.get_clock().now().to_msg() - transform.header.frame_id = parent - transform.child_frame_id = resource_id - - # 设置位置 - transform.transform.translation.x = float(position['x']) - transform.transform.translation.y = float(position['y']) - transform.transform.translation.z = float(position['z']) - - # 设置旋转 - transform.transform.rotation.x = rotation['x'] - transform.transform.rotation.y = rotation['y'] - transform.transform.rotation.z = rotation['z'] - transform.transform.rotation.w = rotation['w'] - - transforms.append(transform) - - # 一次性发布所有静态变换 - if transforms: - self.tf_broadcaster.sendTransform(transforms) - - # self.get_logger().info(f'已发布 {len(transforms)} 个资源TF关系') def add_resource_collision_meshes(self): """ diff --git a/unilabos/registry/devices/sim_nodes.yaml b/unilabos/registry/devices/sim_nodes.yaml index 6f6fa256..ec7ee61b 100644 --- a/unilabos/registry/devices/sim_nodes.yaml +++ b/unilabos/registry/devices/sim_nodes.yaml @@ -8,4 +8,8 @@ resource.mesh_manager: module: unilabos.devices.ros_dev.resource_mesh_manager:ResourceMeshManager type: ros2 +lh_joint_publisher: + class: + module: unilabos.devices.ros_dev.liquid_handler_joint_publisher:LiquidHandlerJointPublisher + type: ros2 diff --git a/unilabos/ros/nodes/presets/joint_republisher.py b/unilabos/ros/nodes/presets/joint_republisher.py new file mode 100644 index 00000000..b731acc7 --- /dev/null +++ b/unilabos/ros/nodes/presets/joint_republisher.py @@ -0,0 +1,60 @@ +import rclpy,json +from rclpy.node import Node +from sensor_msgs.msg import JointState +from std_msgs.msg import String +from rclpy.callback_groups import ReentrantCallbackGroup +from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode + +class JointRepublisher(BaseROS2DeviceNode): + def __init__(self,device_id,resource_tracker): + super().__init__( + driver_instance=self, + device_id=device_id, + status_types={}, + action_value_mappings={}, + hardware_interface={}, + print_publish=False, + resource_tracker=resource_tracker, + ) + + # print('-'*20,device_id) + self.joint_repub = self.create_publisher(String,f'joint_state_repub',10) + # 创建订阅者 + self.create_subscription( + JointState, + '/joint_states', + self.listener_callback, + 10, + callback_group=ReentrantCallbackGroup() + ) + self.msg = String() + + def listener_callback(self, msg:JointState): + + try: + json_dict = {} + json_dict["name"] = list(msg.name) + json_dict["position"] = list(msg.position) + json_dict["velocity"] = list(msg.velocity) + json_dict["effort"] = list(msg.effort) + + self.msg.data = str(json_dict) + self.joint_repub.publish(self.msg) + # print('-'*20) + # print(self.msg.data) + + except Exception as e: + print(e) + + +def main(): + + rclpy.init() + subscriber = JointRepublisher() + rclpy.spin(subscriber) + subscriber.destroy_node() + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/unilabos/ros/nodes/presets/resource_mesh_manager.py b/unilabos/ros/nodes/presets/resource_mesh_manager.py new file mode 100644 index 00000000..cf43b804 --- /dev/null +++ b/unilabos/ros/nodes/presets/resource_mesh_manager.py @@ -0,0 +1,4991 @@ +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, TransformStamped +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 +from tf_transformations import quaternion_from_euler +from tf2_ros import TransformBroadcaster, Buffer, TransformListener +from rclpy.action import ActionServer +from unilabos_msgs.action import SendCmd +from rclpy.action.server import ServerGoalHandle +from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode,DeviceNodeResourceTracker + +class ResourceMeshManager(BaseROS2DeviceNode): + def __init__(self, resource_model: dict, resource_config: list,resource_tracker, device_id: str = "resource_mesh_manager"): + """初始化资源网格管理器节点 + + Args: + resource_model (dict): 资源模型字典,包含资源的3D模型信息 + resource_config (dict): 资源配置字典,包含资源的配置信息 + device_id (str): 节点名称 + """ + super().__init__( + driver_instance=self, + device_id=device_id, + status_types={}, + action_value_mappings={}, + hardware_interface={}, + print_publish=False, + resource_tracker=resource_tracker, + ) + + self.resource_model = resource_model + self.resource_config_dict = {item['id']: item for item in resource_config} + self.move_group_ready = False + self.resource_tf_dict = {} + self.tf_broadcaster = TransformBroadcaster(self) + self.tf_buffer = Buffer() + self.tf_listener = TransformListener(self.tf_buffer, self) + + + self.old_resource_pose = {} + self.__planning_scene = None + self.__old_planning_scene = None + self.__old_allowed_collision_matrix = None + + + 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, + ) + + # 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.resource_pose_publisher = self.create_publisher( + String, f"resource_pose", 10 + ) + self.__collision_object_publisher = self.create_publisher( + CollisionObject, "/collision_object", 10 + ) + self.__attached_collision_object_publisher = self.create_publisher( + AttachedCollisionObject, "/attached_collision_object", 10 + ) + + # 创建一个Action Server用于修改resource_tf_dict + self._action_server = ActionServer( + self, + SendCmd, + f"tf_update", + self.tf_update, + callback_group=callback_group + ) + + self.resource_mesh_setup() + self.create_timer(0.02, self.publish_resource_tf) + self.create_timer(1, self.check_resource_pose_changes) + + + + def check_move_group_ready(self): + """检查move_group节点是否已初始化完成""" + + # 获取当前可用的节点列表 + + tf_ready = self.tf_buffer.can_transform("world", next(iter(self.resource_tf_dict.keys())), rclpy.time.Time(),rclpy.duration.Duration(seconds=2)) + + # if tf_ready: + if self._get_planning_scene_service.service_is_ready() and self._apply_planning_scene_service.service_is_ready() and tf_ready: + self.move_group_ready = True + self.add_resource_collision_meshes() + + # time.sleep(1) + + + + def resource_mesh_setup(self): + """move_group初始化完成后的设置""" + self.get_logger().info('开始设置资源网格管理器') + #遍历resource_config中的资源配置,判断panent是否在resource_model中, + + for resource_id, resource_config in self.resource_config_dict.items(): + + parent = resource_config['parent'] + parent_link = 'world' + if parent in self.resource_model: + parent_link = parent + elif parent is None and resource_id in self.resource_model: + pass + elif parent not in self.resource_model and parent is not None and resource_config['class'] != '': + parent_link = f"{self.resource_config_dict[parent]['parent']}_{parent}_device_link".replace("None","") + else: + continue + # 提取位置信息并转换单位 + position = { + "x": float(resource_config['position']['x'])/1000, + "y": float(resource_config['position']['y'])/1000, + "z": float(resource_config['position']['z'])/1000 + } + + rotation_dict = { + "x": 0, + "y": 0, + "z": 0 + } + + if 'rotation' in resource_config['config']: + rotation_dict = resource_config['config']['rotation'] + + # 从欧拉角转换为四元数 + q = quaternion_from_euler( + float(rotation_dict['x']), + float(rotation_dict['y']), + float(rotation_dict['z']) + ) + # print("-"*20) + # print(f"resource_id: {resource_id}") + # print(f"parent: {parent}") + # print(f"resource_config: {resource_config}") + # print(f"parent_link: {parent_link}") + # print("-"*20) + rotation = { + "x": q[0], + "y": q[1], + "z": q[2], + "w": q[3] + } + + # 更新资源TF字典 + self.resource_tf_dict[resource_id] = { + "parent": parent_link, + "position": position, + "rotation": rotation + } + + + def publish_resource_tf(self): + """ + 发布资源之间的TF关系 + + 遍历self.resource_tf_dict中的每个元素,根据key,parent,以及position和rotation, + 发布key和parent之间的tf关系 + """ + + transforms = [] + + # 遍历资源TF字典 + resource_tf_dict = copy.deepcopy(self.resource_tf_dict) + for resource_id, tf_info in resource_tf_dict.items(): + parent = tf_info['parent'] + position = tf_info['position'] + rotation = tf_info['rotation'] + + # 创建静态变换消息 + + transform = TransformStamped() + transform.header.stamp = self.get_clock().now().to_msg() + transform.header.frame_id = parent + transform.child_frame_id = resource_id + + # 设置位置 + transform.transform.translation.x = float(position['x']) + transform.transform.translation.y = float(position['y']) + transform.transform.translation.z = float(position['z']) + + # 设置旋转 + transform.transform.rotation.x = rotation['x'] + transform.transform.rotation.y = rotation['y'] + transform.transform.rotation.z = rotation['z'] + transform.transform.rotation.w = rotation['w'] + + transforms.append(transform) + + # 一次性发布所有静态变换 + if transforms: + self.tf_broadcaster.sendTransform(transforms) + # self.check_resource_pose_changes() + # self.get_logger().info(f'已发布 {len(transforms)} 个资源TF关系') + + + def check_resource_pose_changes(self): + """ + 遍历资源TF字典,计算每个资源相对于world的变换, + 与旧的位姿比较,记录发生变化的资源,并更新旧位姿记录。 + + Returns: + dict: 包含发生位姿变化的资源ID及其新位姿 + """ + if not self.move_group_ready: + self.check_move_group_ready() + return + changed_poses = {} + resource_tf_dict = copy.deepcopy(self.resource_tf_dict) + for resource_id in resource_tf_dict.keys(): + try: + # 获取从resource_id到world的转换 + + transform = self.tf_buffer.lookup_transform( + "world", + resource_id, + rclpy.time.Time(), + rclpy.duration.Duration(seconds=5) + ) + + # 提取当前位姿信息 + current_pose = { + "position": { + "x": transform.transform.translation.x, + "y": transform.transform.translation.y, + "z": transform.transform.translation.z + }, + "rotation": { + "x": transform.transform.rotation.x, + "y": transform.transform.rotation.y, + "z": transform.transform.rotation.z, + "w": transform.transform.rotation.w + } + } + + # 检查是否存在旧位姿记录 + if resource_id not in self.old_resource_pose: + # 如果没有旧记录,则认为是新资源,记录变化 + changed_poses[resource_id] = current_pose + self.old_resource_pose[resource_id] = current_pose + else: + # 比较当前位姿与旧位姿 + old_pose = self.old_resource_pose[resource_id] + if (not self._is_pose_equal(current_pose, old_pose)): + # 如果位姿发生变化,记录新位姿 + changed_poses[resource_id] = current_pose + self.old_resource_pose[resource_id] = current_pose + + except Exception as e: + self.get_logger().warning(f"获取资源 {resource_id} 的世界坐标变换失败: {e}") + + changed_poses_msg = String() + changed_poses_msg.data = json.dumps(changed_poses) + self.resource_pose_publisher.publish(changed_poses_msg) + + + def _is_pose_equal(self, pose1, pose2, tolerance=1e-5): + """ + 比较两个位姿是否相等(考虑浮点数精度) + + Args: + pose1: 第一个位姿 + pose2: 第二个位姿 + tolerance: 浮点数比较的容差 + + Returns: + bool: 如果位姿相等返回True,否则返回False + """ + # 比较位置 + pos1 = pose1["position"] + pos2 = pose2["position"] + if (abs(pos1["x"] - pos2["x"]) > tolerance or + abs(pos1["y"] - pos2["y"]) > tolerance or + abs(pos1["z"] - pos2["z"]) > tolerance): + return False + + # 比较旋转 + rot1 = pose1["rotation"] + rot2 = pose2["rotation"] + if (abs(rot1["x"] - rot2["x"]) > tolerance or + abs(rot1["y"] - rot2["y"]) > tolerance or + abs(rot1["z"] - rot2["z"]) > tolerance or + abs(rot1["w"] - rot2["w"]) > tolerance): + return False + + return True + + def tf_update(self, goal_handle : ServerGoalHandle): + tf_update_msg = goal_handle.request + + try: + cmd_dict = json.loads(tf_update_msg.command.replace("'",'"')) + for resource_id, target_parent in cmd_dict.items(): + + # 获取从resource_id到target_parent的转换 + transform = self.tf_buffer.lookup_transform( + target_parent, + resource_id, + rclpy.time.Time() + ) + + # 提取转换中的位置和旋转信息 + position = { + "x": transform.transform.translation.x, + "y": transform.transform.translation.y, + "z": transform.transform.translation.z + } + + rotation = { + "x": transform.transform.rotation.x, + "y": transform.transform.rotation.y, + "z": transform.transform.rotation.z, + "w": transform.transform.rotation.w + } + + self.resource_tf_dict[resource_id] = { + "parent": target_parent, + "position": position, + "rotation": rotation + } + + self.attach_collision_object(id=resource_id,link_name=target_parent) + + self.publish_resource_tf() + + except Exception as e: + self.get_logger().error(f"更新资源TF字典失败: {e}") + goal_handle.abort() + return SendCmd.Result(success=False) + goal_handle.succeed() + return SendCmd.Result(success=True) + + def publish_resource_tf(self): + """ + 发布资源之间的TF关系 + + 遍历self.resource_tf_dict中的每个元素,根据key,parent,以及position和rotation, + 发布key和parent之间的tf关系 + """ + + transforms = [] + + # 遍历资源TF字典 + resource_tf_dict = copy.deepcopy(self.resource_tf_dict) + for resource_id, tf_info in resource_tf_dict.items(): + parent = tf_info['parent'] + position = tf_info['position'] + rotation = tf_info['rotation'] + + # 创建静态变换消息 + + transform = TransformStamped() + transform.header.stamp = self.get_clock().now().to_msg() + transform.header.frame_id = parent + transform.child_frame_id = resource_id + + # 设置位置 + transform.transform.translation.x = float(position['x']) + transform.transform.translation.y = float(position['y']) + transform.transform.translation.z = float(position['z']) + + # 设置旋转 + transform.transform.rotation.x = rotation['x'] + transform.transform.rotation.y = rotation['y'] + transform.transform.rotation.z = rotation['z'] + transform.transform.rotation.w = rotation['w'] + + transforms.append(transform) + + # 一次性发布所有静态变换 + if transforms: + self.tf_broadcaster.sendTransform(transforms) + + # self.get_logger().info(f'已发布 {len(transforms)} 个资源TF关系') + + def add_resource_collision_meshes(self): + """ + 遍历资源配置字典,为每个在resource_model中有对应模型的资源添加碰撞网格 + + 该方法检查每个资源ID是否在self.resource_model中有对应的3D模型文件路径, + 如果有,则调用add_collision_mesh方法将其添加到碰撞环境中。 + """ + self.get_logger().info('开始添加资源碰撞网格') + + for resource_id, tf_info in self.resource_tf_dict.items(): + + if resource_id in self.resource_model: + # 获取位置信息 + + position = [ + float(self.resource_model[resource_id]['mesh_tf'][0]), + float(self.resource_model[resource_id]['mesh_tf'][1]), + float(self.resource_model[resource_id]['mesh_tf'][2]) + ] + + # 获取旋转信息并转换为四元数 + + q = quaternion_from_euler( + float(self.resource_model[resource_id]['mesh_tf'][3]), + float(self.resource_model[resource_id]['mesh_tf'][4]), + float(self.resource_model[resource_id]['mesh_tf'][5]) + ) + + # 添加碰撞网格 + self.add_collision_mesh( + filepath=self.resource_model[resource_id]['mesh'], + id=resource_id, + position=position, + quat_xyzw=q, + frame_id=resource_id + ) + + elif f"{tf_info['parent']}_" in self.resource_model: + # 获取资源的父级框架ID + id_ = f"{tf_info['parent']}_" + + # 获取位置信息 + position = [ + float(self.resource_model[id_]['mesh_tf'][0]), + float(self.resource_model[id_]['mesh_tf'][1]), + float(self.resource_model[id_]['mesh_tf'][2]) + ] + + # 获取旋转信息并转换为四元数 + + q = quaternion_from_euler( + float(self.resource_model[id_]['mesh_tf'][3]), + float(self.resource_model[id_]['mesh_tf'][4]), + float(self.resource_model[id_]['mesh_tf'][5]) + ) + + # 添加碰撞网格 + self.add_collision_mesh( + filepath=self.resource_model[id_]['mesh'], + id=resource_id, + position=position, + quat_xyzw=q, + frame_id=resource_id + ) + time.sleep(0.02) + + self.get_logger().info('资源碰撞网格添加完成') + + + 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': {'mesh': '/home/z43/git_pj/Uni-Lab-OS/unilabos/device_mesh/resources/tecan_nested_tip_rack/meshes/plate.stl', 'mesh_tf': [0.064, 0.043, 0, -1.5708, 0, 1.5708]}, +'Plate1_': {'mesh': '/home/z43/git_pj/Uni-Lab-OS/unilabos/device_mesh/resources/generic_labware_tube_10_75/meshes/0_base.stl', 'mesh_tf': [0.0018, 0.0018, 0, -1.5708,0, 0]}} +''' + resource_model = json.loads(model_s.replace("'",'"')) + + config_s = ''' +[ + { + "id": "Gripper1", + "name": "假夹爪", + "children": [], + "parent": null, + "type": "device", + "class": "gripper.mock", + "position": { + "x": 0, + "y": 0, + "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": 0, + "y": 0, + "z": 69 + }, + "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, DeviceNodeResourceTracker()) + # resource_mesh_manager.resource_mesh_setup() + # resource_mesh_manager.check_move_group_ready() + # resource_mesh_manager.publish_resource_tf() + # resource_mesh_manager.clear_all_collision_objects() + # print(json.dumps(resource_mesh_manager.resource_tf_dict, indent=4, ensure_ascii=False)) + + rclpy.spin(resource_mesh_manager) \ No newline at end of file