mirror of
https://github.com/dptech-corp/Uni-Lab-OS.git
synced 2025-12-18 13:31:20 +00:00
Compare commits
19 Commits
dev
...
4b30b8021f
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
4b30b8021f | ||
|
|
344e91bce3 | ||
|
|
7b8638aa03 | ||
|
|
1ca7d4912b | ||
|
|
c04202c6e0 | ||
|
|
93c40e236f | ||
|
|
460f7dd322 | ||
|
|
e5d977e884 | ||
|
|
02425f89e9 | ||
|
|
139fc2158c | ||
|
|
32b50c2680 | ||
|
|
9d2d70c804 | ||
|
|
6eac72ed27 | ||
|
|
9b4daf8e82 | ||
|
|
6795b49e6d | ||
|
|
1461e61648 | ||
|
|
4355135c80 | ||
|
|
63c6fe8427 | ||
|
|
83c765f0ab |
@@ -1,5 +1,5 @@
|
|||||||
使用plr_test.json启动,将Well加入Plate中
|
使用plr_test.json启动,将Well加入Plate中
|
||||||
|
|
||||||
```bash
|
```bash
|
||||||
ros2 action send_goal /devices/host_node/add_resource_from_outer unilabos_msgs/action/_resource_create_from_outer/ResourceCreateFromOuter "{ resources: [ { 'category': '', 'children': [], 'config': { 'type': 'Well', 'size_x': 6.86, 'size_y': 6.86, 'size_z': 10.67, 'rotation': { 'x': 0, 'y': 0, 'z': 0, 'type': 'Rotation' }, 'category': 'well', 'model': null, 'max_volume': 360, 'material_z_thickness': 0.5, 'compute_volume_from_height': null, 'compute_height_from_volume': null, 'bottom_type': 'flat', 'cross_section_type': 'circle' }, 'data': { 'liquids': [], 'pending_liquids': [], 'liquid_history': [] }, 'id': 'plate_well_11_7', 'name': 'plate_well_11_7', 'pose': { 'orientation': { 'w': 1.0, 'x': 0.0, 'y': 0.0, 'z': 0.0 }, 'position': { 'x': 0.0, 'y': 0.0, 'z': 0.0 } }, 'sample_id': '', 'parent': 'plate', 'type': 'device' } ], device_ids: [ 'PLR_STATION' ], bind_parent_ids: [ 'plate' ], bind_locations: [ { 'x': 0.0, 'y': 0.0, 'z': 0.0 } ], other_calling_params: [ '{}' ] }"
|
ros2 action send_goal /devices/host_node/create_resource_detailed unilabos_msgs/action/_resource_create_from_outer/ResourceCreateFromOuter "{ resources: [ { 'category': '', 'children': [], 'config': { 'type': 'Well', 'size_x': 6.86, 'size_y': 6.86, 'size_z': 10.67, 'rotation': { 'x': 0, 'y': 0, 'z': 0, 'type': 'Rotation' }, 'category': 'well', 'model': null, 'max_volume': 360, 'material_z_thickness': 0.5, 'compute_volume_from_height': null, 'compute_height_from_volume': null, 'bottom_type': 'flat', 'cross_section_type': 'circle' }, 'data': { 'liquids': [], 'pending_liquids': [], 'liquid_history': [] }, 'id': 'plate_well_11_7', 'name': 'plate_well_11_7', 'pose': { 'orientation': { 'w': 1.0, 'x': 0.0, 'y': 0.0, 'z': 0.0 }, 'position': { 'x': 0.0, 'y': 0.0, 'z': 0.0 } }, 'sample_id': '', 'parent': 'plate', 'type': 'device' } ], device_ids: [ 'PLR_STATION' ], bind_parent_ids: [ 'plate' ], bind_locations: [ { 'x': 0.0, 'y': 0.0, 'z': 0.0 } ], other_calling_params: [ '{}' ] }"
|
||||||
```
|
```
|
||||||
@@ -56,6 +56,8 @@ dependencies:
|
|||||||
- ros-humble-moveit-servo
|
- ros-humble-moveit-servo
|
||||||
# simulation
|
# simulation
|
||||||
- ros-humble-simulation
|
- ros-humble-simulation
|
||||||
|
- ros-humble-tf-transformations
|
||||||
|
- transforms3d
|
||||||
# ros-humble-gazebo-ros // ignored because of the conflict with ign-gazebo
|
# ros-humble-gazebo-ros // ignored because of the conflict with ign-gazebo
|
||||||
# ilab equipments
|
# ilab equipments
|
||||||
# - ros-humble-unilabos-msgs
|
# - ros-humble-unilabos-msgs
|
||||||
|
|||||||
@@ -56,6 +56,8 @@ dependencies:
|
|||||||
# - ros-humble-moveit-servo
|
# - ros-humble-moveit-servo
|
||||||
# simulation
|
# simulation
|
||||||
- ros-humble-simulation
|
- ros-humble-simulation
|
||||||
|
- ros-humble-tf-transformations
|
||||||
|
- transforms3d
|
||||||
# ros-humble-gazebo-ros // ignored because of the conflict with ign-gazebo
|
# ros-humble-gazebo-ros // ignored because of the conflict with ign-gazebo
|
||||||
# ilab equipments
|
# ilab equipments
|
||||||
# - ros-humble-unilabos-msgs
|
# - ros-humble-unilabos-msgs
|
||||||
|
|||||||
@@ -58,6 +58,8 @@ dependencies:
|
|||||||
- ros-humble-moveit-servo
|
- ros-humble-moveit-servo
|
||||||
# simulation
|
# simulation
|
||||||
- ros-humble-simulation
|
- ros-humble-simulation
|
||||||
|
- ros-humble-tf-transformations
|
||||||
|
- transforms3d
|
||||||
# ros-humble-gazebo-ros // ignored because of the conflict with ign-gazebo
|
# ros-humble-gazebo-ros // ignored because of the conflict with ign-gazebo
|
||||||
# ilab equipments
|
# ilab equipments
|
||||||
# - ros-humble-unilabos-msgs
|
# - ros-humble-unilabos-msgs
|
||||||
|
|||||||
@@ -56,6 +56,8 @@ dependencies:
|
|||||||
- ros-humble-moveit-servo
|
- ros-humble-moveit-servo
|
||||||
# simulation
|
# simulation
|
||||||
- ros-humble-simulation # ignored because of NO python3.11 package in WIN64
|
- ros-humble-simulation # ignored because of NO python3.11 package in WIN64
|
||||||
|
- ros-humble-tf-transformations
|
||||||
|
- transforms3d
|
||||||
# ros-humble-gazebo-ros // ignored because of the conflict with ign-gazebo
|
# ros-humble-gazebo-ros // ignored because of the conflict with ign-gazebo
|
||||||
# ilab equipments
|
# ilab equipments
|
||||||
# ros-humble-unilabos-msgs
|
# ros-humble-unilabos-msgs
|
||||||
|
|||||||
@@ -18,7 +18,6 @@ if unilabos_dir not in sys.path:
|
|||||||
|
|
||||||
from unilabos.config.config import load_config, BasicConfig, _update_config_from_env
|
from unilabos.config.config import load_config, BasicConfig, _update_config_from_env
|
||||||
from unilabos.utils.banner_print import print_status, print_unilab_banner
|
from unilabos.utils.banner_print import print_status, print_unilab_banner
|
||||||
from unilabos.device_mesh.resource_visalization import ResourceVisualization
|
|
||||||
|
|
||||||
|
|
||||||
def parse_args():
|
def parse_args():
|
||||||
@@ -188,11 +187,12 @@ def main():
|
|||||||
if args_dict["visual"] != "disable":
|
if args_dict["visual"] != "disable":
|
||||||
enable_rviz = args_dict["visual"] == "rviz"
|
enable_rviz = args_dict["visual"] == "rviz"
|
||||||
if devices_and_resources is not None:
|
if devices_and_resources is not None:
|
||||||
|
from unilabos.device_mesh.resource_visalization import ResourceVisualization # 此处开启后,logger会变更为INFO,有需要请调整
|
||||||
resource_visualization = ResourceVisualization(devices_and_resources, args_dict["resources_config"] ,enable_rviz=enable_rviz)
|
resource_visualization = ResourceVisualization(devices_and_resources, args_dict["resources_config"] ,enable_rviz=enable_rviz)
|
||||||
args_dict["resources_mesh_config"] = resource_visualization.resource_model
|
args_dict["resources_mesh_config"] = resource_visualization.resource_model
|
||||||
start_backend(**args_dict)
|
start_backend(**args_dict)
|
||||||
server_thread = threading.Thread(target=start_server, kwargs=dict(
|
server_thread = threading.Thread(target=start_server, kwargs=dict(
|
||||||
open_browser=not args_dict["disable_browser"]
|
open_browser=not args_dict["disable_browser"], port=args_dict["port"],
|
||||||
))
|
))
|
||||||
server_thread.start()
|
server_thread.start()
|
||||||
asyncio.set_event_loop(asyncio.new_event_loop())
|
asyncio.set_event_loop(asyncio.new_event_loop())
|
||||||
@@ -201,10 +201,10 @@ def main():
|
|||||||
time.sleep(1)
|
time.sleep(1)
|
||||||
else:
|
else:
|
||||||
start_backend(**args_dict)
|
start_backend(**args_dict)
|
||||||
start_server(open_browser=not args_dict["disable_browser"])
|
start_server(open_browser=not args_dict["disable_browser"], port=args_dict["port"],)
|
||||||
else:
|
else:
|
||||||
start_backend(**args_dict)
|
start_backend(**args_dict)
|
||||||
start_server(open_browser=not args_dict["disable_browser"])
|
start_server(open_browser=not args_dict["disable_browser"], port=args_dict["port"],)
|
||||||
|
|
||||||
|
|
||||||
if __name__ == "__main__":
|
if __name__ == "__main__":
|
||||||
|
|||||||
@@ -26,6 +26,7 @@ class MQTTClient:
|
|||||||
def __init__(self):
|
def __init__(self):
|
||||||
self.mqtt_disable = not MQConfig.lab_id
|
self.mqtt_disable = not MQConfig.lab_id
|
||||||
self.client_id = f"{MQConfig.group_id}@@@{MQConfig.lab_id}{uuid.uuid4()}"
|
self.client_id = f"{MQConfig.group_id}@@@{MQConfig.lab_id}{uuid.uuid4()}"
|
||||||
|
logger.info("[MQTT] Client_id: " + self.client_id)
|
||||||
self.client = mqtt.Client(CallbackAPIVersion.VERSION2, client_id=self.client_id, protocol=mqtt.MQTTv5)
|
self.client = mqtt.Client(CallbackAPIVersion.VERSION2, client_id=self.client_id, protocol=mqtt.MQTTv5)
|
||||||
self._setup_callbacks()
|
self._setup_callbacks()
|
||||||
|
|
||||||
@@ -52,10 +53,7 @@ class MQTTClient:
|
|||||||
try:
|
try:
|
||||||
payload_str = msg.payload.decode("utf-8")
|
payload_str = msg.payload.decode("utf-8")
|
||||||
payload_json = json.loads(payload_str)
|
payload_json = json.loads(payload_str)
|
||||||
logger.debug(f"Topic: {msg.topic}")
|
|
||||||
logger.debug("Payload:", json.dumps(payload_json, indent=2, ensure_ascii=False))
|
|
||||||
if msg.topic == f"labs/{MQConfig.lab_id}/job/start/":
|
if msg.topic == f"labs/{MQConfig.lab_id}/job/start/":
|
||||||
logger.debug("job_add", type(payload_json), payload_json)
|
|
||||||
if "data" not in payload_json:
|
if "data" not in payload_json:
|
||||||
payload_json["data"] = {}
|
payload_json["data"] = {}
|
||||||
if "action" in payload_json:
|
if "action" in payload_json:
|
||||||
|
|||||||
0
unilabos/devices/laiyu_add_solid/__init__.py
Normal file
0
unilabos/devices/laiyu_add_solid/__init__.py
Normal file
@@ -14,7 +14,7 @@ from pylabrobot.resources import (
|
|||||||
Well
|
Well
|
||||||
)
|
)
|
||||||
|
|
||||||
class DPLiquidHandler(LiquidHandler):
|
class LiquidHandlerAbstract(LiquidHandler):
|
||||||
"""Extended LiquidHandler with additional operations."""
|
"""Extended LiquidHandler with additional operations."""
|
||||||
|
|
||||||
# ---------------------------------------------------------------
|
# ---------------------------------------------------------------
|
||||||
@@ -1,11 +1,96 @@
|
|||||||
liquid_handler:
|
liquid_handler:
|
||||||
description: Liquid handler device controlled by pylabrobot
|
description: Liquid handler device controlled by pylabrobot
|
||||||
class:
|
class:
|
||||||
module: pylabrobot.liquid_handling:LiquidHandler
|
module: unilabos.devices.liquid_handling.liquid_handler_abstract:LiquidHandlerAbstract
|
||||||
type: python
|
type: python
|
||||||
status_types:
|
status_types:
|
||||||
name: String
|
name: String
|
||||||
action_value_mappings:
|
action_value_mappings:
|
||||||
|
remove:
|
||||||
|
type: LiquidHandlerRemove
|
||||||
|
goal:
|
||||||
|
vols: vols
|
||||||
|
sources: sources
|
||||||
|
waste_liquid: waste_liquid
|
||||||
|
use_channels: use_channels
|
||||||
|
flow_rates: flow_rates
|
||||||
|
offsets: offsets
|
||||||
|
liquid_height: liquid_height
|
||||||
|
blow_out_air_volume: blow_out_air_volume
|
||||||
|
spread: spread
|
||||||
|
delays: delays
|
||||||
|
is_96_well: is_96_well
|
||||||
|
top: top
|
||||||
|
none_keys: none_keys
|
||||||
|
feedback: { }
|
||||||
|
result: { }
|
||||||
|
add_liquid:
|
||||||
|
type: LiquidHandlerAdd
|
||||||
|
goal:
|
||||||
|
asp_vols: asp_vols
|
||||||
|
dis_vols: dis_vols
|
||||||
|
reagent_sources: reagent_sources
|
||||||
|
targets: targets
|
||||||
|
use_channels: use_channels
|
||||||
|
flow_rates: flow_rates
|
||||||
|
offsets: offsets
|
||||||
|
liquid_height: liquid_height
|
||||||
|
blow_out_air_volume: blow_out_air_volume
|
||||||
|
spread: spread
|
||||||
|
is_96_well: is_96_well
|
||||||
|
mix_time: mix_time
|
||||||
|
mix_vol: mix_vol
|
||||||
|
mix_rate: mix_rate
|
||||||
|
mix_liquid_height: mix_liquid_height
|
||||||
|
none_keys: none_keys
|
||||||
|
feedback: { }
|
||||||
|
result: { }
|
||||||
|
transfer_liquid:
|
||||||
|
type: LiquidHandlerTransfer
|
||||||
|
goal:
|
||||||
|
asp_vols: asp_vols
|
||||||
|
dis_vols: dis_vols
|
||||||
|
sources: sources
|
||||||
|
targets: targets
|
||||||
|
tip_racks: tip_racks
|
||||||
|
use_channels: use_channels
|
||||||
|
asp_flow_rates: asp_flow_rates
|
||||||
|
dis_flow_rates: dis_flow_rates
|
||||||
|
offsets: offsets
|
||||||
|
touch_tip: touch_tip
|
||||||
|
liquid_height: liquid_height
|
||||||
|
blow_out_air_volume: blow_out_air_volume
|
||||||
|
spread: spread
|
||||||
|
is_96_well: is_96_well
|
||||||
|
mix_stage: mix_stage
|
||||||
|
mix_times: mix_times
|
||||||
|
mix_vol: mix_vol
|
||||||
|
mix_rate: mix_rate
|
||||||
|
mix_liquid_height: mix_liquid_height
|
||||||
|
delays: delays
|
||||||
|
none_keys: none_keys
|
||||||
|
feedback: { }
|
||||||
|
result: { }
|
||||||
|
mix:
|
||||||
|
type: LiquidHandlerMix
|
||||||
|
goal:
|
||||||
|
targets: targets
|
||||||
|
mix_time: mix_time
|
||||||
|
mix_vol: mix_vol
|
||||||
|
height_to_bottom: height_to_bottom
|
||||||
|
offsets: offsets
|
||||||
|
mix_rate: mix_rate
|
||||||
|
none_keys: none_keys
|
||||||
|
feedback: { }
|
||||||
|
result: { }
|
||||||
|
move_to:
|
||||||
|
type: LiquidHandlerMoveTo
|
||||||
|
goal:
|
||||||
|
well: well
|
||||||
|
dis_to_top: dis_to_top
|
||||||
|
channel: channel
|
||||||
|
feedback: { }
|
||||||
|
result: { }
|
||||||
aspirate:
|
aspirate:
|
||||||
type: LiquidHandlerAspirate
|
type: LiquidHandlerAspirate
|
||||||
goal:
|
goal:
|
||||||
@@ -170,127 +255,6 @@ liquid_handler:
|
|||||||
- name
|
- name
|
||||||
additionalProperties: false
|
additionalProperties: false
|
||||||
|
|
||||||
dp_liquid_handler:
|
|
||||||
description: 通用液体处理
|
|
||||||
class:
|
|
||||||
module: unilabos.devices.liquid_handling.action_definition:DPLiquidHandler
|
|
||||||
type: python
|
|
||||||
status_types:
|
|
||||||
status: String
|
|
||||||
action_value_mappings:
|
|
||||||
remove_liquid:
|
|
||||||
type: DPLiquidHandlerRemoveLiquid
|
|
||||||
goal:
|
|
||||||
vols: vols
|
|
||||||
sources: sources
|
|
||||||
waste_liquid: waste_liquid
|
|
||||||
use_channels: use_channels
|
|
||||||
flow_rates: flow_rates
|
|
||||||
offsets: offsets
|
|
||||||
liquid_height: liquid_height
|
|
||||||
blow_out_air_volume: blow_out_air_volume
|
|
||||||
spread: spread
|
|
||||||
delays: delays
|
|
||||||
is_96_well: is_96_well
|
|
||||||
top: top
|
|
||||||
none_keys: none_keys
|
|
||||||
feedback: {}
|
|
||||||
result: {}
|
|
||||||
add_liquid:
|
|
||||||
type: DPLiquidHandlerAddLiquid
|
|
||||||
goal:
|
|
||||||
asp_vols: asp_vols
|
|
||||||
dis_vols: dis_vols
|
|
||||||
reagent_sources: reagent_sources
|
|
||||||
targets: targets
|
|
||||||
use_channels: use_channels
|
|
||||||
flow_rates: flow_rates
|
|
||||||
offsets: offsets
|
|
||||||
liquid_height: liquid_height
|
|
||||||
blow_out_air_volume: blow_out_air_volume
|
|
||||||
spread: spread
|
|
||||||
is_96_well: is_96_well
|
|
||||||
mix_time: mix_time
|
|
||||||
mix_vol: mix_vol
|
|
||||||
mix_rate: mix_rate
|
|
||||||
mix_liquid_height: mix_liquid_height
|
|
||||||
none_keys: none_keys
|
|
||||||
feedback: {}
|
|
||||||
result: {}
|
|
||||||
transfer_liquid:
|
|
||||||
type: DPLiquidHandlerTransferLiquid
|
|
||||||
goal:
|
|
||||||
asp_vols: asp_vols
|
|
||||||
dis_vols: dis_vols
|
|
||||||
sources: sources
|
|
||||||
targets: targets
|
|
||||||
tip_racks: tip_racks
|
|
||||||
use_channels: use_channels
|
|
||||||
asp_flow_rates: asp_flow_rates
|
|
||||||
dis_flow_rates: dis_flow_rates
|
|
||||||
offsets: offsets
|
|
||||||
touch_tip: touch_tip
|
|
||||||
liquid_height: liquid_height
|
|
||||||
blow_out_air_volume: blow_out_air_volume
|
|
||||||
spread: spread
|
|
||||||
is_96_well: is_96_well
|
|
||||||
mix_stage: mix_stage
|
|
||||||
mix_times: mix_times
|
|
||||||
mix_vol: mix_vol
|
|
||||||
mix_rate: mix_rate
|
|
||||||
mix_liquid_height: mix_liquid_height
|
|
||||||
delays: delays
|
|
||||||
none_keys: none_keys
|
|
||||||
feedback: {}
|
|
||||||
result: {}
|
|
||||||
custom_delay:
|
|
||||||
type: DPLiquidHandlerCustomDelay
|
|
||||||
goal:
|
|
||||||
seconds: seconds
|
|
||||||
msg: msg
|
|
||||||
feedback: {}
|
|
||||||
result: {}
|
|
||||||
touch_tip:
|
|
||||||
type: DPLiquidHandlerTouchTip
|
|
||||||
goal:
|
|
||||||
targets: targets
|
|
||||||
feedback: {}
|
|
||||||
result: {}
|
|
||||||
mix:
|
|
||||||
type: DPLiquidHandlerMix
|
|
||||||
goal:
|
|
||||||
targets: targets
|
|
||||||
mix_time: mix_time
|
|
||||||
mix_vol: mix_vol
|
|
||||||
height_to_bottom: height_to_bottom
|
|
||||||
offsets: offsets
|
|
||||||
mix_rate: mix_rate
|
|
||||||
none_keys: none_keys
|
|
||||||
feedback: {}
|
|
||||||
result: {}
|
|
||||||
set_tiprack:
|
|
||||||
type: DPLiquidHandlerSetTiprack
|
|
||||||
goal:
|
|
||||||
tip_racks: tip_racks
|
|
||||||
feedback: {}
|
|
||||||
result: {}
|
|
||||||
move_to:
|
|
||||||
type: DPLiquidHandlerMoveTo
|
|
||||||
goal:
|
|
||||||
well: well
|
|
||||||
dis_to_top: dis_to_top
|
|
||||||
channel: channel
|
|
||||||
feedback: {}
|
|
||||||
result: {}
|
|
||||||
schema:
|
|
||||||
type: object
|
|
||||||
properties:
|
|
||||||
name:
|
|
||||||
type: string
|
|
||||||
description: 物料名
|
|
||||||
required:
|
|
||||||
- name
|
|
||||||
|
|
||||||
liquid_handler.revvity:
|
liquid_handler.revvity:
|
||||||
class:
|
class:
|
||||||
module: unilabos.devices.liquid_handling.revvity:Revvity
|
module: unilabos.devices.liquid_handling.revvity:Revvity
|
||||||
|
|||||||
@@ -1,5 +1,4 @@
|
|||||||
import io
|
import io
|
||||||
import json
|
|
||||||
import os
|
import os
|
||||||
import sys
|
import sys
|
||||||
from pathlib import Path
|
from pathlib import Path
|
||||||
@@ -7,10 +6,9 @@ from typing import Any
|
|||||||
|
|
||||||
import yaml
|
import yaml
|
||||||
|
|
||||||
from unilabos.utils import logger
|
|
||||||
from unilabos.ros.msgs.message_converter import msg_converter_manager, ros_action_to_json_schema
|
from unilabos.ros.msgs.message_converter import msg_converter_manager, ros_action_to_json_schema
|
||||||
|
from unilabos.utils import logger
|
||||||
from unilabos.utils.decorator import singleton
|
from unilabos.utils.decorator import singleton
|
||||||
from unilabos.utils.type_check import TypeEncoder
|
|
||||||
|
|
||||||
DEFAULT_PATHS = [Path(__file__).absolute().parent]
|
DEFAULT_PATHS = [Path(__file__).absolute().parent]
|
||||||
|
|
||||||
@@ -21,10 +19,12 @@ class Registry:
|
|||||||
self.registry_paths = DEFAULT_PATHS.copy() # 使用copy避免修改默认值
|
self.registry_paths = DEFAULT_PATHS.copy() # 使用copy避免修改默认值
|
||||||
if registry_paths:
|
if registry_paths:
|
||||||
self.registry_paths.extend(registry_paths)
|
self.registry_paths.extend(registry_paths)
|
||||||
action_type = self._replace_type_with_class(
|
self.ResourceCreateFromOuter = self._replace_type_with_class(
|
||||||
"ResourceCreateFromOuter", "host_node", f"动作 add_resource_from_outer"
|
"ResourceCreateFromOuter", "host_node", f"动作 create_resource_detailed"
|
||||||
|
)
|
||||||
|
self.ResourceCreateFromOuterEasy = self._replace_type_with_class(
|
||||||
|
"ResourceCreateFromOuterEasy", "host_node", f"动作 create_resource"
|
||||||
)
|
)
|
||||||
schema = ros_action_to_json_schema(action_type)
|
|
||||||
self.device_type_registry = {
|
self.device_type_registry = {
|
||||||
"host_node": {
|
"host_node": {
|
||||||
"description": "UniLabOS主机节点",
|
"description": "UniLabOS主机节点",
|
||||||
@@ -33,7 +33,7 @@ class Registry:
|
|||||||
"type": "python",
|
"type": "python",
|
||||||
"status_types": {},
|
"status_types": {},
|
||||||
"action_value_mappings": {
|
"action_value_mappings": {
|
||||||
"add_resource_from_outer": {
|
"create_resource_detailed": {
|
||||||
"type": msg_converter_manager.search_class("ResourceCreateFromOuter"),
|
"type": msg_converter_manager.search_class("ResourceCreateFromOuter"),
|
||||||
"goal": {
|
"goal": {
|
||||||
"resources": "resources",
|
"resources": "resources",
|
||||||
@@ -46,7 +46,26 @@ class Registry:
|
|||||||
"result": {
|
"result": {
|
||||||
"success": "success"
|
"success": "success"
|
||||||
},
|
},
|
||||||
"schema": schema
|
"schema": ros_action_to_json_schema(self.ResourceCreateFromOuter)
|
||||||
|
},
|
||||||
|
"create_resource": {
|
||||||
|
"type": msg_converter_manager.search_class("ResourceCreateFromOuterEasy"),
|
||||||
|
"goal": {
|
||||||
|
"res_id": "res_id",
|
||||||
|
"class_name": "class_name",
|
||||||
|
"parent": "parent",
|
||||||
|
"device_id": "device_id",
|
||||||
|
"bind_locations": "bind_locations",
|
||||||
|
"liquid_input_slot": "liquid_input_slot[]",
|
||||||
|
"liquid_type": "liquid_type[]",
|
||||||
|
"liquid_volume": "liquid_volume[]",
|
||||||
|
"slot_on_deck": "slot_on_deck",
|
||||||
|
},
|
||||||
|
"feedback": {},
|
||||||
|
"result": {
|
||||||
|
"success": "success"
|
||||||
|
},
|
||||||
|
"schema": ros_action_to_json_schema(self.ResourceCreateFromOuterEasy)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
|
|||||||
@@ -1,35 +1,35 @@
|
|||||||
agilent_1_reservoir_290ml:
|
agilent_1_reservoir_290ml:
|
||||||
description: Agilent 1 reservoir 290ml
|
description: Agilent 1 reservoir 290ml
|
||||||
class:
|
class:
|
||||||
module: pylabrobot.resources.opentrons.reserviors:agilent_1_reservoir_290ml
|
module: pylabrobot.resources.opentrons.reservoirs:agilent_1_reservoir_290ml
|
||||||
type: pylabrobot
|
type: pylabrobot
|
||||||
|
|
||||||
axygen_1_reservoir_90ml:
|
axygen_1_reservoir_90ml:
|
||||||
description: Axygen 1 reservoir 90ml
|
description: Axygen 1 reservoir 90ml
|
||||||
class:
|
class:
|
||||||
module: pylabrobot.resources.opentrons.reserviors:axygen_1_reservoir_90ml
|
module: pylabrobot.resources.opentrons.reservoirs:axygen_1_reservoir_90ml
|
||||||
type: pylabrobot
|
type: pylabrobot
|
||||||
|
|
||||||
nest_12_reservoir_15ml:
|
nest_12_reservoir_15ml:
|
||||||
description: Nest 12 reservoir 15ml
|
description: Nest 12 reservoir 15ml
|
||||||
class:
|
class:
|
||||||
module: pylabrobot.resources.opentrons.reserviors:nest_12_reservoir_15ml
|
module: pylabrobot.resources.opentrons.reservoirs:nest_12_reservoir_15ml
|
||||||
type: pylabrobot
|
type: pylabrobot
|
||||||
|
|
||||||
nest_1_reservoir_195ml:
|
nest_1_reservoir_195ml:
|
||||||
description: Nest 1 reservoir 195ml
|
description: Nest 1 reservoir 195ml
|
||||||
class:
|
class:
|
||||||
module: pylabrobot.resources.opentrons.reserviors:nest_1_reservoir_195ml
|
module: pylabrobot.resources.opentrons.reservoirs:nest_1_reservoir_195ml
|
||||||
type: pylabrobot
|
type: pylabrobot
|
||||||
|
|
||||||
nest_1_reservoir_290ml:
|
nest_1_reservoir_290ml:
|
||||||
description: Nest 1 reservoir 290ml
|
description: Nest 1 reservoir 290ml
|
||||||
class:
|
class:
|
||||||
module: pylabrobot.resources.opentrons.reserviors:nest_1_reservoir_290ml
|
module: pylabrobot.resources.opentrons.reservoirs:nest_1_reservoir_290ml
|
||||||
type: pylabrobot
|
type: pylabrobot
|
||||||
|
|
||||||
usascientific_12_reservoir_22ml:
|
usascientific_12_reservoir_22ml:
|
||||||
description: USAScientific 12 reservoir 22ml
|
description: USAScientific 12 reservoir 22ml
|
||||||
class:
|
class:
|
||||||
module: pylabrobot.resources.opentrons.reserviors:usascientific_12_reservoir_22ml
|
module: pylabrobot.resources.opentrons.reservoirs:usascientific_12_reservoir_22ml
|
||||||
type: pylabrobot
|
type: pylabrobot
|
||||||
|
|||||||
@@ -189,6 +189,7 @@ def dict_from_graph(graph: nx.Graph) -> dict:
|
|||||||
def dict_to_tree(nodes: dict, devices_only: bool = False) -> list[dict]:
|
def dict_to_tree(nodes: dict, devices_only: bool = False) -> list[dict]:
|
||||||
# 将节点转换为字典,以便通过 ID 快速查找
|
# 将节点转换为字典,以便通过 ID 快速查找
|
||||||
nodes_list = [node for node in nodes.values() if node.get("type") == "device" or not devices_only]
|
nodes_list = [node for node in nodes.values() if node.get("type") == "device" or not devices_only]
|
||||||
|
id_list = [node["id"] for node in nodes_list]
|
||||||
|
|
||||||
# 初始化每个节点的 children 为包含节点字典的列表
|
# 初始化每个节点的 children 为包含节点字典的列表
|
||||||
for node in nodes_list:
|
for node in nodes_list:
|
||||||
@@ -196,7 +197,7 @@ def dict_to_tree(nodes: dict, devices_only: bool = False) -> list[dict]:
|
|||||||
|
|
||||||
# 找到根节点并返回
|
# 找到根节点并返回
|
||||||
root_nodes = [
|
root_nodes = [
|
||||||
node for node in nodes_list if len(nodes_list) == 1 or node.get("parent", node.get("parent_name")) in [None, "", "None", np.nan]
|
node for node in nodes_list if len(nodes_list) == 1 or node.get("parent", node.get("parent_name")) in [None, "", "None", np.nan] or node.get("parent", node.get("parent_name")) not in id_list
|
||||||
]
|
]
|
||||||
|
|
||||||
# 如果存在多个根节点,返回所有根节点
|
# 如果存在多个根节点,返回所有根节点
|
||||||
@@ -421,7 +422,7 @@ def resource_plr_to_ulab(resource_plr: "ResourcePLR", parent_name: str = None):
|
|||||||
return r
|
return r
|
||||||
|
|
||||||
|
|
||||||
def initialize_resource(resource_config: dict, lab_registry: dict) -> list[dict]:
|
def initialize_resource(resource_config: dict) -> list[dict]:
|
||||||
"""Initializes a resource based on its configuration.
|
"""Initializes a resource based on its configuration.
|
||||||
|
|
||||||
If the config is detailed, then do nothing;
|
If the config is detailed, then do nothing;
|
||||||
@@ -433,6 +434,7 @@ def initialize_resource(resource_config: dict, lab_registry: dict) -> list[dict]
|
|||||||
Returns:
|
Returns:
|
||||||
None
|
None
|
||||||
"""
|
"""
|
||||||
|
from unilabos.registry.registry import lab_registry
|
||||||
resource_class_config = resource_config.get("class", None)
|
resource_class_config = resource_config.get("class", None)
|
||||||
if resource_class_config is None:
|
if resource_class_config is None:
|
||||||
return [resource_config]
|
return [resource_config]
|
||||||
@@ -476,11 +478,8 @@ def initialize_resources(resources_config) -> list[dict]:
|
|||||||
None
|
None
|
||||||
"""
|
"""
|
||||||
|
|
||||||
from unilabos.registry.registry import lab_registry
|
|
||||||
resources = []
|
resources = []
|
||||||
for resource_config in resources_config:
|
for resource_config in resources_config:
|
||||||
if resource_config["parent"] == "tip_rack" or resource_config["parent"] == "plate_well":
|
resources.extend(initialize_resource(resource_config))
|
||||||
continue
|
|
||||||
resources.extend(initialize_resource(resource_config, lab_registry))
|
|
||||||
|
|
||||||
return resources
|
return resources
|
||||||
|
|||||||
@@ -348,10 +348,16 @@ def convert_to_ros_msg(ros_msg_type: Union[Type, Any], obj: Any) -> Any:
|
|||||||
if isinstance(td, NamespacedType):
|
if isinstance(td, NamespacedType):
|
||||||
target_class = msg_converter_manager.get_class(f"{'.'.join(td.namespaces)}.{td.name}")
|
target_class = msg_converter_manager.get_class(f"{'.'.join(td.namespaces)}.{td.name}")
|
||||||
setattr(ros_msg, key, [convert_to_ros_msg(target_class, v) for v in value])
|
setattr(ros_msg, key, [convert_to_ros_msg(target_class, v) for v in value])
|
||||||
|
elif isinstance(td, UnboundedString):
|
||||||
|
setattr(ros_msg, key, value)
|
||||||
else:
|
else:
|
||||||
|
logger.warning(f"Not Supported type: {td}")
|
||||||
setattr(ros_msg, key, []) # FIXME
|
setattr(ros_msg, key, []) # FIXME
|
||||||
elif "array.array" in str(type(attr)):
|
elif "array.array" in str(type(attr)):
|
||||||
setattr(ros_msg, key, value)
|
if attr.typecode == "f":
|
||||||
|
setattr(ros_msg, key, [float(i) for i in value])
|
||||||
|
else:
|
||||||
|
setattr(ros_msg, key, value)
|
||||||
else:
|
else:
|
||||||
nested_ros_msg = convert_to_ros_msg(type(attr)(), value)
|
nested_ros_msg = convert_to_ros_msg(type(attr)(), value)
|
||||||
setattr(ros_msg, key, nested_ros_msg)
|
setattr(ros_msg, key, nested_ros_msg)
|
||||||
@@ -574,6 +580,7 @@ basic_type_map = {
|
|||||||
'int64': {'type': 'integer'},
|
'int64': {'type': 'integer'},
|
||||||
'uint64': {'type': 'integer', 'minimum': 0},
|
'uint64': {'type': 'integer', 'minimum': 0},
|
||||||
'double': {'type': 'number'},
|
'double': {'type': 'number'},
|
||||||
|
'float': {'type': 'number'},
|
||||||
'float32': {'type': 'number'},
|
'float32': {'type': 'number'},
|
||||||
'float64': {'type': 'number'},
|
'float64': {'type': 'number'},
|
||||||
'string': {'type': 'string'},
|
'string': {'type': 'string'},
|
||||||
|
|||||||
@@ -1,3 +1,4 @@
|
|||||||
|
import copy
|
||||||
import functools
|
import functools
|
||||||
import json
|
import json
|
||||||
import threading
|
import threading
|
||||||
@@ -20,7 +21,7 @@ from unilabos_msgs.action import SendCmd
|
|||||||
from unilabos_msgs.srv._serial_command import SerialCommand_Request, SerialCommand_Response
|
from unilabos_msgs.srv._serial_command import SerialCommand_Request, SerialCommand_Response
|
||||||
|
|
||||||
from unilabos.resources.graphio import convert_resources_to_type, convert_resources_from_type, resource_ulab_to_plr, \
|
from unilabos.resources.graphio import convert_resources_to_type, convert_resources_from_type, resource_ulab_to_plr, \
|
||||||
initialize_resources
|
initialize_resources, list_to_nested_dict, dict_to_tree, resource_plr_to_ulab, tree_to_list
|
||||||
from unilabos.ros.msgs.message_converter import (
|
from unilabos.ros.msgs.message_converter import (
|
||||||
convert_to_ros_msg,
|
convert_to_ros_msg,
|
||||||
convert_from_ros_msg,
|
convert_from_ros_msg,
|
||||||
@@ -312,7 +313,10 @@ class BaseROS2DeviceNode(Node, Generic[T]):
|
|||||||
# 物料传输到对应的node节点
|
# 物料传输到对应的node节点
|
||||||
rclient = self.create_client(ResourceAdd, "/resources/add")
|
rclient = self.create_client(ResourceAdd, "/resources/add")
|
||||||
rclient.wait_for_service()
|
rclient.wait_for_service()
|
||||||
|
rclient2 = self.create_client(ResourceAdd, "/resources/add")
|
||||||
|
rclient2.wait_for_service()
|
||||||
request = ResourceAdd.Request()
|
request = ResourceAdd.Request()
|
||||||
|
request2 = ResourceAdd.Request()
|
||||||
command_json = json.loads(req.command)
|
command_json = json.loads(req.command)
|
||||||
namespace = command_json["namespace"]
|
namespace = command_json["namespace"]
|
||||||
bind_parent_id = command_json["bind_parent_id"]
|
bind_parent_id = command_json["bind_parent_id"]
|
||||||
@@ -321,11 +325,23 @@ class BaseROS2DeviceNode(Node, Generic[T]):
|
|||||||
other_calling_param = command_json["other_calling_param"]
|
other_calling_param = command_json["other_calling_param"]
|
||||||
resources = command_json["resource"]
|
resources = command_json["resource"]
|
||||||
initialize_full = other_calling_param.pop("initialize_full", False)
|
initialize_full = other_calling_param.pop("initialize_full", False)
|
||||||
|
# 用来增加液体
|
||||||
|
ADD_LIQUID_TYPE = other_calling_param.pop("ADD_LIQUID_TYPE", [])
|
||||||
|
LIQUID_VOLUME = other_calling_param.pop("LIQUID_VOLUME", [])
|
||||||
|
LIQUID_INPUT_SLOT = other_calling_param.pop("LIQUID_INPUT_SLOT", [])
|
||||||
|
slot = other_calling_param.pop("slot", -1)
|
||||||
|
if slot >= 0: # slot为负数的时候采用assign方法
|
||||||
|
other_calling_param["slot"] = slot
|
||||||
# 本地拿到这个物料,可能需要先做初始化?
|
# 本地拿到这个物料,可能需要先做初始化?
|
||||||
if isinstance(resources, list):
|
if isinstance(resources, list):
|
||||||
if initialize_full:
|
if len(resources) == 1 and isinstance(resources[0], list) and not initialize_full: # 取消,不存在的情况
|
||||||
|
# 预先initialize过,以整组的形式传入
|
||||||
|
request.resources = [convert_to_ros_msg(Resource, resource_) for resource_ in resources[0]]
|
||||||
|
elif initialize_full:
|
||||||
resources = initialize_resources(resources)
|
resources = initialize_resources(resources)
|
||||||
request.resources = [convert_to_ros_msg(Resource, resource) for resource in resources]
|
request.resources = [convert_to_ros_msg(Resource, resource) for resource in resources]
|
||||||
|
else:
|
||||||
|
request.resources = [convert_to_ros_msg(Resource, resource) for resource in resources]
|
||||||
else:
|
else:
|
||||||
if initialize_full:
|
if initialize_full:
|
||||||
resources = initialize_resources([resources])
|
resources = initialize_resources([resources])
|
||||||
@@ -335,20 +351,31 @@ class BaseROS2DeviceNode(Node, Generic[T]):
|
|||||||
res.response = "OK"
|
res.response = "OK"
|
||||||
# 接下来该根据bind_parent_id进行assign了,目前只有plr可以进行assign,不然没有办法输入到物料系统中
|
# 接下来该根据bind_parent_id进行assign了,目前只有plr可以进行assign,不然没有办法输入到物料系统中
|
||||||
resource = self.resource_tracker.figure_resource({"name": bind_parent_id})
|
resource = self.resource_tracker.figure_resource({"name": bind_parent_id})
|
||||||
request.resources = [convert_to_ros_msg(Resource, resources)]
|
# request.resources = [convert_to_ros_msg(Resource, resources)]
|
||||||
|
|
||||||
try:
|
try:
|
||||||
from pylabrobot.resources.resource import Resource as ResourcePLR
|
from pylabrobot.resources.resource import Resource as ResourcePLR
|
||||||
from pylabrobot.resources.deck import Deck
|
from pylabrobot.resources.deck import Deck
|
||||||
from pylabrobot.resources import Coordinate
|
from pylabrobot.resources import Coordinate
|
||||||
from pylabrobot.resources import OTDeck
|
from pylabrobot.resources import OTDeck
|
||||||
|
from pylabrobot.resources import Plate
|
||||||
contain_model = not isinstance(resource, Deck)
|
contain_model = not isinstance(resource, Deck)
|
||||||
if isinstance(resource, ResourcePLR):
|
if isinstance(resource, ResourcePLR):
|
||||||
# resources.list()
|
# resources.list()
|
||||||
plr_instance = resource_ulab_to_plr(resources, contain_model)
|
resources_tree = dict_to_tree(copy.deepcopy({r["id"]: r for r in resources}))
|
||||||
|
plr_instance = resource_ulab_to_plr(resources_tree[0], contain_model)
|
||||||
|
if isinstance(plr_instance, Plate):
|
||||||
|
empty_liquid_info_in = [(None, 0)] * plr_instance.num_items
|
||||||
|
for liquid_type, liquid_volume, liquid_input_slot in zip(ADD_LIQUID_TYPE, LIQUID_VOLUME, LIQUID_INPUT_SLOT):
|
||||||
|
empty_liquid_info_in[liquid_input_slot] = (liquid_type, liquid_volume)
|
||||||
|
plr_instance.set_well_liquids(empty_liquid_info_in)
|
||||||
if isinstance(resource, OTDeck) and "slot" in other_calling_param:
|
if isinstance(resource, OTDeck) and "slot" in other_calling_param:
|
||||||
resource.assign_child_at_slot(plr_instance, **other_calling_param)
|
resource.assign_child_at_slot(plr_instance, **other_calling_param)
|
||||||
resource.assign_child_resource(plr_instance, Coordinate(location["x"], location["y"], location["z"]), **other_calling_param)
|
else:
|
||||||
|
_discard_slot = other_calling_param.pop("slot", -1)
|
||||||
|
resource.assign_child_resource(plr_instance, Coordinate(location["x"], location["y"], location["z"]), **other_calling_param)
|
||||||
|
request2.resources = [convert_to_ros_msg(Resource, r) for r in tree_to_list([resource_plr_to_ulab(resource)])]
|
||||||
|
rclient2.call(request2)
|
||||||
# 发送给ResourceMeshManager
|
# 发送给ResourceMeshManager
|
||||||
action_client = ActionClient(
|
action_client = ActionClient(
|
||||||
self, SendCmd, "/devices/resource_mesh_manager/add_resource_mesh", callback_group=self.callback_group
|
self, SendCmd, "/devices/resource_mesh_manager/add_resource_mesh", callback_group=self.callback_group
|
||||||
@@ -526,7 +553,7 @@ class BaseROS2DeviceNode(Node, Generic[T]):
|
|||||||
action_kwargs = convert_from_ros_msg_with_mapping(goal, action_value_mapping["goal"])
|
action_kwargs = convert_from_ros_msg_with_mapping(goal, action_value_mapping["goal"])
|
||||||
self.lab_logger().debug(f"接收到原始目标: {action_kwargs}")
|
self.lab_logger().debug(f"接收到原始目标: {action_kwargs}")
|
||||||
# 向Host查询物料当前状态,如果是host本身的增加物料的请求,则直接跳过
|
# 向Host查询物料当前状态,如果是host本身的增加物料的请求,则直接跳过
|
||||||
if action_name != "add_resource_from_outer":
|
if action_name not in ["create_resource_detailed", "create_resource"]:
|
||||||
for k, v in goal.get_fields_and_field_types().items():
|
for k, v in goal.get_fields_and_field_types().items():
|
||||||
if v in ["unilabos_msgs/Resource", "sequence<unilabos_msgs/Resource>"]:
|
if v in ["unilabos_msgs/Resource", "sequence<unilabos_msgs/Resource>"]:
|
||||||
self.lab_logger().info(f"查询资源状态: Key: {k} Type: {v}")
|
self.lab_logger().info(f"查询资源状态: Key: {k} Type: {v}")
|
||||||
@@ -625,7 +652,7 @@ class BaseROS2DeviceNode(Node, Generic[T]):
|
|||||||
del future
|
del future
|
||||||
|
|
||||||
# 向Host更新物料当前状态
|
# 向Host更新物料当前状态
|
||||||
if action_name != "add_resource_from_outer":
|
if action_name not in ["create_resource_detailed", "create_resource"]:
|
||||||
for k, v in goal.get_fields_and_field_types().items():
|
for k, v in goal.get_fields_and_field_types().items():
|
||||||
if v not in ["unilabos_msgs/Resource", "sequence<unilabos_msgs/Resource>"]:
|
if v not in ["unilabos_msgs/Resource", "sequence<unilabos_msgs/Resource>"]:
|
||||||
continue
|
continue
|
||||||
@@ -764,7 +791,7 @@ class ROS2DeviceNode:
|
|||||||
self.resource_tracker = DeviceNodeResourceTracker()
|
self.resource_tracker = DeviceNodeResourceTracker()
|
||||||
|
|
||||||
# use_pylabrobot_creator 使用 cls的包路径检测
|
# use_pylabrobot_creator 使用 cls的包路径检测
|
||||||
use_pylabrobot_creator = driver_class.__module__.startswith("pylabrobot") or driver_class.__name__ == "DPLiquidHandler"
|
use_pylabrobot_creator = driver_class.__module__.startswith("pylabrobot") or driver_class.__name__ == "LiquidHandlerAbstract"
|
||||||
|
|
||||||
# TODO: 要在创建之前预先请求服务器是否有当前id的物料,放到resource_tracker中,让pylabrobot进行创建
|
# TODO: 要在创建之前预先请求服务器是否有当前id的物料,放到resource_tracker中,让pylabrobot进行创建
|
||||||
# 创建设备类实例
|
# 创建设备类实例
|
||||||
|
|||||||
@@ -17,6 +17,7 @@ from unilabos_msgs.srv import ResourceAdd, ResourceGet, ResourceDelete, Resource
|
|||||||
from unique_identifier_msgs.msg import UUID
|
from unique_identifier_msgs.msg import UUID
|
||||||
|
|
||||||
from unilabos.registry.registry import lab_registry
|
from unilabos.registry.registry import lab_registry
|
||||||
|
from unilabos.resources.graphio import initialize_resource
|
||||||
from unilabos.resources.registry import add_schema
|
from unilabos.resources.registry import add_schema
|
||||||
from unilabos.ros.initialize_device import initialize_device_from_dict
|
from unilabos.ros.initialize_device import initialize_device_from_dict
|
||||||
from unilabos.ros.msgs.message_converter import (
|
from unilabos.ros.msgs.message_converter import (
|
||||||
@@ -100,7 +101,14 @@ class HostNode(BaseROS2DeviceNode):
|
|||||||
self.devices_names: Dict[str, str] = {device_id: self.namespace} # 存储设备名称和命名空间的映射
|
self.devices_names: Dict[str, str] = {device_id: self.namespace} # 存储设备名称和命名空间的映射
|
||||||
self.devices_instances: Dict[str, ROS2DeviceNode] = {} # 存储设备实例
|
self.devices_instances: Dict[str, ROS2DeviceNode] = {} # 存储设备实例
|
||||||
self.device_machine_names: Dict[str, str] = {device_id: "本地", } # 存储设备ID到机器名称的映射
|
self.device_machine_names: Dict[str, str] = {device_id: "本地", } # 存储设备ID到机器名称的映射
|
||||||
self._action_clients: Dict[str, ActionClient] = {} # 用来存储多个ActionClient实例
|
self._action_clients: Dict[str, ActionClient] = { # 为了方便了解实际的数据类型,host的默认写好
|
||||||
|
"/devices/host_node/create_resource": ActionClient(
|
||||||
|
self, lab_registry.ResourceCreateFromOuterEasy, "/devices/host_node/create_resource", callback_group=self.callback_group
|
||||||
|
),
|
||||||
|
"/devices/host_node/create_resource_detailed": ActionClient(
|
||||||
|
self, lab_registry.ResourceCreateFromOuter, "/devices/host_node/create_resource_detailed", callback_group=self.callback_group
|
||||||
|
)
|
||||||
|
} # 用来存储多个ActionClient实例
|
||||||
self._action_value_mappings: Dict[str, Dict] = {} # 用来存储多个ActionClient的type, goal, feedback, result的变量名映射关系
|
self._action_value_mappings: Dict[str, Dict] = {} # 用来存储多个ActionClient的type, goal, feedback, result的变量名映射关系
|
||||||
self._goals: Dict[str, Any] = {} # 用来存储多个目标的状态
|
self._goals: Dict[str, Any] = {} # 用来存储多个目标的状态
|
||||||
self._online_devices: Set[str] = {f"{self.namespace}/{device_id}"} # 用于跟踪在线设备
|
self._online_devices: Set[str] = {f"{self.namespace}/{device_id}"} # 用于跟踪在线设备
|
||||||
@@ -141,6 +149,21 @@ class HostNode(BaseROS2DeviceNode):
|
|||||||
].items():
|
].items():
|
||||||
controller_config["update_rate"] = update_rate
|
controller_config["update_rate"] = update_rate
|
||||||
self.initialize_controller(controller_id, controller_config)
|
self.initialize_controller(controller_id, controller_config)
|
||||||
|
resources_config.insert(0, {
|
||||||
|
"id": "host_node",
|
||||||
|
"name": "host_node",
|
||||||
|
"parent": None,
|
||||||
|
"type": "device",
|
||||||
|
"class": "host_node",
|
||||||
|
"position": {
|
||||||
|
"x": 0,
|
||||||
|
"y": 0,
|
||||||
|
"z": 0
|
||||||
|
},
|
||||||
|
"config": {},
|
||||||
|
"data": {},
|
||||||
|
"children": []
|
||||||
|
})
|
||||||
resource_with_parent_name = []
|
resource_with_parent_name = []
|
||||||
resource_ids_to_instance = {i["id"]: i for i in resources_config}
|
resource_ids_to_instance = {i["id"]: i for i in resources_config}
|
||||||
for res in resources_config:
|
for res in resources_config:
|
||||||
@@ -278,7 +301,7 @@ class HostNode(BaseROS2DeviceNode):
|
|||||||
except Exception as e:
|
except Exception as e:
|
||||||
self.lab_logger().error(f"[Host Node] Failed to create ActionClient for {action_id}: {str(e)}")
|
self.lab_logger().error(f"[Host Node] Failed to create ActionClient for {action_id}: {str(e)}")
|
||||||
|
|
||||||
def add_resource_from_outer(self, resources: list["Resource"], device_ids: list[str], bind_parent_ids: list[str], bind_locations: list[Point], other_calling_params: list[str]):
|
def create_resource_detailed(self, resources: list["Resource"], device_ids: list[str], bind_parent_ids: list[str], bind_locations: list[Point], other_calling_params: list[str]):
|
||||||
for resource, device_id, bind_parent_id, bind_location, other_calling_param in zip(resources, device_ids, bind_parent_ids, bind_locations, other_calling_params):
|
for resource, device_id, bind_parent_id, bind_location, other_calling_param in zip(resources, device_ids, bind_parent_ids, bind_locations, other_calling_params):
|
||||||
# 这里要求device_id传入必须是edge_device_id
|
# 这里要求device_id传入必须是edge_device_id
|
||||||
namespace = "/devices/" + device_id
|
namespace = "/devices/" + device_id
|
||||||
@@ -287,7 +310,7 @@ class HostNode(BaseROS2DeviceNode):
|
|||||||
sclient.wait_for_service()
|
sclient.wait_for_service()
|
||||||
request = SerialCommand.Request()
|
request = SerialCommand.Request()
|
||||||
request.command = json.dumps({
|
request.command = json.dumps({
|
||||||
"resource": resource,
|
"resource": resource, # 单个/单组 可为 list[list[Resource]]
|
||||||
"namespace": namespace,
|
"namespace": namespace,
|
||||||
"edge_device_id": device_id,
|
"edge_device_id": device_id,
|
||||||
"bind_parent_id": bind_parent_id,
|
"bind_parent_id": bind_parent_id,
|
||||||
@@ -302,6 +325,31 @@ class HostNode(BaseROS2DeviceNode):
|
|||||||
pass
|
pass
|
||||||
pass
|
pass
|
||||||
|
|
||||||
|
def create_resource(self, device_id: str, res_id: str, class_name: str, parent: str, bind_locations: Point, liquid_input_slot: list[int], liquid_type: list[str], liquid_volume: list[int], slot_on_deck: int):
|
||||||
|
init_new_res = initialize_resource({
|
||||||
|
"name": res_id,
|
||||||
|
"class": class_name,
|
||||||
|
"parent": parent,
|
||||||
|
"position": {
|
||||||
|
"x": bind_locations.x,
|
||||||
|
"y": bind_locations.y,
|
||||||
|
"z": bind_locations.z,
|
||||||
|
}
|
||||||
|
}) # flatten的格式
|
||||||
|
resources = [init_new_res]
|
||||||
|
device_id = [device_id]
|
||||||
|
bind_parent_id = [parent]
|
||||||
|
bind_location = [bind_locations]
|
||||||
|
other_calling_param = [json.dumps({
|
||||||
|
"ADD_LIQUID_TYPE": liquid_type,
|
||||||
|
"LIQUID_VOLUME": liquid_volume,
|
||||||
|
"LIQUID_INPUT_SLOT": liquid_input_slot,
|
||||||
|
"initialize_full": False,
|
||||||
|
"slot": slot_on_deck
|
||||||
|
})]
|
||||||
|
|
||||||
|
return self.create_resource_detailed(resources, device_id, bind_parent_id, bind_location, other_calling_param)
|
||||||
|
|
||||||
def initialize_device(self, device_id: str, device_config: Dict[str, Any]) -> None:
|
def initialize_device(self, device_id: str, device_config: Dict[str, Any]) -> None:
|
||||||
"""
|
"""
|
||||||
根据配置初始化设备,
|
根据配置初始化设备,
|
||||||
|
|||||||
@@ -43,14 +43,10 @@ set(action_files
|
|||||||
"action/LiquidHandlerStamp.action"
|
"action/LiquidHandlerStamp.action"
|
||||||
"action/LiquidHandlerTransfer.action"
|
"action/LiquidHandlerTransfer.action"
|
||||||
|
|
||||||
"action/DPLiquidHandlerAddLiquid.action"
|
"action/LiquidHandlerAdd.action"
|
||||||
"action/DPLiquidHandlerCustomDelay.action"
|
"action/LiquidHandlerMix.action"
|
||||||
"action/DPLiquidHandlerMix.action"
|
"action/LiquidHandlerMoveTo.action"
|
||||||
"action/DPLiquidHandlerMoveTo.action"
|
"action/LiquidHandlerRemove.action"
|
||||||
"action/DPLiquidHandlerRemoveLiquid.action"
|
|
||||||
"action/DPLiquidHandlerSetTiprack.action"
|
|
||||||
"action/DPLiquidHandlerTouchTip.action"
|
|
||||||
"action/DPLiquidHandlerTransferLiquid.action"
|
|
||||||
|
|
||||||
"action/EmptyIn.action"
|
"action/EmptyIn.action"
|
||||||
"action/FloatSingleInput.action"
|
"action/FloatSingleInput.action"
|
||||||
@@ -59,9 +55,10 @@ set(action_files
|
|||||||
"action/Point3DSeparateInput.action"
|
"action/Point3DSeparateInput.action"
|
||||||
|
|
||||||
"action/ResourceCreateFromOuter.action"
|
"action/ResourceCreateFromOuter.action"
|
||||||
|
"action/ResourceCreateFromOuterEasy.action"
|
||||||
|
|
||||||
"action/SolidDispenseAddPowderTube.action"
|
"action/SolidDispenseAddPowderTube.action"
|
||||||
|
|
||||||
"action/PumpTransfer.action"
|
"action/PumpTransfer.action"
|
||||||
"action/Clean.action"
|
"action/Clean.action"
|
||||||
"action/Separate.action"
|
"action/Separate.action"
|
||||||
|
|||||||
@@ -1,6 +0,0 @@
|
|||||||
float64 seconds
|
|
||||||
string msg
|
|
||||||
---
|
|
||||||
bool success
|
|
||||||
---
|
|
||||||
# 反馈
|
|
||||||
@@ -1,5 +0,0 @@
|
|||||||
Resource[] tip_racks
|
|
||||||
---
|
|
||||||
bool success
|
|
||||||
---
|
|
||||||
# 反馈
|
|
||||||
@@ -1,5 +0,0 @@
|
|||||||
Resource[] targets
|
|
||||||
---
|
|
||||||
bool success
|
|
||||||
---
|
|
||||||
# 反馈
|
|
||||||
@@ -1,25 +0,0 @@
|
|||||||
float64[] asp_vols
|
|
||||||
float64[] dis_vols
|
|
||||||
Resource[] sources
|
|
||||||
Resource[] targets
|
|
||||||
Resource[] tip_racks
|
|
||||||
int32[] use_channels
|
|
||||||
float64[] asp_flow_rates
|
|
||||||
float64[] dis_flow_rates
|
|
||||||
geometry_msgs/Point[] offsets
|
|
||||||
bool touch_tip
|
|
||||||
float64[] liquid_height
|
|
||||||
float64[] blow_out_air_volume
|
|
||||||
string spread
|
|
||||||
bool is_96_well
|
|
||||||
string mix_stage
|
|
||||||
int32[] mix_times
|
|
||||||
int32 mix_vol
|
|
||||||
int32 mix_rate
|
|
||||||
float64 mix_liquid_height
|
|
||||||
int32[] delays
|
|
||||||
string[] none_keys
|
|
||||||
---
|
|
||||||
bool success
|
|
||||||
---
|
|
||||||
# 反馈
|
|
||||||
@@ -5,7 +5,7 @@ float64[] flow_rates
|
|||||||
geometry_msgs/Point[] offsets
|
geometry_msgs/Point[] offsets
|
||||||
float64[] liquid_height
|
float64[] liquid_height
|
||||||
float64[] blow_out_air_volume
|
float64[] blow_out_air_volume
|
||||||
string spread="wide"
|
string spread
|
||||||
---
|
---
|
||||||
bool success
|
bool success
|
||||||
---
|
---
|
||||||
@@ -5,7 +5,7 @@ int32[] use_channels
|
|||||||
float64[] flow_rates
|
float64[] flow_rates
|
||||||
geometry_msgs/Point[] offsets
|
geometry_msgs/Point[] offsets
|
||||||
int32[] blow_out_air_volume
|
int32[] blow_out_air_volume
|
||||||
string spread="wide"
|
string spread
|
||||||
---
|
---
|
||||||
# 结果字段
|
# 结果字段
|
||||||
bool success
|
bool success
|
||||||
|
|||||||
@@ -1,11 +1,26 @@
|
|||||||
# Bio
|
# Bio
|
||||||
Resource source
|
float64[] asp_vols
|
||||||
|
float64[] dis_vols
|
||||||
|
Resource[] sources
|
||||||
Resource[] targets
|
Resource[] targets
|
||||||
float64 source_vol
|
Resource[] tip_racks
|
||||||
float64[] ratios
|
int32[] use_channels
|
||||||
float64[] target_vols
|
float64[] asp_flow_rates
|
||||||
float64 aspiration_flow_rate
|
float64[] dis_flow_rates
|
||||||
float64[] dispense_flow_rates
|
geometry_msgs/Point[] offsets
|
||||||
|
bool touch_tip
|
||||||
|
float64[] liquid_height
|
||||||
|
float64[] blow_out_air_volume
|
||||||
|
string spread
|
||||||
|
bool is_96_well
|
||||||
|
string mix_stage
|
||||||
|
int32[] mix_times
|
||||||
|
int32 mix_vol
|
||||||
|
int32 mix_rate
|
||||||
|
float64 mix_liquid_height
|
||||||
|
int32[] delays
|
||||||
|
string[] none_keys
|
||||||
---
|
---
|
||||||
bool success
|
bool success
|
||||||
---
|
---
|
||||||
|
# 反馈
|
||||||
12
unilabos_msgs/action/ResourceCreateFromOuterEasy.action
Normal file
12
unilabos_msgs/action/ResourceCreateFromOuterEasy.action
Normal file
@@ -0,0 +1,12 @@
|
|||||||
|
string res_id
|
||||||
|
string device_id
|
||||||
|
string class_name
|
||||||
|
string parent
|
||||||
|
geometry_msgs/Point bind_locations
|
||||||
|
int32[] liquid_input_slot
|
||||||
|
string[] liquid_type
|
||||||
|
float32[] liquid_volume
|
||||||
|
int32 slot_on_deck
|
||||||
|
---
|
||||||
|
bool success
|
||||||
|
---
|
||||||
Reference in New Issue
Block a user