391 lines
8.0 KiB
XML
391 lines
8.0 KiB
XML
<?xml version="1.0" encoding="utf-8"?>
|
|
<!-- 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
|
|
name="xin">
|
|
<link
|
|
name="base_link">
|
|
<inertial>
|
|
<origin
|
|
xyz="2.2062E-06 -0.089452 0.015312"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="1.0633" />
|
|
<inertia
|
|
ixx="0.0031488"
|
|
ixy="-7.846E-08"
|
|
ixz="1.0021E-07"
|
|
iyy="0.00202"
|
|
iyz="-1.6521E-08"
|
|
izz="0.0051396" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://xin/meshes/base_link.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.75294 0.75294 0.75294 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://xin/meshes/base_link.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<link
|
|
name="Link1">
|
|
<inertial>
|
|
<origin
|
|
xyz="-0.0071819 0.00031034 0.061598"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="2.2629" />
|
|
<inertia
|
|
ixx="0.0035533"
|
|
ixy="1.4877E-06"
|
|
ixz="-3.269E-05"
|
|
iyy="0.0024578"
|
|
iyz="-1.066E-06"
|
|
izz="0.0036303" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://xin/meshes/Link1.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.75294 0.75294 0.75294 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://xin/meshes/Link1.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint
|
|
name="j1"
|
|
type="continuous">
|
|
<origin
|
|
xyz="0 0 0.024"
|
|
rpy="0 0 0" />
|
|
<parent
|
|
link="base_link" />
|
|
<child
|
|
link="Link1" />
|
|
<axis
|
|
xyz="0 0 1" />
|
|
<limit
|
|
effort="60"
|
|
velocity="3.14" />
|
|
</joint>
|
|
<link
|
|
name="Link2">
|
|
<inertial>
|
|
<origin
|
|
xyz="0.22947 -0.0031632 -0.0022707"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.97482" />
|
|
<inertia
|
|
ixx="0.00042566"
|
|
ixy="0.00027677"
|
|
ixz="-1.1303E-15"
|
|
iyy="0.0043535"
|
|
iyz="-6.9832E-13"
|
|
izz="0.0047666" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://xin/meshes/Link2.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.75294 0.75294 0.75294 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://xin/meshes/Link2.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint
|
|
name="j2"
|
|
type="revolute">
|
|
<origin
|
|
xyz="-0.001395 0 0.1015"
|
|
rpy="1.5708 0 -1.5708" />
|
|
<parent
|
|
link="Link1" />
|
|
<child
|
|
link="Link2" />
|
|
<axis
|
|
xyz="0 0 1" />
|
|
<limit
|
|
lower="0"
|
|
upper="3.14"
|
|
effort="60"
|
|
velocity="3.14" />
|
|
</joint>
|
|
<link
|
|
name="Link3">
|
|
<inertial>
|
|
<origin
|
|
xyz="0.086963 0.0016734 -0.017806"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.72964" />
|
|
<inertia
|
|
ixx="0.00028636"
|
|
ixy="1.1866E-05"
|
|
ixz="-4.7151E-08"
|
|
iyy="0.00040609"
|
|
iyz="8.3967E-07"
|
|
izz="0.00030158" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://xin/meshes/Link3.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.75294 0.75294 0.75294 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://xin/meshes/Link3.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint
|
|
name="j3"
|
|
type="revolute">
|
|
<origin
|
|
xyz="0.3265 0 -0.0071975"
|
|
rpy="0 0 0" />
|
|
<parent
|
|
link="Link2" />
|
|
<child
|
|
link="Link3" />
|
|
<axis
|
|
xyz="0 0 1" />
|
|
<limit
|
|
lower="0"
|
|
upper="1.57"
|
|
effort="20"
|
|
velocity="3.14" />
|
|
</joint>
|
|
<link
|
|
name="Link4">
|
|
<inertial>
|
|
<origin
|
|
xyz="5.52951427810755E-05 -0.00230270444841696 0.109727165961792"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.541483189887007" />
|
|
<inertia
|
|
ixx="0.000263059603979983"
|
|
ixy="1.23868002229671E-08"
|
|
ixz="-1.24134280810698E-08"
|
|
iyy="0.000284201134854818"
|
|
iyz="1.12515113310631E-06"
|
|
izz="0.000145605109171895" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://xin/meshes/Link4.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://xin/meshes/Link4.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint
|
|
name="j4"
|
|
type="continuous">
|
|
<origin
|
|
xyz="0.0905 0.052775 0.0058025"
|
|
rpy="1.5708 0 3.1416" />
|
|
<parent
|
|
link="Link3" />
|
|
<child
|
|
link="Link4" />
|
|
<axis
|
|
xyz="0 0 1" />
|
|
<limit
|
|
effort="20"
|
|
velocity="3.14" />
|
|
</joint>
|
|
<link
|
|
name="Link5">
|
|
<inertial>
|
|
<origin
|
|
xyz="0.056542 0.0013106 0.0010268"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.21817" />
|
|
<inertia
|
|
ixx="8.1275E-05"
|
|
ixy="1.143E-08"
|
|
ixz="5.0118E-07"
|
|
iyy="8.1233E-05"
|
|
iyz="1.1372E-08"
|
|
izz="8.3976E-05" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://xin/meshes/Link5.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.75294 0.75294 0.75294 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://xin/meshes/Link5.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint
|
|
name="j5"
|
|
type="revolute">
|
|
<origin
|
|
xyz="0.001627 0 0.18467"
|
|
rpy="1.5708 0 0" />
|
|
<parent
|
|
link="Link4" />
|
|
<child
|
|
link="Link5" />
|
|
<axis
|
|
xyz="0 0 1" />
|
|
<limit
|
|
lower="0"
|
|
upper="3.14"
|
|
effort="20"
|
|
velocity="3.14" />
|
|
</joint>
|
|
<link
|
|
name="Link6">
|
|
<inertial>
|
|
<origin
|
|
xyz="-7.7997E-06 1.2767E-05 0.10159"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.56255" />
|
|
<inertia
|
|
ixx="0.00025673"
|
|
ixy="-1.884E-06"
|
|
ixz="-1.1047E-07"
|
|
iyy="0.00016698"
|
|
iyz="-7.6179E-08"
|
|
izz="0.00024233" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://xin/meshes/Link6.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.75294 0.75294 0.75294 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://xin/meshes/Link6.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint
|
|
name="j6"
|
|
type="revolute">
|
|
<origin
|
|
xyz="0.10487 0.0013347 0"
|
|
rpy="1.5708 0 1.5708" />
|
|
<parent
|
|
link="Link5" />
|
|
<child
|
|
link="Link6" />
|
|
<axis
|
|
xyz="0 0 1" />
|
|
<limit
|
|
lower="0"
|
|
upper="6.3"
|
|
effort="20"
|
|
velocity="3.14" />
|
|
</joint>
|
|
</robot> |