Commit f59ed252 authored by mnaveau's avatar mnaveau

modify the urdf and srdf to fit the walking pattern generator needs

parent fb739663
......@@ -12,7 +12,7 @@
TODO: - the set of interesting collision pairs
-->
<robot name=simple_humanoid>
<robot name="simple_humanoid">
<!-- groups -->
<!-- To remove when the grippers will be added
......@@ -55,36 +55,59 @@
<!-- pre-defined states -->
<!-- simple_humanoid pre-defined states -->
<group_state name="half_sitting" group="all">
<joint name="waist" value="0 0 0 0 0 0 " />
<joint name="RLEG_HIP_R" value="0" />
<joint name="RLEG_HIP_P" value="0" />
<joint name="RLEG_HIP_Y" value="0" />
<joint name="RLEG_KNEE" value="0" />
<joint name="RLEG_ANKLE_P" value="0" />
<joint name="RLEG_ANKLE_R" value="0" />
<joint name="RARM_SHOULDER_P"value="0" />
<joint name="RARM_SHOULDER_R"value="0" />
<joint name="RARM_SHOULDER_Y"value="0" />
<joint name="RARM_ELBOW" value="0" />
<joint name="RARM_WRIST_Y" value="0" />
<joint name="RARM_WRIST_P" value="0" />
<joint name="RARM_WRIST_R" value="0" />
<joint name="LLEG_HIP_R" value="0" />
<joint name="LLEG_HIP_P" value="0" />
<joint name="LLEG_HIP_Y" value="0" />
<joint name="LLEG_KNEE" value="0" />
<joint name="LLEG_ANKLE_P" value="0" />
<joint name="LLEG_ANKLE_R" value="0" />
<joint name="LARM_SHOULDER_P"value="0" />
<joint name="LARM_SHOULDER_R"value="0" />
<joint name="LARM_SHOULDER_Y"value="0" />
<joint name="LARM_ELBOW" value="0" />
<joint name="LARM_WRIST_Y" value="0" />
<joint name="LARM_WRIST_P" value="0" />
<joint name="LARM_WRIST_R" value="0" />
<joint name="WAIST_P" value="0" />
<joint name="WAIST_R" value="0" />
<joint name="CHEST" value="0" />
<!-- <joint name="waist" value="0 0 0 0 0 0 " /> -->
<joint name="RLEG_HIP_R" value="0" />
<joint name="RLEG_HIP_P" value="-0.453786" />
<joint name="RLEG_HIP_Y" value="0" />
<joint name="RLEG_KNEE" value="0.872665" />
<joint name="RLEG_ANKLE_P" value="-0.418879" />
<joint name="RLEG_ANKLE_R" value="0" />
<joint name="RARM_SHOULDER_P" value="-0.17453" />
<joint name="RARM_SHOULDER_R" value="0.261799" />
<joint name="RARM_SHOULDER_Y" value="0" />
<joint name="RARM_ELBOW" value="-0.523599" />
<joint name="RARM_WRIST_Y" value="0" />
<joint name="RARM_WRIST_P" value="0" />
<joint name="RARM_WRIST_R" value="0" />
<joint name="LLEG_HIP_R" value="0" />
<joint name="LLEG_HIP_P" value="-0.453786" />
<joint name="LLEG_HIP_Y" value="0" />
<joint name="LLEG_KNEE" value="0.872665" />
<joint name="LLEG_ANKLE_P" value="-0.418879" />
<joint name="LLEG_ANKLE_R" value="0" />
<joint name="LARM_SHOULDER_P" value="0.17453" />
<joint name="LARM_SHOULDER_R" value="0.261799" />
<joint name="LARM_SHOULDER_Y" value="0" />
<joint name="LARM_ELBOW" value="-0.523599" />
<joint name="LARM_WRIST_Y" value="0" />
<joint name="LARM_WRIST_P" value="0" />
<joint name="LARM_WRIST_R" value="0" />
<joint name="WAIST_P" value="0" />
<joint name="WAIST_R" value="0" />
<joint name="CHEST" value="0" />
</group_state>
<!--
Simple Humnaoid Specificities.
foot height = y axis
foot width = x axis
foot depth = z axis
-->
<specificities>
<feet>
<right>
<size height="0.14" width="0.25" depth="0.10" />
<anklePosition x="0.0" y="0.0" z="0.105" />
</right>
<left>
<size height="0.14" width="0.25" depth="0.10" />
<anklePosition x="0.0" y="0.0" z="0.105" />
</left>
</feet>
</specificities>
</robot>
......@@ -7,7 +7,8 @@
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="simple_humanoid">
<link name="base_link"/>
<link name="WAIST_LINK0">
<!-- VRML link name="WAIST_LINK0" -->
<link name="BODY">
<inertial>
<origin xyz="0 0 0.0375" rpy="0 0 0"/>
<mass value="27"/>
......@@ -31,7 +32,8 @@
</inertial>
</link>
<link name="WAIST_LINK3">
<!-- VRML link name="WAIST_LINK3" -->
<link name="torso">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="13"/>
......@@ -87,7 +89,8 @@
</inertial>
</link>
<link name="LARM_LINK7">
<!-- VRML link name="LARM_LINK7" -->
<link name="l_wrist">
<inertial>
<origin xyz="0 0 -0.1" rpy="0 0 0"/>
<mass value="0.4"/>
......@@ -143,7 +146,8 @@
</inertial>
</link>
<link name="RARM_LINK7">
<!-- VRML link name="RARM_LINK7" -->
<link name="r_wrist">
<inertial>
<origin xyz="0 0 -0.1" rpy="0 0 0"/>
<mass value="0.4"/>
......@@ -191,7 +195,8 @@
</inertial>
</link>
<link name="LLEG_LINK6">
<!-- VRML link name="LLEG_LINK6" -->
<link name="l_ankle">
<inertial>
<origin xyz="0.28 0 -0.2" rpy="0 0 0"/>
<mass value="1.9"/>
......@@ -239,7 +244,8 @@
</inertial>
</link>
<link name="RLEG_LINK6">
<!-- VRML link name="RLEG_LINK6" -->
<link name="r_ankle">
<inertial>
<origin xyz="0.28 0 -0.2" rpy="0 0 0"/>
<mass value="1.9"/>
......@@ -253,13 +259,14 @@
<joint name="waist" type="fixed">
<parent link="base_link"/>
<child link="WAIST_LINK0"/>
<child link="BODY"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
</joint>
<joint name="RLEG_HIP_R" type="revolute">
<origin xyz="0 -0.09 0" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
<parent link="WAIST_LINK0"/>
<parent link="BODY"/>
<child link="RLEG_LINK1"/>
<limit effort="30" lower="0" upper="0" velocity="0" />
</joint>
......@@ -300,14 +307,14 @@
<origin xyz="0 0 0" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
<parent link="RLEG_LINK5"/>
<child link="RLEG_LINK6"/>
<child link="r_ankle"/>
<limit effort="30" lower="0" upper="0" velocity="0" />
</joint>
<joint name="RARM_SHOULDER_P" type="revolute">
<origin xyz="0 -0.21 0" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<parent link="WAIST_LINK3"/>
<parent link="torso"/>
<child link="RARM_LINK1"/>
<limit effort="30" lower="0" upper="0" velocity="0" />
</joint>
......@@ -356,14 +363,14 @@
<origin xyz="0 0 0" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
<parent link="RARM_LINK6"/>
<child link="RARM_LINK7"/>
<child link="r_wrist"/>
<limit effort="30" lower="0" upper="0" velocity="0" />
</joint>
<joint name="LLEG_HIP_R" type="revolute">
<origin xyz="0 0.09 0" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
<parent link="WAIST_LINK0"/>
<parent link="BODY"/>
<child link="LLEG_LINK1"/>
<limit effort="30" lower="0" upper="0" velocity="0" />
</joint>
......@@ -404,14 +411,14 @@
<origin xyz="0 0 0" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
<parent link="LLEG_LINK5"/>
<child link="LLEG_LINK6"/>
<child link="l_ankle"/>
<limit effort="30" lower="0" upper="0" velocity="0" />
</joint>
<joint name="LARM_SHOULDER_P" type="revolute">
<origin xyz="0 0.21 0" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<parent link="WAIST_LINK3"/>
<parent link="torso"/>
<child link="LARM_LINK1"/>
<limit effort="30" lower="0" upper="0" velocity="0" />
</joint>
......@@ -460,14 +467,14 @@
<origin xyz="0 0 0" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
<parent link="LARM_LINK6"/>
<child link="LARM_LINK7"/>
<child link="l_wrist"/>
<limit effort="30" lower="0" upper="0" velocity="0" />
</joint>
<joint name="WAIST_P" type="revolute">
<origin xyz="0 0 0.176" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<parent link="WAIST_LINK0"/>
<parent link="BODY"/>
<child link="WAIST_LINK1"/>
<limit effort="30" lower="0" upper="0" velocity="0" />
</joint>
......@@ -484,7 +491,7 @@
<origin xyz="0 0 0.35" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<parent link="WAIST_LINK2"/>
<child link="WAIST_LINK3"/>
<child link="torso"/>
<limit effort="30" lower="0" upper="0" velocity="0" />
</joint>
......
Markdown is supported
0%
or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment