Files
bullet3/examples/pybullet/gym/pybullet_data/humanoid/humanoid.urdf
erwincoumans 9bddca873c allow pybullet_envs.deep_mimic.testrl --arg_file run_humanoid3d_backflip_args.txt to perform a backflip. Can only backflip twice, then drops on ground.
this deepmimic is still very slow, due to slow mass matrix/inverse dynamics computation. once spherical motor drive is enabled, it should be fast(er)
move pd_controller_stable to pybullet_utils for easier re-use
add plane_transparent.urdf to pybullet_data
allow spacebar in keyboardEvents (Windows for now)
2019-02-10 20:56:31 -08:00

288 lines
9.6 KiB
XML
Raw Blame History

This file contains invisible Unicode characters

This file contains invisible Unicode characters that are indistinguishable to humans but may be processed differently by a computer. If you think that this is intentional, you can safely ignore this warning. Use the Escape button to reveal them.

<robot name="dumpUrdf">
<link name="base" >
<inertial>
<origin rpy = "0 0 0" xyz = "0 0 0" />
<mass value = "0.0001" />
<inertia ixx = "0.0001" ixy = "0" ixz = "0" iyy = "0.0001" iyz = "0" izz = "0.0001" />
</inertial>
</link>
<link name="root" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 0.280000 0.000000" />
<mass value = "6.000000" />
<inertia ixx = "0.1" ixy = "0" ixz = "0" iyy = "0.1" iyz = "0" izz = "0.1" />
</inertial>
<collision>
<origin rpy = "0 0 0" xyz = "0.000000 0.280000 0.000000" />
<geometry>
<sphere radius = "0.360000" />
</geometry>
</collision>
</link>
<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="chest" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 0.480000 0.000000" />
<mass value = "14.000000" />
<inertia ixx = "0.1" ixy = "0" ixz = "0" iyy = "0.1" iyz = "0" izz = "0.1" />
</inertial>
<collision>
<origin rpy = "0 0 0" xyz = "0.000000 0.480000 0.000000" />
<geometry>
<sphere radius = "0.440000" />
</geometry>
</collision>
</link>
<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="neck" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 0.700000 0.000000" />
<mass value = "2.000000" />
<inertia ixx = "0.1" ixy = "0" ixz = "0" iyy = "0.1" iyz = "0" izz = "0.1" />
</inertial>
<collision>
<origin rpy = "0 0 0" xyz = "0.000000 0.700000 0.000000" />
<geometry>
<sphere radius = "0.410000" />
</geometry>
</collision>
</link>
<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="right_hip" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 -0.840000 0.000000" />
<mass value = "4.500000" />
<inertia ixx = "0.1" ixy = "0" ixz = "0" iyy = "0.1" iyz = "0" izz = "0.1" />
</inertial>
<collision>
<origin rpy = "-1.570796 0 0" xyz = "0.000000 -0.840000 0.000000" />
<geometry>
<capsule length="1.200000" radius="0.220000"/>
</geometry>
</collision>
</link>
<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="right_knee" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 -0.800000 0.000000" />
<mass value = "3.000000" />
<inertia ixx = "0.1" ixy = "0" ixz = "0" iyy = "0.1" iyz = "0" izz = "0.1" />
</inertial>
<collision>
<origin rpy = "-1.570796 0 0" xyz = "0.000000 -0.800000 0.000000" />
<geometry>
<capsule length="1.240000" radius="0.200000"/>
</geometry>
</collision>
</link>
<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="right_ankle" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.180000 -0.090000 0.000000" />
<mass value = "1.000000" />
<inertia ixx = "0.1" ixy = "0" ixz = "0" iyy = "0.1" iyz = "0" izz = "0.1" />
</inertial>
<collision>
<origin rpy = "0 0 0" xyz = "0.180000 -0.090000 0.000000" />
<geometry>
<box size="0.708000 0.220000 0.360000" />
</geometry>
</collision>
</link>
<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="right_shoulder" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 -0.560000 0.000000" />
<mass value = "1.500000" />
<inertia ixx = "0.1" ixy = "0" ixz = "0" iyy = "0.1" iyz = "0" izz = "0.1" />
</inertial>
<collision>
<origin rpy = "-1.570796 0 0" xyz = "0.000000 -0.560000 0.000000" />
<geometry>
<capsule length="0.720000" radius="0.180000"/>
</geometry>
</collision>
</link>
<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="right_elbow" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 -0.480000 0.000000" />
<mass value = "1.000000" />
<inertia ixx = "0.1" ixy = "0" ixz = "0" iyy = "0.1" iyz = "0" izz = "0.1" />
</inertial>
<collision>
<origin rpy = "-1.570796 0 0" xyz = "0.000000 -0.480000 0.000000" />
<geometry>
<capsule length="0.540000" radius="0.160000"/>
</geometry>
</collision>
</link>
<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="right_wrist" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 0.000000 0.000000" />
<mass value = "0.500000" />
<inertia ixx = "0.1" ixy = "0" ixz = "0" iyy = "0.1" iyz = "0" izz = "0.1" />
</inertial>
<collision>
<origin rpy = "0 0 0" xyz = "0.000000 0.000000 0.000000" />
<geometry>
<sphere radius = "0.160000" />
</geometry>
</collision>
</link>
<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="left_hip" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 -0.840000 0.000000" />
<mass value = "4.500000" />
<inertia ixx = "0.1" ixy = "0" ixz = "0" iyy = "0.1" iyz = "0" izz = "0.1" />
</inertial>
<collision>
<origin rpy = "-1.570796 0 0" xyz = "0.000000 -0.840000 0.000000" />
<geometry>
<capsule length="1.200000" radius="0.220000"/>
</geometry>
</collision>
</link>
<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="left_knee" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 -0.800000 0.000000" />
<mass value = "3.000000" />
<inertia ixx = "0.1" ixy = "0" ixz = "0" iyy = "0.1" iyz = "0" izz = "0.1" />
</inertial>
<collision>
<origin rpy = "-1.570796 0 0" xyz = "0.000000 -0.800000 0.000000" />
<geometry>
<capsule length="1.240000" radius="0.200000"/>
</geometry>
</collision>
</link>
<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="left_ankle" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.180000 -0.090000 0.000000" />
<mass value = "1.000000" />
<inertia ixx = "0.1" ixy = "0" ixz = "0" iyy = "0.1" iyz = "0" izz = "0.1" />
</inertial>
<collision>
<origin rpy = "0 0 0" xyz = "0.180000 -0.090000 0.000000" />
<geometry>
<box size="0.708000 0.220000 0.360000" />
</geometry>
</collision>
</link>
<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="left_shoulder" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 -0.560000 0.000000" />
<mass value = "1.500000" />
<inertia ixx = "0.1" ixy = "0" ixz = "0" iyy = "0.1" iyz = "0" izz = "0.1" />
</inertial>
<collision>
<origin rpy = "-1.570796 0 0" xyz = "0.000000 -0.560000 0.000000" />
<geometry>
<capsule length="0.720000" radius="0.180000"/>
</geometry>
</collision>
</link>
<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="left_elbow" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 -0.480000 0.000000" />
<mass value = "1.000000" />
<inertia ixx = "0.1" ixy = "0" ixz = "0" iyy = "0.1" iyz = "0" izz = "0.1" />
</inertial>
<collision>
<origin rpy = "-1.570796 0 0" xyz = "0.000000 -0.480000 0.000000" />
<geometry>
<capsule length="0.540000" radius="0.160000"/>
</geometry>
</collision>
</link>
<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="left_wrist" >
<inertial>
<origin rpy = "0 0 0" xyz = "0.000000 0.000000 0.000000" />
<mass value = "0.500000" />
<inertia ixx = "0.1" ixy = "0" ixz = "0" iyy = "0.1" iyz = "0" izz = "0.1" />
</inertial>
<collision>
<origin rpy = "0 0 0" xyz = "0.000000 0.000000 0.000000" />
<geometry>
<sphere radius = "0.160000" />
</geometry>
</collision>
</link>
<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>