Uni-Lab 动作指令集

Uni-Lab 当前动作指令集设计时,主要考虑兼容领域历史开源工具。目前包括以下场景:

简单单变量动作函数

SendCmd

# Simple
string command
---
string return_info
bool success
---
string status

常量有机化学操作

Uni-Lab 常量有机化学指令集多数来自 XDL,包含有机合成实验中常见的操作,如加热、搅拌、冷却等。

Clean

# Organic
Resource vessel  # Vessel to clean.
string solvent # Solvent to clean vessel with.
float64 volume # Optional. Volume of solvent to clean vessel with.
float64 temp   # Optional. Temperature to heat vessel to while cleaning.
int32 repeats  # Optional. Number of cleaning cycles to perform.
---
string return_info
bool success
---
string status
string current_device
builtin_interfaces/Duration time_spent
builtin_interfaces/Duration time_remaining

HeatChillStart

# Organic
Resource vessel
float64 temp
string purpose
---
string return_info
bool success
---
string status

HeatChillStop

# Organic
Resource vessel
---
string return_info
bool success
---
string status

PumpTransfer

# Organic
Resource from_vessel
Resource to_vessel
float64 volume
string amount
float64 time
bool viscous
string rinsing_solvent
float64 rinsing_volume
int32 rinsing_repeats
bool solid
float64 flowrate
float64 transfer_flowrate
string rate_spec
string event
string through
---
string return_info
bool success
---
string status
string current_device
builtin_interfaces/Duration time_spent
builtin_interfaces/Duration time_remaining

移液工作站及相关生物自动化设备操作

Uni-Lab 生物操作指令集多数来自 PyLabRobot,包含生物实验中常见的操作,如移液、混匀、离心等。

LiquidHandlerDiscardTips

# Bio
# 请求字段
int32[] use_channels
---
# 结果字段
string return_info
bool success
---
# 反馈字段 

LiquidHandlerDropTips

# Bio
# 请求字段
Resource[] tip_spots
int32[] use_channels
geometry_msgs/Point[] offsets
bool allow_nonzero_volume
---
# 结果字段
string return_info
bool success
---
# 反馈字段 

LiquidHandlerDropTips96

# Bio
# 请求字段
Resource tip_rack
geometry_msgs/Point offset
bool allow_nonzero_volume
---
# 结果字段
string return_info
bool success
---
# 反馈字段 

LiquidHandlerMoveLid

# Bio
# 请求字段
Resource lid
Resource to
geometry_msgs/Point[] intermediate_locations
geometry_msgs/Point resource_offset
geometry_msgs/Point destination_offset
string pickup_direction
string drop_direction
string get_direction
string put_direction
float64 pickup_distance_from_top
---
# 结果字段
string return_info
bool success
---
# 反馈字段 

LiquidHandlerMovePlate

# Bio
# 请求字段
Resource plate
Resource to
geometry_msgs/Point[] intermediate_locations
geometry_msgs/Point resource_offset
geometry_msgs/Point pickup_offset
geometry_msgs/Point destination_offset
string pickup_direction
string drop_direction
string get_direction
string put_direction
float64 pickup_distance_from_top
---
# 结果字段
string return_info
bool success
---
# 反馈字段 

LiquidHandlerMoveResource

# Bio
# 请求字段
Resource resource
geometry_msgs/Point to
geometry_msgs/Point[] intermediate_locations
geometry_msgs/Point resource_offset
geometry_msgs/Point destination_offset
float64 pickup_distance_from_top
string pickup_direction
string drop_direction
string get_direction
string put_direction
---
# 结果字段
string return_info
bool success
---
# 反馈字段 

LiquidHandlerPickUpTips

# Bio
# 请求字段
Resource[] tip_spots
int32[] use_channels
geometry_msgs/Point[] offsets
---
# 结果字段
string return_info
bool success
---
# 反馈字段 

LiquidHandlerPickUpTips96

# Bio
# 请求字段
Resource tip_rack
geometry_msgs/Point offset
---
# 结果字段
string return_info
bool success
---
# 反馈字段 

LiquidHandlerReturnTips

# Bio
# 请求字段
int32[] use_channels
bool allow_nonzero_volume
---
# 结果字段
string return_info
bool success
---
# 反馈字段 

LiquidHandlerReturnTips96

# Bio
# 请求字段
bool allow_nonzero_volume
---
# 结果字段
string return_info
bool success
---
# 反馈字段 

LiquidHandlerStamp

# Bio
# 请求字段
Resource source
Resource target
float64 volume
float64 aspiration_flow_rate
float64 dispense_flow_rate
---
# 结果字段
string return_info
bool success
---
# 反馈字段 

多工作站及小车运行、物料转移

AGVTransfer

# MobileRobot
Resource from_repo
string from_repo_position
Resource to_repo
string to_repo_position
---
string return_info
bool success
---
string status

WorkStationRun

# MobileRobot
string wf_name
string params
Resource resource
---
string return_info
bool success
---
string status
string gantt

机械臂、夹爪等机器人设备

Uni-Lab 机械臂、机器人、夹爪和导航指令集沿用 ROS2 的 control_msgsnav2_msgs

FollowJointTrajectory

# The trajectory for all revolute, continuous or prismatic joints
trajectory_msgs/JointTrajectory trajectory
# The trajectory for all planar or floating joints (i.e. individual joints with more than one DOF)
trajectory_msgs/MultiDOFJointTrajectory multi_dof_trajectory

# Tolerances for the trajectory.  If the measured joint values fall
# outside the tolerances the trajectory goal is aborted.  Any
# tolerances that are not specified (by being omitted or set to 0) are
# set to the defaults for the action server (often taken from the
# parameter server).

# Tolerances applied to the joints as the trajectory is executed.  If
# violated, the goal aborts with error_code set to
# PATH_TOLERANCE_VIOLATED.
JointTolerance[] path_tolerance
JointComponentTolerance[] component_path_tolerance

# To report success, the joints must be within goal_tolerance of the
# final trajectory value.  The goal must be achieved by time the
# trajectory ends plus goal_time_tolerance.  (goal_time_tolerance
# allows some leeway in time, so that the trajectory goal can still
# succeed even if the joints reach the goal some time after the
# precise end time of the trajectory).
#
# If the joints are not within goal_tolerance after "trajectory finish
# time" + goal_time_tolerance, the goal aborts with error_code set to
# GOAL_TOLERANCE_VIOLATED
JointTolerance[] goal_tolerance
JointComponentTolerance[] component_goal_tolerance
builtin_interfaces/Duration goal_time_tolerance

---
int32 error_code
int32 SUCCESSFUL = 0
int32 INVALID_GOAL = -1
int32 INVALID_JOINTS = -2
int32 OLD_HEADER_TIMESTAMP = -3
int32 PATH_TOLERANCE_VIOLATED = -4
int32 GOAL_TOLERANCE_VIOLATED = -5

# Human readable description of the error code. Contains complementary
# information that is especially useful when execution fails, for instance:
# - INVALID_GOAL: The reason for the invalid goal (e.g., the requested
#   trajectory is in the past).
# - INVALID_JOINTS: The mismatch between the expected controller joints
#   and those provided in the goal.
# - PATH_TOLERANCE_VIOLATED and GOAL_TOLERANCE_VIOLATED: Which joint
#   violated which tolerance, and by how much.
string error_string

---
std_msgs/Header header
string[] joint_names
trajectory_msgs/JointTrajectoryPoint desired
trajectory_msgs/JointTrajectoryPoint actual
trajectory_msgs/JointTrajectoryPoint error

string[] multi_dof_joint_names
trajectory_msgs/MultiDOFJointTrajectoryPoint multi_dof_desired
trajectory_msgs/MultiDOFJointTrajectoryPoint multi_dof_actual
trajectory_msgs/MultiDOFJointTrajectoryPoint multi_dof_error

GripperCommand

GripperCommand command
---
float64 position  # The current gripper gap size (in meters)
float64 effort    # The current effort exerted (in Newtons)
bool stalled      # True iff the gripper is exerting max effort and not moving
bool reached_goal # True iff the gripper position has reached the commanded setpoint
---
float64 position  # The current gripper gap size (in meters)
float64 effort    # The current effort exerted (in Newtons)
bool stalled      # True iff the gripper is exerting max effort and not moving
bool reached_goal # True iff the gripper position has reached the commanded setpoint

JointTrajectory

trajectory_msgs/JointTrajectory trajectory
---
---

ParallelGripperCommand

# Parallel grippers refer to an end effector where two opposing fingers grasp an object from opposite sides.
sensor_msgs/JointState command
# name: the name(s) of the joint this command is requesting
# position: desired position of each gripper joint (radians or meters)
# velocity: (optional, not used if empty) max velocity of the joint allowed while moving (radians or meters / second)
# effort: (optional, not used if empty) max effort of the joint allowed while moving (Newtons or Newton-meters)
---
sensor_msgs/JointState state # The current gripper state.
# position of each joint (radians or meters)
# optional: velocity of each joint (radians or meters / second)
# optional: effort of each joint (Newtons or Newton-meters)
bool stalled      # True if the gripper is exerting max effort and not moving
bool reached_goal # True if the gripper position has reached the commanded setpoint
---
sensor_msgs/JointState state # The current gripper state.
# position of each joint (radians or meters)
# optional: velocity of each joint (radians or meters / second)
# optional: effort of each joint (Newtons or Newton-meters)

PointHead

geometry_msgs/PointStamped target
geometry_msgs/Vector3 pointing_axis
string pointing_frame
builtin_interfaces/Duration min_duration
float64 max_velocity
---
---
float64 pointing_angle_error

SingleJointPosition

float64 position
builtin_interfaces/Duration min_duration
float64 max_velocity
---
---
std_msgs/Header header
float64 position
float64 velocity
float64 error

AssistedTeleop

#goal definition
builtin_interfaces/Duration time_allowance
---
#result definition
builtin_interfaces/Duration total_elapsed_time
---
#feedback
builtin_interfaces/Duration current_teleop_duration

BackUp

#goal definition
geometry_msgs/Point target
float32 speed
builtin_interfaces/Duration time_allowance
---
#result definition
builtin_interfaces/Duration total_elapsed_time
---
#feedback definition
float32 distance_traveled

ComputePathThroughPoses

#goal definition
geometry_msgs/PoseStamped[] goals
geometry_msgs/PoseStamped start
string planner_id
bool use_start # If false, use current robot pose as path start, if true, use start above instead
---
#result definition
nav_msgs/Path path
builtin_interfaces/Duration planning_time
---
#feedback definition

ComputePathToPose

#goal definition
geometry_msgs/PoseStamped goal
geometry_msgs/PoseStamped start
string planner_id
bool use_start # If false, use current robot pose as path start, if true, use start above instead
---
#result definition
nav_msgs/Path path
builtin_interfaces/Duration planning_time
---
#feedback definition

DriveOnHeading

#goal definition
geometry_msgs/Point target
float32 speed
builtin_interfaces/Duration time_allowance
---
#result definition
builtin_interfaces/Duration total_elapsed_time
---
#feedback definition
float32 distance_traveled

DummyBehavior

#goal definition
std_msgs/String command
---
#result definition
builtin_interfaces/Duration total_elapsed_time
---
#feedback definition

FollowPath

#goal definition
nav_msgs/Path path
string controller_id
string goal_checker_id
---
#result definition
std_msgs/Empty result
---
#feedback definition
float32 distance_to_goal
float32 speed

FollowWaypoints

#goal definition
geometry_msgs/PoseStamped[] poses
---
#result definition
int32[] missed_waypoints
---
#feedback definition
uint32 current_waypoint



SmoothPath

#goal definition
nav_msgs/Path path
string smoother_id
builtin_interfaces/Duration max_smoothing_duration
bool check_for_collisions
---
#result definition
nav_msgs/Path path
builtin_interfaces/Duration smoothing_duration
bool was_completed
---
#feedback definition

Spin

#goal definition
float32 target_yaw
builtin_interfaces/Duration time_allowance
---
#result definition
builtin_interfaces/Duration total_elapsed_time
---
#feedback definition
float32 angular_distance_traveled

Wait

#goal definition
builtin_interfaces/Duration time
---
#result definition
builtin_interfaces/Duration total_elapsed_time
---
#feedback definition
builtin_interfaces/Duration time_left