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)
This commit is contained in:
erwincoumans
2019-02-10 20:56:31 -08:00
parent 28c9ea3aad
commit 9bddca873c
17 changed files with 551 additions and 224 deletions

View File

@@ -2,8 +2,8 @@
<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" />
<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" >

View File

@@ -0,0 +1,14 @@
newmtl Material
Ns 10.0000
Ni 1.5000
d 1.0000
Tr 0.0000
Tf 1.0000 1.0000 1.0000
illum 2
Ka 0.0000 0.0000 0.0000
Kd 0.5880 0.5880 0.5880
Ks 0.0000 0.0000 0.0000
Ke 0.0000 0.0000 0.0000
map_Kd checker_blue.png

View File

@@ -0,0 +1,18 @@
# Blender v2.66 (sub 1) OBJ File: ''
# www.blender.org
mtllib plane_transparent.mtl
o Plane
v 15.000000 -15.000000 0.000000
v 15.000000 15.000000 0.000000
v -15.000000 15.000000 0.000000
v -15.000000 -15.000000 0.000000
vt 15.000000 0.000000
vt 15.000000 15.000000
vt 0.000000 15.000000
vt 0.000000 0.000000
usemtl Material
s off
f 1/1 2/2 3/3
f 1/1 3/3 4/4

View File

@@ -0,0 +1,29 @@
<?xml version="1.0" ?>
<robot name="plane">
<link name="planeLink">
<contact>
<lateral_friction value="1"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value=".0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="plane_transparent.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 .7"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 -5"/>
<geometry>
<box size="30 30 10"/>
</geometry>
</collision>
</link>
</robot>