mirror of
https://github.com/dptech-corp/Uni-Lab-OS.git
synced 2025-12-17 04:51:10 +00:00
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}/device/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}/device/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}/device/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}/device/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}/device/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}/device/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}/device/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}/device/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>
|