2021-10-19 20:52:07 +04:00
|
|
|
<?xml version="1.0" encoding="utf-8"?>
|
2021-10-19 23:26:26 +04:00
|
|
|
<robot name="rasms" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
2021-10-19 20:52:07 +04:00
|
|
|
|
|
|
|
|
2021-10-19 23:26:26 +04:00
|
|
|
<xacro:include filename="$(find rasms_description)/urdf/rasms.gazebo.xacro"/>
|
|
|
|
<xacro:include filename="$(find rasms_description)/urdf/rasms.control.xacro"/>
|
2021-10-19 20:52:07 +04:00
|
|
|
<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.000332122479320982 0.000107427994729828 -0.0364210136165633"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<mass
|
|
|
|
value="1.31011976880718" />
|
|
|
|
<inertia
|
|
|
|
ixx="0.00259583556985636"
|
|
|
|
ixy="9.78631121059142E-07"
|
|
|
|
ixz="-1.47312310265428E-05"
|
|
|
|
iyy="0.00238834687122552"
|
|
|
|
iyz="5.81913913034168E-07"
|
|
|
|
izz="0.00430679870377171" />
|
|
|
|
</inertial>
|
|
|
|
<visual>
|
|
|
|
<origin
|
|
|
|
xyz="0 0 0"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<geometry>
|
|
|
|
<mesh
|
2021-10-19 23:26:26 +04:00
|
|
|
filename="package://rasms_description/meshes/base.stl" />
|
2021-10-19 20:52:07 +04:00
|
|
|
</geometry>
|
|
|
|
<material
|
|
|
|
name="">
|
|
|
|
<color
|
|
|
|
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
|
|
|
</material>
|
|
|
|
</visual>
|
|
|
|
<collision>
|
|
|
|
<origin
|
|
|
|
xyz="0 0 0"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<geometry>
|
|
|
|
<mesh
|
2021-10-19 23:26:26 +04:00
|
|
|
filename="package://rasms_description/meshes/base.stl" />
|
2021-10-19 20:52:07 +04:00
|
|
|
</geometry>
|
|
|
|
</collision>
|
|
|
|
</link>
|
|
|
|
<link
|
|
|
|
name="link1">
|
|
|
|
<inertial>
|
|
|
|
<origin
|
|
|
|
xyz="0.028753 0.080526 1.3501E-08"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<mass
|
|
|
|
value="0.52648" />
|
|
|
|
<inertia
|
|
|
|
ixx="0.00076496"
|
|
|
|
ixy="-3.5256E-05"
|
|
|
|
ixz="-2.8173E-10"
|
|
|
|
iyy="0.00038929"
|
|
|
|
iyz="1.9918E-09"
|
|
|
|
izz="0.00075521" />
|
|
|
|
</inertial>
|
|
|
|
<visual>
|
|
|
|
<origin
|
|
|
|
xyz="0 0 0"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<geometry>
|
|
|
|
<mesh
|
2021-10-19 23:26:26 +04:00
|
|
|
filename="package://rasms_description/meshes/link1.stl" />
|
2021-10-19 20:52:07 +04:00
|
|
|
</geometry>
|
|
|
|
<material
|
|
|
|
name="">
|
|
|
|
<color
|
|
|
|
rgba="0.79216 0.81961 0.93333 1" />
|
|
|
|
</material>
|
|
|
|
</visual>
|
|
|
|
<collision>
|
|
|
|
<origin
|
|
|
|
xyz="0 0 0"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<geometry>
|
|
|
|
<mesh
|
2021-10-19 23:26:26 +04:00
|
|
|
filename="package://rasms_description/meshes/link1.stl" />
|
2021-10-19 20:52:07 +04:00
|
|
|
</geometry>
|
|
|
|
</collision>
|
|
|
|
</link>
|
|
|
|
<joint
|
|
|
|
name="joint1"
|
|
|
|
type="continuous">
|
|
|
|
<origin
|
|
|
|
xyz="0 0 0"
|
|
|
|
rpy="1.5708 0 -1.5708" />
|
|
|
|
<parent
|
|
|
|
link="base" />
|
|
|
|
<child
|
|
|
|
link="link1" />
|
|
|
|
<axis
|
|
|
|
xyz="0 1 0" />
|
|
|
|
</joint>
|
|
|
|
<link
|
|
|
|
name="link2">
|
|
|
|
<inertial>
|
|
|
|
<origin
|
|
|
|
xyz="-0.0098423932944443 0.025631709550142 2.62062855886029E-08"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<mass
|
|
|
|
value="0.466449031624498" />
|
|
|
|
<inertia
|
|
|
|
ixx="0.000250149264856934"
|
|
|
|
ixy="-6.39625267943634E-06"
|
|
|
|
ixz="1.16240576365026E-09"
|
|
|
|
iyy="0.000302356392836182"
|
|
|
|
iyz="-5.72107071817652E-10"
|
|
|
|
izz="0.000264859050215469" />
|
|
|
|
</inertial>
|
|
|
|
<visual>
|
|
|
|
<origin
|
|
|
|
xyz="0 0 0"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<geometry>
|
|
|
|
<mesh
|
2021-10-19 23:26:26 +04:00
|
|
|
filename="package://rasms_description/meshes/link2.stl" />
|
2021-10-19 20:52:07 +04:00
|
|
|
</geometry>
|
|
|
|
<material
|
|
|
|
name="">
|
|
|
|
<color
|
|
|
|
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
|
|
|
</material>
|
|
|
|
</visual>
|
|
|
|
<collision>
|
|
|
|
<origin
|
|
|
|
xyz="0 0 0"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<geometry>
|
|
|
|
<mesh
|
2021-10-19 23:26:26 +04:00
|
|
|
filename="package://rasms_description/meshes/link2.stl" />
|
2021-10-19 20:52:07 +04:00
|
|
|
</geometry>
|
|
|
|
</collision>
|
|
|
|
</link>
|
|
|
|
<joint
|
|
|
|
name="joint2"
|
|
|
|
type="continuous">
|
|
|
|
<origin
|
|
|
|
xyz="0 0.14172 0"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<parent
|
|
|
|
link="link1" />
|
|
|
|
<child
|
|
|
|
link="link2" />
|
|
|
|
<axis
|
|
|
|
xyz="1 0 0" />
|
|
|
|
</joint>
|
|
|
|
<link
|
|
|
|
name="link3">
|
|
|
|
<inertial>
|
|
|
|
<origin
|
|
|
|
xyz="0.0215100033761789 0.0694423986454957 3.93278649368959E-08"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<mass
|
|
|
|
value="0.70816935413754" />
|
|
|
|
<inertia
|
|
|
|
ixx="0.000864850509477081"
|
|
|
|
ixy="-3.62319530566251E-05"
|
|
|
|
ixz="-2.95541145601842E-10"
|
|
|
|
iyy="0.000482143975333292"
|
|
|
|
iyz="2.00353934934295E-09"
|
|
|
|
izz="0.000860394915615017" />
|
|
|
|
</inertial>
|
|
|
|
<visual>
|
|
|
|
<origin
|
|
|
|
xyz="0 0 0"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<geometry>
|
|
|
|
<mesh
|
2021-10-19 23:26:26 +04:00
|
|
|
filename="package://rasms_description/meshes/link3.stl" />
|
2021-10-19 20:52:07 +04:00
|
|
|
</geometry>
|
|
|
|
<material
|
|
|
|
name="">
|
|
|
|
<color
|
|
|
|
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
|
|
|
</material>
|
|
|
|
</visual>
|
|
|
|
<collision>
|
|
|
|
<origin
|
|
|
|
xyz="0 0 0"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<geometry>
|
|
|
|
<mesh
|
2021-10-19 23:26:26 +04:00
|
|
|
filename="package://rasms_description/meshes/link3.stl" />
|
2021-10-19 20:52:07 +04:00
|
|
|
</geometry>
|
|
|
|
</collision>
|
|
|
|
</link>
|
|
|
|
<joint
|
|
|
|
name="joint3"
|
|
|
|
type="continuous">
|
|
|
|
<origin
|
|
|
|
xyz="0 0.081346 0"
|
|
|
|
rpy="0 0.0071935 0" />
|
|
|
|
<parent
|
|
|
|
link="link2" />
|
|
|
|
<child
|
|
|
|
link="link3" />
|
|
|
|
<axis
|
|
|
|
xyz="0 1 0" />
|
|
|
|
</joint>
|
|
|
|
<link
|
|
|
|
name="link4">
|
|
|
|
<inertial>
|
|
|
|
<origin
|
|
|
|
xyz="-0.0098423941326931 0.025631710847922 2.62314079923008E-08"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<mass
|
|
|
|
value="0.466449036998311" />
|
|
|
|
<inertia
|
|
|
|
ixx="0.0002501492525602"
|
|
|
|
ixy="-6.39624584934821E-06"
|
|
|
|
ixz="1.15937712750973E-09"
|
|
|
|
iyy="0.000302356392948396"
|
|
|
|
iyz="-5.70585180406975E-10"
|
|
|
|
izz="0.000264859056361031" />
|
|
|
|
</inertial>
|
|
|
|
<visual>
|
|
|
|
<origin
|
|
|
|
xyz="0 0 0"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<geometry>
|
|
|
|
<mesh
|
2021-10-19 23:26:26 +04:00
|
|
|
filename="package://rasms_description/meshes/link4.stl" />
|
2021-10-19 20:52:07 +04:00
|
|
|
</geometry>
|
|
|
|
<material
|
|
|
|
name="">
|
|
|
|
<color
|
|
|
|
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
|
|
|
</material>
|
|
|
|
</visual>
|
|
|
|
<collision>
|
|
|
|
<origin
|
|
|
|
xyz="0 0 0"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<geometry>
|
|
|
|
<mesh
|
2021-10-19 23:26:26 +04:00
|
|
|
filename="package://rasms_description/meshes/link4.stl" />
|
2021-10-19 20:52:07 +04:00
|
|
|
</geometry>
|
|
|
|
</collision>
|
|
|
|
</link>
|
|
|
|
<joint
|
|
|
|
name="joint4"
|
|
|
|
type="continuous">
|
|
|
|
<origin
|
|
|
|
xyz="0 0.14438 0"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<parent
|
|
|
|
link="link3" />
|
|
|
|
<child
|
|
|
|
link="link4" />
|
|
|
|
<axis
|
|
|
|
xyz="1 0 0" />
|
|
|
|
</joint>
|
|
|
|
<link
|
|
|
|
name="link5">
|
|
|
|
<inertial>
|
|
|
|
<origin
|
|
|
|
xyz="0.0215100033039704 0.0694423990612557 3.93278667377771E-08"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<mass
|
|
|
|
value="0.708169356775496" />
|
|
|
|
<inertia
|
|
|
|
ixx="0.000864850515095"
|
|
|
|
ixy="-3.6231953093431E-05"
|
|
|
|
ixz="-2.95541136548844E-10"
|
|
|
|
iyy="0.000482143976309882"
|
|
|
|
iyz="2.00353938873391E-09"
|
|
|
|
izz="0.000860394921240315" />
|
|
|
|
</inertial>
|
|
|
|
<visual>
|
|
|
|
<origin
|
|
|
|
xyz="0 0 0"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<geometry>
|
|
|
|
<mesh
|
2021-10-19 23:26:26 +04:00
|
|
|
filename="package://rasms_description/meshes/link5.stl" />
|
2021-10-19 20:52:07 +04:00
|
|
|
</geometry>
|
|
|
|
<material
|
|
|
|
name="">
|
|
|
|
<color
|
|
|
|
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
|
|
|
</material>
|
|
|
|
</visual>
|
|
|
|
<collision>
|
|
|
|
<origin
|
|
|
|
xyz="0 0 0"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<geometry>
|
|
|
|
<mesh
|
2021-10-19 23:26:26 +04:00
|
|
|
filename="package://rasms_description/meshes/link5.stl" />
|
2021-10-19 20:52:07 +04:00
|
|
|
</geometry>
|
|
|
|
</collision>
|
|
|
|
</link>
|
|
|
|
<joint
|
|
|
|
name="joint5"
|
|
|
|
type="continuous">
|
|
|
|
<origin
|
|
|
|
xyz="0 0.081346 0"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<parent
|
|
|
|
link="link4" />
|
|
|
|
<child
|
|
|
|
link="link5" />
|
|
|
|
<axis
|
|
|
|
xyz="0 1 0" />
|
|
|
|
</joint>
|
|
|
|
<link
|
|
|
|
name="link6">
|
|
|
|
<inertial>
|
|
|
|
<origin
|
|
|
|
xyz="-0.0107961703559938 0.0337046197725978 6.41961769822694E-06"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<mass
|
|
|
|
value="0.599356299495803" />
|
|
|
|
<inertia
|
|
|
|
ixx="0.000286310483854348"
|
|
|
|
ixy="-5.79903953240378E-06"
|
|
|
|
ixz="6.26853068396246E-08"
|
|
|
|
iyy="0.000358508548445319"
|
|
|
|
iyz="-4.97585335654749E-10"
|
|
|
|
izz="0.000295138763544911" />
|
|
|
|
</inertial>
|
|
|
|
<visual>
|
|
|
|
<origin
|
|
|
|
xyz="0 0 0"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<geometry>
|
|
|
|
<mesh
|
2021-10-19 23:26:26 +04:00
|
|
|
filename="package://rasms_description/meshes/link6.stl" />
|
2021-10-19 20:52:07 +04:00
|
|
|
</geometry>
|
|
|
|
<material
|
|
|
|
name="">
|
|
|
|
<color
|
|
|
|
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
|
|
|
</material>
|
|
|
|
</visual>
|
|
|
|
<collision>
|
|
|
|
<origin
|
|
|
|
xyz="0 0 0"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<geometry>
|
|
|
|
<mesh
|
2021-10-19 23:26:26 +04:00
|
|
|
filename="package://rasms_description/meshes/link6.stl" />
|
2021-10-19 20:52:07 +04:00
|
|
|
</geometry>
|
|
|
|
</collision>
|
|
|
|
</link>
|
|
|
|
<joint
|
|
|
|
name="joint6"
|
|
|
|
type="continuous">
|
|
|
|
<origin
|
|
|
|
xyz="0 0.14438 0"
|
|
|
|
rpy="0 0 0" />
|
|
|
|
<parent
|
|
|
|
link="link5" />
|
|
|
|
<child
|
|
|
|
link="link6" />
|
|
|
|
<axis
|
|
|
|
xyz="1 0 0" />
|
|
|
|
</joint>
|
|
|
|
|
|
|
|
<xacro:rasms_hi/>
|
|
|
|
<xacro:rasms_gazebo/>
|
|
|
|
</robot>
|