runtime/rasms_description/urdf/rasms_description.urdf.xacro

409 lines
No EOL
8.9 KiB
XML
Executable file

<?xml version="1.0" encoding="utf-8"?>
<robot name="rasms" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find rasms_description)/urdf/rasms.gazebo.xacro"/>
<xacro:include filename="$(find rasms_description)/urdf/rasms.control.xacro"/>
<link name="world"/>
<joint name="to_world" type="fixed">
<parent link="world"/>
<child link="base"/>
<origin xyz="0.0 0.0 0.07" rpy="0.0 0.0 0.0"/>
</joint>
<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="0 -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="revolute">
<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="revolute">
<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="revolute">
<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="revolute">
<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="revolute">
<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>
<link name="tool0"/>
<joint name="to_tool0" type="fixed">
<parent link="link6"/>
<child link="tool0"/>
<origin xyz="0.101 0 0" rpy="0 1.5708 0"/>
</joint>
<xacro:rasms_hi/>
<xacro:rasms_gazebo/>
</robot>