|
|
<?xml version="1.0" encoding="utf-8"?> |
|
|
|
|
|
|
|
|
<robot name="X5A">
|
|
|
<link name="base_link">
|
|
|
<inertial>
|
|
|
<origin xyz="-3.0001E-05 3.0589E-05 0.027324" rpy="0 0 0" />
|
|
|
<mass value="0.43995" />
|
|
|
<inertia ixx="0.00017" ixy="0.00000" ixz="0.00000" iyy="0.00017" iyz="0.00000" izz="0.00016" />
|
|
|
</inertial>
|
|
|
<visual>
|
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
|
<geometry>
|
|
|
<mesh filename="meshes/base_link.STL" />
|
|
|
</geometry>
|
|
|
<material name="black">
|
|
|
<color rgba="0 0 0 1" />
|
|
|
</material>
|
|
|
</visual>
|
|
|
<collision>
|
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
|
<geometry>
|
|
|
<mesh filename="meshes/base_link.STL" />
|
|
|
</geometry>
|
|
|
</collision>
|
|
|
</link>
|
|
|
<link name="link1">
|
|
|
<inertial>
|
|
|
<origin xyz="0.0054231 -0.0080289 0.017086" rpy="0 0 0" />
|
|
|
<mass value="0.066982" />
|
|
|
<inertia ixx="0.00008" ixy="0.00000" ixz="0.00001" iyy="0.00003" iyz="0.00000" izz="0.00008" />
|
|
|
</inertial>
|
|
|
<visual>
|
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
|
<geometry>
|
|
|
<mesh filename="meshes/link1.STL" />
|
|
|
</geometry>
|
|
|
<material name="black">
|
|
|
<color rgba="0 0 0 1" />
|
|
|
</material>
|
|
|
</visual>
|
|
|
<collision>
|
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
|
<geometry>
|
|
|
<mesh filename="meshes/link1.STL" />
|
|
|
</geometry>
|
|
|
</collision>
|
|
|
</link>
|
|
|
<joint name="joint1" type="revolute">
|
|
|
<origin xyz="0 0 0.0605" rpy="0 0 0" />
|
|
|
<parent link="base_link" />
|
|
|
<child link="link1" />
|
|
|
<axis xyz="0 0 1" />
|
|
|
<limit lower="-10" upper="10" effort="100" velocity="1000" />
|
|
|
</joint>
|
|
|
<link name="link2">
|
|
|
<inertial>
|
|
|
<origin xyz="-0.13237 0.0020852 0.00010549" rpy="0 0 0" />
|
|
|
<mass value="1.0795" />
|
|
|
<inertia ixx="0.00051" ixy="0.00001" ixz="-0.00004" iyy="0.01599" iyz="0.00000" izz="0.01605" />
|
|
|
</inertial>
|
|
|
<visual>
|
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
|
<geometry>
|
|
|
<mesh filename="meshes/link2.STL" />
|
|
|
</geometry>
|
|
|
<material name="black">
|
|
|
<color rgba="0 0 0 1" />
|
|
|
</material>
|
|
|
</visual>
|
|
|
<collision>
|
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
|
<geometry>
|
|
|
<mesh filename="meshes/link2.STL" />
|
|
|
</geometry>
|
|
|
</collision>
|
|
|
</link>
|
|
|
<joint name="joint2" type="revolute">
|
|
|
<origin xyz="0.02 0 0.04" rpy="0 0 0" />
|
|
|
<parent link="link1" />
|
|
|
<child link="link2" />
|
|
|
<axis xyz="0 1 0" />
|
|
|
<limit lower="-10" upper="10" effort="100" velocity="1000" />
|
|
|
</joint>
|
|
|
<link name="link3">
|
|
|
<inertial>
|
|
|
<origin xyz="0.18531 0.00068376 -0.051638" rpy="0 0 0" />
|
|
|
<mass value="0.54534" />
|
|
|
<inertia ixx="0.00036" ixy="-0.00003" ixz="-0.00039" iyy="0.00423" iyz="0.00001" izz="0.00420" />
|
|
|
</inertial>
|
|
|
<visual>
|
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
|
<geometry>
|
|
|
<mesh filename="meshes/link3.STL" />
|
|
|
</geometry>
|
|
|
<material name="white">
|
|
|
<color rgba="1 1 1 1" />
|
|
|
</material>
|
|
|
</visual>
|
|
|
<collision>
|
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
|
<geometry>
|
|
|
<mesh filename="meshes/link3.STL" />
|
|
|
</geometry>
|
|
|
</collision>
|
|
|
</link>
|
|
|
<joint name="joint3" type="revolute">
|
|
|
<origin xyz="-0.264 0 0" rpy="3.1416 0 0" />
|
|
|
<parent link="link2" />
|
|
|
<child link="link3" />
|
|
|
<axis xyz="0 1 0" />
|
|
|
<limit lower="-10" upper="10" effort="100" velocity="1000" />
|
|
|
</joint>
|
|
|
<link name="link4">
|
|
|
<inertial>
|
|
|
<origin xyz="0.040231 0.0044807 -0.035335" rpy="0 0 0" />
|
|
|
<mass value="0.11714" />
|
|
|
<inertia ixx="0.00019" ixy="-0.00002" ixz="-0.00009" iyy="0.00023" iyz="0.00002" izz="0.00014" />
|
|
|
</inertial>
|
|
|
<visual>
|
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
|
<geometry>
|
|
|
<mesh filename="meshes/link4.STL" />
|
|
|
</geometry>
|
|
|
<material name="black">
|
|
|
<color rgba="0 0 0 1" />
|
|
|
</material>
|
|
|
</visual>
|
|
|
<collision>
|
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
|
<geometry>
|
|
|
<mesh filename="meshes/link4.STL" />
|
|
|
</geometry>
|
|
|
</collision>
|
|
|
</link>
|
|
|
<joint name="joint4" type="revolute">
|
|
|
<origin xyz="0.245 0 -0.056" rpy="0 0 0" />
|
|
|
<parent link="link3" />
|
|
|
<child link="link4" />
|
|
|
<axis xyz="0 1 0" />
|
|
|
<limit lower="-10" upper="10" effort="100" velocity="1000" />
|
|
|
</joint>
|
|
|
<link name="link5">
|
|
|
<inertial>
|
|
|
<origin xyz="0.003612 -1.5455E-05 0.055214" rpy="0 0 0" />
|
|
|
<mass value="0.63488" />
|
|
|
<inertia ixx="0.00083" ixy="0.00000" ixz="0.00007" iyy="0.00082" iyz="0.00000" izz="0.00026" />
|
|
|
</inertial>
|
|
|
<visual>
|
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
|
<geometry>
|
|
|
<mesh filename="meshes/link5.STL" />
|
|
|
</geometry>
|
|
|
<material name="black">
|
|
|
<color rgba="0 0 0 1" />
|
|
|
</material>
|
|
|
</visual>
|
|
|
<collision>
|
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
|
<geometry>
|
|
|
<mesh filename="meshes/link5.STL" />
|
|
|
</geometry>
|
|
|
</collision>
|
|
|
</link>
|
|
|
<joint name="joint5" type="revolute">
|
|
|
<origin xyz="0.06775 0.0005 -0.0865" rpy="0 0 0" />
|
|
|
<parent link="link4" />
|
|
|
<child link="link5" />
|
|
|
<axis xyz="0 0 1" />
|
|
|
<limit lower="-10" upper="10" effort="100" velocity="1000" />
|
|
|
</joint>
|
|
|
<link name="link6">
|
|
|
<inertial>
|
|
|
<origin xyz="0.041697 2.4368E-05 0.00014464" rpy="0 0 0" />
|
|
|
<mass value="0.44089" />
|
|
|
<inertia ixx="0.00038" ixy="0.00000" ixz="0.00000" iyy="0.00028" iyz="0.00000" izz="0.00050" />
|
|
|
</inertial>
|
|
|
<visual>
|
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
|
<geometry>
|
|
|
<mesh filename="meshes/link6.STL" />
|
|
|
</geometry>
|
|
|
<material name="black">
|
|
|
<color rgba="0 0 0 1" />
|
|
|
</material>
|
|
|
</visual>
|
|
|
<collision>
|
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
|
<geometry>
|
|
|
<mesh filename="meshes/link6.STL" />
|
|
|
</geometry>
|
|
|
</collision>
|
|
|
</link>
|
|
|
<joint name="joint6" type="revolute">
|
|
|
<origin xyz="0.02895 0 0.0865" rpy="-3.1416 0 0" />
|
|
|
<parent link="link5" />
|
|
|
<child link="link6" />
|
|
|
<axis xyz="1 0 0" />
|
|
|
<limit lower="-3.14" upper="3.14" effort="100" velocity="1000" />
|
|
|
</joint>
|
|
|
|
|
|
<link name="camera_base">
|
|
|
<visual>
|
|
|
<origin xyz="0 0 0.0" rpy="0 0 0"/>
|
|
|
<geometry>
|
|
|
<mesh filename="meshes/camera_base.glb" />
|
|
|
</geometry>
|
|
|
</visual>
|
|
|
</link>
|
|
|
<joint name="hand_to_camera_mount" type="fixed">
|
|
|
<parent link="link6"/>
|
|
|
<child link="camera_base"/>
|
|
|
<origin xyz="0.057 0 0" rpy="0 0 -3.1416"/>
|
|
|
</joint>
|
|
|
|
|
|
<link name="camera">
|
|
|
<visual>
|
|
|
<origin rpy="0.0 0.0 -1.5707963267948966" xyz="0.0 0.0 -0.0"/>
|
|
|
<geometry>
|
|
|
<mesh filename="meshes/camera.glb" />
|
|
|
</geometry>
|
|
|
</visual>
|
|
|
</link>
|
|
|
<joint name="camera_joint" type="fixed">
|
|
|
<parent link="camera_base"/>
|
|
|
<child link="camera"/>
|
|
|
<origin xyz="-0.0275 0.0 0.05" rpy="0 0.3491 3.141592653589793"/>
|
|
|
</joint>
|
|
|
|
|
|
<link name="link7">
|
|
|
<inertial>
|
|
|
<origin xyz="-0.00035522 -0.007827 -0.0029883" rpy="0 0 0" />
|
|
|
<mass value="0.064798" />
|
|
|
<inertia ixx="0.00002" ixy="0.00000" ixz="0.00000" iyy="0.00003" iyz="0.00000" izz="0.00003" />
|
|
|
</inertial>
|
|
|
<visual>
|
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
|
<geometry>
|
|
|
<mesh filename="meshes/link7.STL" />
|
|
|
</geometry>
|
|
|
<material name="black">
|
|
|
<color rgba="0 0 0 1" />
|
|
|
</material>
|
|
|
</visual>
|
|
|
<collision>
|
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
|
<geometry>
|
|
|
<mesh filename="meshes/link7.STL" />
|
|
|
</geometry>
|
|
|
</collision>
|
|
|
</link>
|
|
|
<joint name="joint7" type="prismatic">
|
|
|
<origin xyz="0.08657 0.024896 -0.0002436" rpy="0 0 0" />
|
|
|
<parent link="link6" />
|
|
|
<child link="link7" />
|
|
|
<axis xyz="0 1 0" />
|
|
|
<limit lower="0" upper="0.044" effort="100" velocity="1000" />
|
|
|
</joint>
|
|
|
<link name="link8">
|
|
|
<inertial>
|
|
|
<origin xyz="-0.00035522 0.0078277 0.0024201" rpy="0 0 0" />
|
|
|
<mass value="0.064798" />
|
|
|
<inertia ixx="0.00002" ixy="0.00000" ixz="0.00000" iyy="0.00003" iyz="0.00000" izz="0.00003" />
|
|
|
</inertial>
|
|
|
<visual>
|
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
|
<geometry>
|
|
|
<mesh filename="meshes/link8.STL" />
|
|
|
</geometry>
|
|
|
<material name="black">
|
|
|
<color rgba="0 0 0 1" />
|
|
|
</material>
|
|
|
</visual>
|
|
|
<collision>
|
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
|
<geometry>
|
|
|
<mesh filename="meshes/link8.STL" />
|
|
|
</geometry>
|
|
|
</collision>
|
|
|
</link>
|
|
|
<joint name="joint8" type="prismatic">
|
|
|
<origin xyz="0.08657 -0.0249 -0.00024366" rpy="0 0 0" />
|
|
|
<parent link="link6" />
|
|
|
<child link="link8" />
|
|
|
<axis xyz="0 -1 0" />
|
|
|
<limit lower="0" upper="0.044" effort="100" velocity="1000" />
|
|
|
</joint>
|
|
|
</robot> |