Add link/joint names for DeepMimic humanoid urdf

This commit is contained in:
erwincoumans 2018-11-20 21:40:20 -08:00
parent bded2968ea
commit 41e28e3587

View File

@ -1,12 +1,12 @@
<robot name="dumpUrdf">
<link name="root" >
<link name="base" >
<inertial>
<origin rpy = "0 0 0" xyz = "0 0 0" />
<mass value = "0.00100" />
<inertia ixx = "0.1" ixy = "0" ixz = "0" iyy = "0.1" iyz = "0" izz = "0.1" />
</inertial>
</link>
<link name="link0" >
<link name="root" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 0.280000 0.000000" />
<mass value = "6.000000" />
@ -19,12 +19,12 @@
</geometry>
</collision>
</link>
<joint name="joint0" type="fixed" >
<parent link = "root" />
<child link="link0" />
<joint name="root" type="fixed" >
<parent link = "base" />
<child link="root" />
<origin rpy = "0 0 0" xyz = "0.000000 0.000000 0.000000" />
</joint>
<link name="link1" >
<link name="chest" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 0.480000 0.000000" />
<mass value = "14.000000" />
@ -37,12 +37,12 @@
</geometry>
</collision>
</link>
<joint name="joint1" type="spherical" >
<parent link="link0" />
<child link="link1" />
<joint name="chest" type="spherical" >
<parent link="root" />
<child link="chest" />
<origin rpy = "0 0 0" xyz = "0.000000 0.944604 0.000000" />
</joint>
<link name="link2" >
<link name="neck" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 0.700000 0.000000" />
<mass value = "2.000000" />
@ -55,12 +55,12 @@
</geometry>
</collision>
</link>
<joint name="joint2" type="spherical" >
<parent link="link1" />
<child link="link2" />
<joint name="neck" type="spherical" >
<parent link="chest" />
<child link="neck" />
<origin rpy = "0 0 0" xyz = "0.000000 0.895576 0.000000" />
</joint>
<link name="link3" >
<link name="right_hip" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 -0.840000 0.000000" />
<mass value = "4.500000" />
@ -73,12 +73,12 @@
</geometry>
</collision>
</link>
<joint name="joint3" type="spherical" >
<parent link="link0" />
<child link="link3" />
<joint name="right_hip" type="spherical" >
<parent link="root" />
<child link="right_hip" />
<origin rpy = "0 0 0" xyz = "0.000000 0.000000 0.339548" />
</joint>
<link name="link4" >
<link name="right_knee" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 -0.800000 0.000000" />
<mass value = "3.000000" />
@ -91,13 +91,14 @@
</geometry>
</collision>
</link>
<joint name="joint4" type="continuous" >
<parent link="link3" />
<child link="link4" />
<joint name="right_knee" type="revolute" >
<parent link="right_hip" />
<child link="right_knee" />
<limit effort="1000.0" lower="-3.14" upper="0." velocity="0.5"/>
<origin rpy = "0 0 0" xyz = "0.000000 -1.686184 0.000000" />
<axis xyz = "0.000000 0.000000 1.000000" />
</joint>
<link name="link5" >
<link name="right_ankle" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.180000 -0.090000 0.000000" />
<mass value = "1.000000" />
@ -110,12 +111,12 @@
</geometry>
</collision>
</link>
<joint name="joint5" type="spherical" >
<parent link="link4" />
<child link="link5" />
<joint name="right_ankle" type="spherical" >
<parent link="right_knee" />
<child link="right_ankle" />
<origin rpy = "0 0 0" xyz = "0.000000 -1.639480 0.000000" />
</joint>
<link name="link6" >
<link name="right_shoulder" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 -0.560000 0.000000" />
<mass value = "1.500000" />
@ -128,12 +129,12 @@
</geometry>
</collision>
</link>
<joint name="joint6" type="spherical" >
<parent link="link1" />
<child link="link6" />
<joint name="right_shoulder" type="spherical" >
<parent link="chest" />
<child link="right_shoulder" />
<origin rpy = "0 0 0" xyz = "-0.096200 0.974000 0.732440" />
</joint>
<link name="link7" >
<link name="right_elbow" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 -0.480000 0.000000" />
<mass value = "1.000000" />
@ -146,13 +147,14 @@
</geometry>
</collision>
</link>
<joint name="joint7" type="continuous" >
<parent link="link6" />
<child link="link7" />
<joint name="right_elbow" type="revolute" >
<parent link="right_shoulder" />
<child link="right_elbow" />
<limit effort="1000.0" lower="0" upper="3.14" velocity="0.5"/>
<origin rpy = "0 0 0" xyz = "0.000000 -1.099152 0.000000" />
<axis xyz = "0.000000 0.000000 1.000000" />
</joint>
<link name="link8" >
<link name="right_wrist" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 0.000000 0.000000" />
<mass value = "0.500000" />
@ -165,12 +167,12 @@
</geometry>
</collision>
</link>
<joint name="joint8" type="fixed" >
<parent link="link7" />
<child link="link8" />
<joint name="right_wrist" type="fixed" >
<parent link="right_elbow" />
<child link="right_wrist" />
<origin rpy = "0 0 0" xyz = "0.000000 -1.035788 0.000000" />
</joint>
<link name="link9" >
<link name="left_hip" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 -0.840000 0.000000" />
<mass value = "4.500000" />
@ -183,12 +185,12 @@
</geometry>
</collision>
</link>
<joint name="joint9" type="spherical" >
<parent link="link0" />
<child link="link9" />
<joint name="left_hip" type="spherical" >
<parent link="root" />
<child link="left_hip" />
<origin rpy = "0 0 0" xyz = "0.000000 0.000000 -0.339548" />
</joint>
<link name="link10" >
<link name="left_knee" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 -0.800000 0.000000" />
<mass value = "3.000000" />
@ -201,13 +203,14 @@
</geometry>
</collision>
</link>
<joint name="joint10" type="continuous" >
<parent link="link9" />
<child link="link10" />
<joint name="left_knee" type="revolute" >
<parent link="left_hip" />
<child link="left_knee" />
<limit effort="1000.0" lower="-3.14" upper="0." velocity="0.5"/>
<origin rpy = "0 0 0" xyz = "0.000000 -1.686184 0.000000" />
<axis xyz = "0.000000 0.000000 1.000000" />
</joint>
<link name="link11" >
<link name="left_ankle" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.180000 -0.090000 0.000000" />
<mass value = "1.000000" />
@ -220,12 +223,12 @@
</geometry>
</collision>
</link>
<joint name="joint11" type="spherical" >
<parent link="link10" />
<child link="link11" />
<joint name="left_ankle" type="spherical" >
<parent link="left_knee" />
<child link="left_ankle" />
<origin rpy = "0 0 0" xyz = "0.000000 -1.639480 0.000000" />
</joint>
<link name="link12" >
<link name="left_shoulder" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 -0.560000 0.000000" />
<mass value = "1.500000" />
@ -238,12 +241,12 @@
</geometry>
</collision>
</link>
<joint name="joint12" type="spherical" >
<parent link="link1" />
<child link="link12" />
<joint name="left_shoulder" type="spherical" >
<parent link="chest" />
<child link="left_shoulder" />
<origin rpy = "0 0 0" xyz = "-0.096200 0.974000 -0.732440" />
</joint>
<link name="link13" >
<link name="left_elbow" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 -0.480000 0.000000" />
<mass value = "1.000000" />
@ -256,13 +259,14 @@
</geometry>
</collision>
</link>
<joint name="joint13" type="continuous" >
<parent link="link12" />
<child link="link13" />
<joint name="left_elbow" type="revolute" >
<parent link="left_shoulder" />
<child link="left_elbow" />
<limit effort="1000.0" lower="0" upper="3.14" velocity="0.5"/>
<origin rpy = "0 0 0" xyz = "0.000000 -1.099152 0.000000" />
<axis xyz = "0.000000 0.000000 1.000000" />
</joint>
<link name="link14" >
<link name="left_wrist" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 0.000000 0.000000" />
<mass value = "0.500000" />
@ -275,9 +279,9 @@
</geometry>
</collision>
</link>
<joint name="joint14" type="fixed" >
<parent link="link13" />
<child link="link14" />
<joint name="left_wrist" type="fixed" >
<parent link="left_elbow" />
<child link="left_wrist" />
<origin rpy = "0 0 0" xyz = "0.000000 -1.035788 0.000000" />
</joint>
</robot>