runtime/rasms_description/urdf/rasms_description.urdf

395 lines
8.2 KiB
Text
Raw Normal View History

<?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-1-g15f4949 Build Version: 1.6.7594.29634
For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
<robot
name="rasms">
<link
name="base">
<inertial>
<origin
xyz="-0.00033212 0.00010743 -0.036421"
rpy="0 0 0" />
<mass
value="1.3101" />
<inertia
ixx="0.0025958"
ixy="9.7863E-07"
ixz="-1.4731E-05"
iyy="0.0023883"
iyz="5.8191E-07"
izz="0.0043068" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://rasms_description/meshes/base.STL" />
</geometry>
<material
name="rasms_color">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://rasms_description/meshes/base.STL" />
</geometry>
</collision>
</link>
<link
name="link1">
<inertial>
<origin
xyz="0.080526 -0.028752 -0.00018483"
rpy="0 0 0" />
<mass
value="0.52648" />
<inertia
ixx="0.00038929"
ixy="3.5255E-05"
ixz="2.2864E-07"
iyy="0.00076496"
iyz="6.2982E-08"
izz="0.00075521" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://rasms_description/meshes/link1.STL" />
</geometry>
<material
name="rasms_color">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://rasms_description/meshes/link1.STL" />
</geometry>
</collision>
</link>
<joint
name="joint1"
type="revolute">
<origin
xyz="0 0 0"
rpy="3.1352 -1.5708 0" />
<parent
link="base" />
<child
link="link1" />
<axis
xyz="1 0 0" />
<limit
lower="-3.1416"
upper="3.1416"
effort="0"
velocity="0" />
</joint>
<link
name="link2">
<inertial>
<origin
xyz="0.025632 0.0098422 6.3301E-05"
rpy="0 0 0" />
<mass
value="0.46645" />
<inertia
ixx="0.00030236"
ixy="6.3961E-06"
ixz="4.0548E-08"
iyy="0.00025015"
iyz="-9.5727E-08"
izz="0.00026486" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://rasms_description/meshes/link2.STL" />
</geometry>
<material
name="rasms_color">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://rasms_description/meshes/link2.STL" />
</geometry>
</collision>
</link>
<joint
name="joint2"
type="continuous">
<origin
xyz="0.14172 0 0"
rpy="0 0 0" />
<parent
link="link1" />
<child
link="link2" />
<axis
xyz="0 1 0" />
<limit
lower="-2.0944"
upper="2.0944"
effort="0"
velocity="0" />
</joint>
<link
name="link3">
<inertial>
<origin
xyz="0.069442 -0.021508 -0.00029297"
rpy="0 0 0" />
<mass
value="0.70817" />
<inertia
ixx="0.00048214"
ixy="3.6229E-05"
ixz="4.9555E-07"
iyy="0.00086485"
iyz="6.0984E-08"
izz="0.0008604" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://rasms_description/meshes/link3.STL" />
</geometry>
<material
name="rasms_color">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://rasms_description/meshes/link3.STL" />
</geometry>
</collision>
</link>
<joint
name="joint3"
type="continuous">
<origin
xyz="0.081346 0 0"
rpy="0 0 0" />
<parent
link="link2" />
<child
link="link3" />
<axis
xyz="1 0 0" />
<limit
lower="-2.0944"
upper="2.0944"
effort="0"
velocity="0" />
</joint>
<link
name="link4">
<inertial>
<origin
xyz="0.025632 0.0098415 0.0001341"
rpy="0 0 0" />
<mass
value="0.46645" />
<inertia
ixx="0.00030236"
ixy="6.3957E-06"
ixz="8.6559E-08"
iyy="0.00025015"
iyz="-2.0152E-07"
izz="0.00026486" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://rasms_description/meshes/link4.STL" />
</geometry>
<material
name="rasms_color">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://rasms_description/meshes/link4.STL" />
</geometry>
</collision>
</link>
<joint
name="joint4"
type="continuous">
<origin
xyz="0.14438 0 0"
rpy="0 0 0" />
<parent
link="link3" />
<child
link="link4" />
<axis
xyz="0 1 0" />
<limit
lower="-2.0944"
upper="2.0944"
effort="0"
velocity="0" />
</joint>
<link
name="link5">
<inertial>
<origin
xyz="0.069442 -0.021508 -0.00029297"
rpy="0 0 0" />
<mass
value="0.70817" />
<inertia
ixx="0.00048214"
ixy="3.6229E-05"
ixz="4.9555E-07"
iyy="0.00086485"
iyz="6.0984E-08"
izz="0.0008604" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://rasms_description/meshes/link5.STL" />
</geometry>
<material
name="rasms_color">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://rasms_description/meshes/link5.STL" />
</geometry>
</collision>
</link>
<joint
name="joint5"
type="continuous">
<origin
xyz="0.081346 0 0"
rpy="0 0 0" />
<parent
link="link4" />
<child
link="link5" />
<axis
xyz="1 0 0" />
<limit
lower="-2.0944"
upper="2.0944"
effort="0"
velocity="0" />
</joint>
<link
name="link6">
<inertial>
<origin
xyz="0.033705 0.010795 0.00015348"
rpy="0 0 0" />
<mass
value="0.59936" />
<inertia
ixx="0.00035851"
ixy="5.7985E-06"
ixz="7.8497E-08"
iyy="0.00028631"
iyz="-1.8291E-07"
izz="0.00029514" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://rasms_description/meshes/link6.STL" />
</geometry>
<material
name="rasms_color">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://rasms_description/meshes/link6.STL" />
</geometry>
</collision>
</link>
<joint
name="joint6"
type="continuous">
<origin
xyz="0.14438 0 0"
rpy="0 0 0" />
<parent
link="link5" />
<child
link="link6" />
<axis
xyz="0 1 0" />
<limit
lower="-2.0944"
upper="2.0944"
effort="0"
velocity="0" />
</joint>
</robot>