mirror of
https://github.com/dptech-corp/Uni-Lab-OS.git
synced 2026-02-06 23:15:10 +00:00
* Update README and MQTTClient for installation instructions and code improvements * feat: 支持local_config启动 add: 增加对crt path的说明,为传入config.py的相对路径 move: web component * add: registry description * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * feat: node_info_update srv fix: OTDeck cant create * close #12 feat: slave node registry * feat: show machine name fix: host node registry not uploaded * feat: add hplc registry * feat: add hplc registry * fix: hplc status typo * fix: devices/ * 完成启动OT并联动rviz * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * 完成启动OT并联动rviz * fix: device.class possible null * fix: HPLC additions with online service * fix: slave mode spin not working * fix: slave mode spin not working * 修复rviz位置问题, 修复rviz位置问题, 在无tf变动时减缓发送频率 在backend中添加物料跟随方法 * feat: 多ProtocolNode 允许子设备ID相同 feat: 上报发现的ActionClient feat: Host重启动,通过discover机制要求slaveNode重新注册,实现信息及时上报 * feat: 支持env设置config * fix: running logic * fix: running logic * fix: missing ot * 在main中直接初始化republisher和物料的mesh节点 * 将joint_republisher和resource_mesh_manager添加进 main_slave_run.py中 * Device visualization (#14) * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * 完成启动OT并联动rviz * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * 完成启动OT并联动rviz * 修复rviz位置问题, 修复rviz位置问题, 在无tf变动时减缓发送频率 在backend中添加物料跟随方法 * fix: running logic * fix: running logic * fix: missing ot * 在main中直接初始化republisher和物料的mesh节点 * 将joint_republisher和resource_mesh_manager添加进 main_slave_run.py中 --------- Co-authored-by: zhangshixiang <@zhangshixiang> Co-authored-by: wznln <18435084+Xuwznln@users.noreply.github.com> * fix: missing hostname in devices_names fix: upload_file for model file * fix: missing paho-mqtt package bump version to 0.9.0 * fix startup add ResourceCreateFromOuter.action * fix type hint * update actions * update actions * host node add_resource_from_outer fix cmake list * pass device config to device class * add: bind_parent_ids to resource create action fix: message convert string * fix: host node should not be re_discovered * feat: resource tracker support dict * feat: add more necessary params * feat: fix boolean null in registry action data * feat: add outer resource * 编写mesh添加action * feat: append resource * add action * feat: vis 2d for plr * fix * fix: browser on rviz * fix: cloud bridge error fallback to local * fix: salve auto run rviz * 初始化两个plate * Device visualization (#22) * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * 完成启动OT并联动rviz * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * 完成启动OT并联动rviz * 修复rviz位置问题, 修复rviz位置问题, 在无tf变动时减缓发送频率 在backend中添加物料跟随方法 * fix: running logic * fix: running logic * fix: missing ot * 在main中直接初始化republisher和物料的mesh节点 * 将joint_republisher和resource_mesh_manager添加进 main_slave_run.py中 * 编写mesh添加action * add action * fix * fix: browser on rviz * fix: cloud bridge error fallback to local * fix: salve auto run rviz * 初始化两个plate --------- Co-authored-by: zhangshixiang <@zhangshixiang> Co-authored-by: wznln <18435084+Xuwznln@users.noreply.github.com> * fix: multi channel * fix: aspirate * fix: aspirate * fix: aspirate * fix: aspirate * 提交 * fix: jobadd * fix: jobadd * fix: msg converter * tijiao * add resource creat easy action * identify debug msg * mq client id * 提取lh的joint发布 * unify liquid_handler definition * 修改物料跟随与物料添加逻辑 修改物料跟随与物料添加逻辑 将joint_publisher类移出lh的backends,但仍需要对lh的backends进行一些改写 * Revert "修改物料跟随与物料添加逻辑" This reverts commit498c997ad7. * Reapply "修改物料跟随与物料添加逻辑" This reverts commit3a60d2ae81. * Revert "Merge remote-tracking branch 'upstream/dev' into device_visualization" This reverts commitfa727220af, reversing changes made to498c997ad7. * 修改物料放下时的方法,如果选择 修改物料放下时的方法, 如果选择drop_trash,则删除物料显示 如果选择drop,则让其解除连接 * unilab添加moveit启动 1,整合所有moveit节点到一个move_group中,并整合所有的controller依次激活 2,添加pymoveit2的节点,使用json可直接启动 3,修改机械臂规划方式,添加约束,让冗余关节不会进行过多移动 * 修改物体attach时,多次赋值当前时间导致卡顿问题, * Revert "修改物体attach时,多次赋值当前时间导致卡顿问题," This reverts commit56d45b94f5. * Reapply "修改物体attach时,多次赋值当前时间导致卡顿问题," This reverts commit07d9db20c3. * 添加缺少物料:"plate_well_G12", * add * fix tip resource data * liquid states * change to debug level * Revert "change to debug level" This reverts commit5d9953c3e5. * Reapply "change to debug level" This reverts commit2487bb6ffc. * fix tip resource data * add full device * add moveit yaml * 修复moveit 增加post_init阶段,给予ros_node反向 * remove necessary node * fix moveit action client * remove necessary imports * Update moveit_interface.py * fix handler_key uppercase * json add liquids * fix setup * add * change to "sources" and "targets" for lh * bump version * remove parent's parent link * change arm's name * change name * fix ik error * 修改moveit_interface,并在mqtt上报时发送一个时间戳 * 添加机械臂和移液站 * 添加 * 添加硬件 * update * 添加 --------- Co-authored-by: Harvey Que <Q-Query@outlook.com> Co-authored-by: wznln <18435084+Xuwznln@users.noreply.github.com> Co-authored-by: zhangshixiang <@zhangshixiang> Co-authored-by: Junhan Chang <changjh@pku.edu.cn>
160 lines
6.4 KiB
XML
160 lines
6.4 KiB
XML
<?xml version="1.0"?>
|
|
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="elite_robot">
|
|
<xacro:macro name="elite_robot" params="mesh_path:='' parent_link:='' station_name:='' device_name:='' cs_type:='cs66' fake_dev:='true' x:=0 y:=0 z:=0 rx:=0 ry:=0 r:=0" >
|
|
<!-- robot name parameter -->
|
|
<xacro:arg name="name" default="cs"/>
|
|
<!-- import main macro -->
|
|
<xacro:include filename="${mesh_path}/devices/elite_robot/urdf/cs_macro.xacro"/>
|
|
|
|
<!-- possible 'cs_type' values: cs63, cs66, cs612, cs616, cs620, cs625 -->
|
|
<!-- the default value should raise an error in case this was called without defining the type -->
|
|
<xacro:arg name="cs_type" default="${cs_type}"/>
|
|
|
|
<!-- parameters -->
|
|
<xacro:arg name="tf_prefix" default="${station_name}${device_name}" />
|
|
<xacro:arg name="joint_limit_params" default="${mesh_path}/devices/elite_robot/config/$(arg cs_type)/joint_limits.yaml"/>
|
|
<xacro:arg name="kinematics_params" default="${mesh_path}/devices/elite_robot/config/$(arg cs_type)/default_kinematics.yaml"/>
|
|
<xacro:arg name="physical_params" default="${mesh_path}/devices/elite_robot/config/$(arg cs_type)/physical_parameters.yaml"/>
|
|
<xacro:arg name="visual_params" default="${mesh_path}/devices/elite_robot/config/$(arg cs_type)/visual_parameters.yaml"/>
|
|
<xacro:arg name="transmission_hw_interface" default=""/>
|
|
<xacro:arg name="safety_limits" default="false"/>
|
|
<xacro:arg name="safety_pos_margin" default="0.15"/>
|
|
<xacro:arg name="safety_k_position" default="20"/>
|
|
<!-- ros2_control related parameters -->
|
|
<xacro:arg name="headless_mode" default="false" />
|
|
<xacro:arg name="robot_ip" default="0.0.0.0" />
|
|
<xacro:arg name="script_filename" default=""/>
|
|
<xacro:arg name="output_recipe_filename" default=""/>
|
|
<xacro:arg name="input_recipe_filename" default=""/>
|
|
<xacro:arg name="local_ip" default="0.0.0.0"/>
|
|
<xacro:arg name="script_command_port" default="50004"/>
|
|
<xacro:arg name="reverse_port" default="50001"/>
|
|
<xacro:arg name="script_sender_port" default="50002"/>
|
|
<xacro:arg name="trajectory_port" default="50003"/>
|
|
<!-- tool communication related parameters-->
|
|
<xacro:arg name="use_tool_communication" default="false" />
|
|
<xacro:arg name="tool_voltage" default="0" />
|
|
<xacro:arg name="tool_parity" default="0" />
|
|
<xacro:arg name="tool_baud_rate" default="115200" />
|
|
<xacro:arg name="tool_stop_bits" default="1" />
|
|
<xacro:arg name="tool_tcp_port" default="54321" />
|
|
|
|
<!-- Simulation parameters -->
|
|
<xacro:arg name="use_fake_hardware" default="${fake_dev}" />
|
|
<xacro:arg name="fake_sensor_commands" default="${fake_dev}" />
|
|
<xacro:arg name="sim_gazebo" default="false" />
|
|
<xacro:arg name="sim_ignition" default="false" />
|
|
<xacro:arg name="simulation_controllers" default="" />
|
|
|
|
<!-- initial position for simulations (Fake Hardware, Gazebo, Ignition) -->
|
|
<xacro:arg name="initial_positions_file" default="${mesh_path}/devices/elite_robot/config/initial_positions.yaml"/>
|
|
|
|
<!-- convert to property to use substitution in function -->
|
|
<xacro:property name="initial_positions_file" default="$(arg initial_positions_file)"/>
|
|
|
|
|
|
|
|
<joint name="${station_name}${device_name}base_link_joint" type="fixed">
|
|
<origin xyz="${x} ${y} ${z}" rpy="${rx} ${ry} ${r}" />
|
|
<parent link="${parent_link}"/>
|
|
<child link="${station_name}${device_name}device_link"/>
|
|
<axis xyz="0 0 0"/>
|
|
</joint>
|
|
|
|
<link name="${station_name}${device_name}device_link"/>
|
|
|
|
<!-- arm -->
|
|
<xacro:cs_robot
|
|
name="$(arg name)"
|
|
tf_prefix="$(arg tf_prefix)"
|
|
parent="${station_name}${device_name}device_link"
|
|
joint_limits_parameters_file="$(arg joint_limit_params)"
|
|
kinematics_parameters_file="$(arg kinematics_params)"
|
|
physical_parameters_file="$(arg physical_params)"
|
|
visual_parameters_file="$(arg visual_params)"
|
|
transmission_hw_interface="$(arg transmission_hw_interface)"
|
|
safety_limits="$(arg safety_limits)"
|
|
safety_pos_margin="$(arg safety_pos_margin)"
|
|
safety_k_position="$(arg safety_k_position)"
|
|
use_fake_hardware="$(arg use_fake_hardware)"
|
|
fake_sensor_commands="$(arg fake_sensor_commands)"
|
|
sim_gazebo="$(arg sim_gazebo)"
|
|
sim_ignition="$(arg sim_ignition)"
|
|
headless_mode="$(arg headless_mode)"
|
|
initial_positions="${xacro.load_yaml(initial_positions_file)}"
|
|
use_tool_communication="$(arg use_tool_communication)"
|
|
tool_voltage="$(arg tool_voltage)"
|
|
tool_parity="$(arg tool_parity)"
|
|
tool_baud_rate="$(arg tool_baud_rate)"
|
|
tool_stop_bits="$(arg tool_stop_bits)"
|
|
tool_tcp_port="$(arg tool_tcp_port)"
|
|
robot_ip="$(arg robot_ip)"
|
|
script_filename="$(arg script_filename)"
|
|
output_recipe_filename="$(arg output_recipe_filename)"
|
|
input_recipe_filename="$(arg input_recipe_filename)"
|
|
local_ip="$(arg local_ip)"
|
|
script_command_port="$(arg script_command_port)"
|
|
reverse_port="$(arg reverse_port)"
|
|
script_sender_port="$(arg script_sender_port)"
|
|
trajectory_port="$(arg trajectory_port)"
|
|
mesh_path="${mesh_path}"
|
|
>
|
|
<origin xyz="0 0 0" rpy="0 0 0" /> <!-- position robot in the world -->
|
|
</xacro:cs_robot>
|
|
|
|
<link name="${station_name}${device_name}gripper">
|
|
<inertial>
|
|
<origin
|
|
xyz="-2.76718112539598E-05 0.0255270141715087 0.0270559267296449"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.2571510360664" />
|
|
<inertia
|
|
ixx="0.000164806957167171"
|
|
ixy="1.52519074989277E-08"
|
|
ixz="9.6332716899636E-08"
|
|
iyy="8.72759579414916E-05"
|
|
iyz="-5.40735277087457E-07"
|
|
izz="0.000196871100878503" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="file://${mesh_path}/devices/elite_robot/meshes/gripper.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.749019607843137 0.749019607843137 0.749019607843137 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="file://${mesh_path}/devices/elite_robot/meshes/gripper.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="${station_name}${device_name}gripper_joint"
|
|
type="fixed">
|
|
<origin
|
|
xyz="0 0 -0.003"
|
|
rpy="0 0 -1.570796326589793" />
|
|
<parent
|
|
link="${station_name}${device_name}tool0" />
|
|
<child
|
|
link="${station_name}${device_name}gripper" />
|
|
<axis
|
|
xyz="0 0 0" />
|
|
</joint>
|
|
|
|
</xacro:macro>
|
|
|
|
</robot>
|