mirror of
https://github.com/dptech-corp/Uni-Lab-OS.git
synced 2025-12-17 04:51:10 +00:00
Add high-level PLR functions Add Laiyu/Zhida driver support Fix ROS node discovery issues Add hostname and resource query support Fix ROS message conversion logic Support configuration via environment variables * 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 --------- Co-authored-by: Harvey Que <Q-Query@outlook.com> Co-authored-by: zhangshixiang <@zhangshixiang> Co-authored-by: q434343 <73513873+q434343@users.noreply.github.com>
137 lines
5.6 KiB
XML
137 lines
5.6 KiB
XML
<?xml version="1.0" ?>
|
|
<!-- =================================================================================== -->
|
|
<!-- | This document was autogenerated by xacro from slide.urdf | -->
|
|
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
|
<!-- =================================================================================== -->
|
|
<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com)
|
|
Commit Version: 1.6.0-4-g7f85cfe Build Version: 1.6.7995.38578
|
|
For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
|
|
<robot xmlns:xacro="http://ros.org/wiki/xacro">
|
|
|
|
<xacro:macro name="slide_w140" params="mesh_path:='' length:=0.1 min_d:=0.1 max_d:=0.1 slider_d:=0.14 parent_link:='' station_name:='' device_name:='' x:=0 y:=0 z:=0 r:=0" >
|
|
|
|
|
|
<joint name="${station_name}${device_name}base_link_joint" type="fixed">
|
|
<origin xyz="${x} ${y} ${z}" rpy="0 0 ${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"/>
|
|
<joint name="${station_name}${device_name}device_link_joint" type="fixed">
|
|
<origin xyz="${-min_d} 0 0" rpy="0 0 0" />
|
|
<parent link="${station_name}${device_name}device_link"/>
|
|
<child link="${station_name}${device_name}base_link"/>
|
|
<axis xyz="0 0 0"/>
|
|
</joint>
|
|
|
|
<link name="${station_name}${device_name}base_link">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-0.00073944 -0.070732 0.035966"/>
|
|
<mass value="0.88697"/>
|
|
<inertia ixx="0.0019162" ixy="-2.5282E-11" ixz="6.1083E-07" iyy="0.00066605" iyz="1.4627E-08" izz="0.0019573"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="file://${mesh_path}/devices/slide_w140/meshes/base_link.STL"/>
|
|
</geometry>
|
|
<material name="">
|
|
<color rgba="1 1 1 1"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="file://${mesh_path}/devices/slide_w140/meshes/base_link.STL"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<link name="${station_name}${device_name}slider">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 -4.7184E-16 0.0095496"/>
|
|
<mass value="0.27913"/>
|
|
<inertia ixx="0.00048249" ixy="2.0866E-19" ixz="2.788E-21" iyy="0.00047014" iyz="1.1542E-17" izz="0.0009242"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="file://${mesh_path}/devices/slide_w140/meshes/slider.STL" />
|
|
</geometry>
|
|
<material name="">
|
|
<color rgba="1 1 1 1"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="file://${mesh_path}/devices/slide_w140/meshes/slider.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="${station_name}${device_name}slider_joint" type="prismatic">
|
|
<origin rpy="0 0 0" xyz="${min_d + slider_d/2} 0 0.0475"/>
|
|
<parent link="${station_name}${device_name}base_link"/>
|
|
<child link="${station_name}${device_name}slider"/>
|
|
<axis xyz="1 0 0"/>
|
|
<limit effort="100" lower="0" upper="${length}" velocity="1"/>
|
|
</joint>
|
|
<link name="${station_name}${device_name}length">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0.005 -9.3044E-10 0.02803"/>
|
|
<mass value="0.050532"/>
|
|
<inertia ixx="8.098E-05" ixy="-1.2574E-19" ixz="3.1207E-20" iyy="4.4152E-06" iyz="-3.1294E-13" izz="7.7407E-05"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="file://${mesh_path}/devices/slide_w140/meshes/length.STL" scale="${(length + min_d + max_d + slider_d)} 1 1"/>
|
|
</geometry>
|
|
<material name="">
|
|
<color rgba="1 1 1 1"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="file://${mesh_path}/devices/slide_w140/meshes/length.STL" scale="${(length + min_d + max_d + slider_d)} 1 1"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="${station_name}${device_name}length_joint" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<parent link="${station_name}${device_name}base_link"/>
|
|
<child link="${station_name}${device_name}length"/>
|
|
</joint>
|
|
<link name="${station_name}${device_name}slide_end">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0.003 8.6044E-06 0.035593"/>
|
|
<mass value="0.055452"/>
|
|
<inertia ixx="9.9729E-05" ixy="-1.0228E-21" ixz="3.8344E-22" iyy="2.3158E-05" iyz="1.5613E-08" izz="7.6904E-05"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="file://${mesh_path}/devices/slide_w140/meshes/slide_end.STL"/>
|
|
</geometry>
|
|
<material name="">
|
|
<color rgba="1 1 1 1"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="file://${mesh_path}/devices/slide_w140/meshes/slide_end.STL"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="${station_name}${device_name}slide_end_joint" type="fixed">
|
|
<origin rpy="0 0 0" xyz="${length + max_d +min_d + slider_d} 0 0"/>
|
|
<parent link="${station_name}${device_name}base_link"/>
|
|
<child link="${station_name}${device_name}slide_end"/>
|
|
</joint>
|
|
|
|
</xacro:macro>
|
|
</robot>
|