improve the new pybullet gym environments, follow camera, disable 2D GUI, disable rendering during loading (makes it faster)
disable vsync on Mac fix setup.py file
This commit is contained in:
@@ -470,6 +470,10 @@ int Mac_createWindow(struct MacOpenGLWindowInternalData* m_internalData,struct M
|
|||||||
#else
|
#else
|
||||||
m_internalData->m_retinaScaleFactor=1.f;
|
m_internalData->m_retinaScaleFactor=1.f;
|
||||||
#endif
|
#endif
|
||||||
|
GLint sync = 0;
|
||||||
|
CGLContextObj ctx = CGLGetCurrentContext();
|
||||||
|
CGLSetParameter(ctx, kCGLCPSwapInterval, &sync);
|
||||||
|
|
||||||
[m_internalData->m_myApp finishLaunching];
|
[m_internalData->m_myApp finishLaunching];
|
||||||
[pool release];
|
[pool release];
|
||||||
|
|
||||||
|
|||||||
@@ -3,7 +3,8 @@ import time
|
|||||||
import math
|
import math
|
||||||
from datetime import datetime
|
from datetime import datetime
|
||||||
|
|
||||||
#clid = p.connect(p.SHARED_MEMORY)
|
clid = p.connect(p.SHARED_MEMORY)
|
||||||
|
if (clid<0):
|
||||||
p.connect(p.GUI)
|
p.connect(p.GUI)
|
||||||
p.loadURDF("plane.urdf",[0,0,-0.3])
|
p.loadURDF("plane.urdf",[0,0,-0.3])
|
||||||
kukaId = p.loadURDF("kuka_iiwa/model.urdf",[0,0,0])
|
kukaId = p.loadURDF("kuka_iiwa/model.urdf",[0,0,0])
|
||||||
|
|||||||
@@ -24,24 +24,39 @@ class SmallReactivePolicy:
|
|||||||
def demo_run():
|
def demo_run():
|
||||||
env = gym.make("AntBulletEnv-v0")
|
env = gym.make("AntBulletEnv-v0")
|
||||||
|
|
||||||
cid = p.connect(p.SHARED_MEMORY) # only show graphics if the browser is already running....
|
cid = p.connect(p.GUI)
|
||||||
if cid < 0:
|
p.configureDebugVisualizer(p.COV_ENABLE_GUI,0)
|
||||||
cid = p.connect(p.DIRECT)
|
|
||||||
|
|
||||||
pi = SmallReactivePolicy(env.observation_space, env.action_space)
|
pi = SmallReactivePolicy(env.observation_space, env.action_space)
|
||||||
|
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||||
|
env.reset()
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||||
|
torsoId = -1
|
||||||
|
for i in range (p.getNumBodies()):
|
||||||
|
print(p.getBodyInfo(i))
|
||||||
|
if (p.getBodyInfo(i)[0].decode() == "torso"):
|
||||||
|
torsoId=i
|
||||||
|
print("found torso")
|
||||||
|
|
||||||
while 1:
|
while 1:
|
||||||
frame = 0
|
frame = 0
|
||||||
score = 0
|
score = 0
|
||||||
restart_delay = 0
|
restart_delay = 0
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||||
obs = env.reset()
|
obs = env.reset()
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||||
|
|
||||||
while 1:
|
while 1:
|
||||||
time.sleep(0.01)
|
time.sleep(0.001)
|
||||||
a = pi.act(obs)
|
a = pi.act(obs)
|
||||||
obs, r, done, _ = env.step(a)
|
obs, r, done, _ = env.step(a)
|
||||||
score += r
|
score += r
|
||||||
frame += 1
|
frame += 1
|
||||||
|
distance=5
|
||||||
|
yaw = 0
|
||||||
|
humanPos, humanOrn = p.getBasePositionAndOrientation(torsoId)
|
||||||
|
p.resetDebugVisualizerCamera(distance,yaw,-20,humanPos);
|
||||||
|
|
||||||
still_open = env.render("human")
|
still_open = env.render("human")
|
||||||
if still_open==False:
|
if still_open==False:
|
||||||
return
|
return
|
||||||
|
|||||||
@@ -24,24 +24,42 @@ class SmallReactivePolicy:
|
|||||||
def demo_run():
|
def demo_run():
|
||||||
env = gym.make("HalfCheetahBulletEnv-v0")
|
env = gym.make("HalfCheetahBulletEnv-v0")
|
||||||
|
|
||||||
cid = p.connect(p.SHARED_MEMORY) # only show graphics if the browser is already running....
|
cid = p.connect(p.GUI)
|
||||||
if cid < 0:
|
|
||||||
cid = p.connect(p.DIRECT)
|
|
||||||
|
|
||||||
pi = SmallReactivePolicy(env.observation_space, env.action_space)
|
pi = SmallReactivePolicy(env.observation_space, env.action_space)
|
||||||
|
#disable rendering during reset, makes loading much faster
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_GUI,0)
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||||
|
env.reset()
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||||
|
torsoId = -1
|
||||||
|
for i in range (p.getNumBodies()):
|
||||||
|
print(p.getBodyInfo(i))
|
||||||
|
if (p.getBodyInfo(i)[1].decode() == "cheetah"):
|
||||||
|
torsoId=i
|
||||||
|
print("found torso")
|
||||||
|
print(p.getNumJoints(torsoId))
|
||||||
|
for j in range (p.getNumJoints(torsoId)):
|
||||||
|
print(p.getJointInfo(torsoId,j))#LinkState(torsoId,j))
|
||||||
|
|
||||||
while 1:
|
while 1:
|
||||||
frame = 0
|
frame = 0
|
||||||
score = 0
|
score = 0
|
||||||
restart_delay = 0
|
restart_delay = 0
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||||
obs = env.reset()
|
obs = env.reset()
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||||
|
|
||||||
while 1:
|
while 1:
|
||||||
time.sleep(0.01)
|
time.sleep(0.001)
|
||||||
a = pi.act(obs)
|
a = pi.act(obs)
|
||||||
obs, r, done, _ = env.step(a)
|
obs, r, done, _ = env.step(a)
|
||||||
score += r
|
score += r
|
||||||
frame += 1
|
frame += 1
|
||||||
|
distance=5
|
||||||
|
yaw = 0
|
||||||
|
humanPos = p.getLinkState(torsoId,4)[0]
|
||||||
|
p.resetDebugVisualizerCamera(distance,yaw,-20,humanPos);
|
||||||
still_open = env.render("human")
|
still_open = env.render("human")
|
||||||
if still_open==False:
|
if still_open==False:
|
||||||
return
|
return
|
||||||
|
|||||||
@@ -26,24 +26,40 @@ class SmallReactivePolicy:
|
|||||||
def demo_run():
|
def demo_run():
|
||||||
env = gym.make("HopperBulletEnv-v0")
|
env = gym.make("HopperBulletEnv-v0")
|
||||||
|
|
||||||
cid = p.connect(p.SHARED_MEMORY) # only show graphics if the browser is already running....
|
cid = p.connect(p.GUI)
|
||||||
if cid < 0:
|
p.configureDebugVisualizer(p.COV_ENABLE_GUI,0)
|
||||||
cid = p.connect(p.DIRECT)
|
|
||||||
|
|
||||||
pi = SmallReactivePolicy(env.observation_space, env.action_space)
|
pi = SmallReactivePolicy(env.observation_space, env.action_space)
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||||
|
env.reset()
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||||
|
for i in range (p.getNumBodies()):
|
||||||
|
print(p.getBodyInfo(i))
|
||||||
|
if (p.getBodyInfo(i)[1].decode() == "hopper"):
|
||||||
|
torsoId=i
|
||||||
|
print("found torso")
|
||||||
|
print(p.getNumJoints(torsoId))
|
||||||
|
for j in range (p.getNumJoints(torsoId)):
|
||||||
|
print(p.getJointInfo(torsoId,j))#LinkState(torsoId,j))
|
||||||
while 1:
|
while 1:
|
||||||
frame = 0
|
frame = 0
|
||||||
score = 0
|
score = 0
|
||||||
restart_delay = 0
|
restart_delay = 0
|
||||||
|
#disable rendering during reset, makes loading much faster
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||||
obs = env.reset()
|
obs = env.reset()
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||||
|
|
||||||
while 1:
|
while 1:
|
||||||
time.sleep(0.01)
|
time.sleep(0.001)
|
||||||
a = pi.act(obs)
|
a = pi.act(obs)
|
||||||
obs, r, done, _ = env.step(a)
|
obs, r, done, _ = env.step(a)
|
||||||
score += r
|
score += r
|
||||||
frame += 1
|
frame += 1
|
||||||
|
distance=5
|
||||||
|
yaw = 0
|
||||||
|
humanPos = p.getLinkState(torsoId,4)[0]
|
||||||
|
p.resetDebugVisualizerCamera(distance,yaw,-20,humanPos);
|
||||||
|
|
||||||
still_open = env.render("human")
|
still_open = env.render("human")
|
||||||
if still_open==False:
|
if still_open==False:
|
||||||
return
|
return
|
||||||
|
|||||||
@@ -25,24 +25,37 @@ class SmallReactivePolicy:
|
|||||||
def demo_run():
|
def demo_run():
|
||||||
env = gym.make("HumanoidBulletEnv-v0")
|
env = gym.make("HumanoidBulletEnv-v0")
|
||||||
|
|
||||||
cid = p.connect(p.SHARED_MEMORY) # only show graphics if the browser is already running....
|
cid = p.connect(p.GUI)
|
||||||
if cid < 0:
|
p.configureDebugVisualizer(p.COV_ENABLE_GUI,0)
|
||||||
cid = p.connect(p.DIRECT)
|
|
||||||
|
|
||||||
pi = SmallReactivePolicy(env.observation_space, env.action_space)
|
pi = SmallReactivePolicy(env.observation_space, env.action_space)
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||||
|
env.reset()
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||||
|
torsoId = -1
|
||||||
|
for i in range (p.getNumBodies()):
|
||||||
|
print(p.getBodyInfo(i))
|
||||||
|
if (p.getBodyInfo(i)[0].decode() == "torso"):
|
||||||
|
torsoId=i
|
||||||
|
print("found humanoid torso")
|
||||||
while 1:
|
while 1:
|
||||||
frame = 0
|
frame = 0
|
||||||
score = 0
|
score = 0
|
||||||
restart_delay = 0
|
restart_delay = 0
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||||
obs = env.reset()
|
obs = env.reset()
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||||
|
|
||||||
while 1:
|
while 1:
|
||||||
time.sleep(0.01)
|
time.sleep(0.001)
|
||||||
a = pi.act(obs)
|
a = pi.act(obs)
|
||||||
obs, r, done, _ = env.step(a)
|
obs, r, done, _ = env.step(a)
|
||||||
score += r
|
score += r
|
||||||
frame += 1
|
frame += 1
|
||||||
|
distance=5
|
||||||
|
yaw = 0
|
||||||
|
humanPos, humanOrn = p.getBasePositionAndOrientation(torsoId)
|
||||||
|
p.resetDebugVisualizerCamera(distance,yaw,-20,humanPos);
|
||||||
|
|
||||||
still_open = env.render("human")
|
still_open = env.render("human")
|
||||||
if still_open==False:
|
if still_open==False:
|
||||||
return
|
return
|
||||||
|
|||||||
@@ -24,9 +24,7 @@ class SmallReactivePolicy:
|
|||||||
def demo_run():
|
def demo_run():
|
||||||
env = gym.make("InvertedDoublePendulumBulletEnv-v0")
|
env = gym.make("InvertedDoublePendulumBulletEnv-v0")
|
||||||
|
|
||||||
cid = p.connect(p.SHARED_MEMORY) # only show graphics if the browser is already running....
|
cid = p.connect(p.GUI)
|
||||||
if cid < 0:
|
|
||||||
cid = p.connect(p.DIRECT)
|
|
||||||
|
|
||||||
pi = SmallReactivePolicy(env.observation_space, env.action_space)
|
pi = SmallReactivePolicy(env.observation_space, env.action_space)
|
||||||
|
|
||||||
|
|||||||
@@ -22,12 +22,10 @@ class SmallReactivePolicy:
|
|||||||
return x
|
return x
|
||||||
|
|
||||||
def demo_run():
|
def demo_run():
|
||||||
|
print("create env")
|
||||||
env = gym.make("InvertedPendulumBulletEnv-v0")
|
env = gym.make("InvertedPendulumBulletEnv-v0")
|
||||||
|
print("connecting")
|
||||||
cid = p.connect(p.SHARED_MEMORY) # only show graphics if the browser is already running....
|
cid = p.connect(p.GUI)
|
||||||
if cid < 0:
|
|
||||||
cid = p.connect(p.DIRECT)
|
|
||||||
|
|
||||||
pi = SmallReactivePolicy(env.observation_space, env.action_space)
|
pi = SmallReactivePolicy(env.observation_space, env.action_space)
|
||||||
|
|
||||||
while 1:
|
while 1:
|
||||||
@@ -35,7 +33,7 @@ def demo_run():
|
|||||||
score = 0
|
score = 0
|
||||||
restart_delay = 0
|
restart_delay = 0
|
||||||
obs = env.reset()
|
obs = env.reset()
|
||||||
|
print("frame")
|
||||||
while 1:
|
while 1:
|
||||||
time.sleep(0.05)
|
time.sleep(0.05)
|
||||||
a = pi.act(obs)
|
a = pi.act(obs)
|
||||||
|
|||||||
@@ -24,9 +24,7 @@ class SmallReactivePolicy:
|
|||||||
def demo_run():
|
def demo_run():
|
||||||
env = gym.make("InvertedPendulumSwingupBulletEnv-v0")
|
env = gym.make("InvertedPendulumSwingupBulletEnv-v0")
|
||||||
|
|
||||||
cid = p.connect(p.SHARED_MEMORY) # only show graphics if the browser is already running....
|
cid = p.connect(p.GUI)
|
||||||
if cid < 0:
|
|
||||||
cid = p.connect(p.DIRECT)
|
|
||||||
|
|
||||||
pi = SmallReactivePolicy(env.observation_space, env.action_space)
|
pi = SmallReactivePolicy(env.observation_space, env.action_space)
|
||||||
|
|
||||||
|
|||||||
@@ -24,12 +24,24 @@ class SmallReactivePolicy:
|
|||||||
def demo_run():
|
def demo_run():
|
||||||
env = gym.make("Walker2DBulletEnv-v0")
|
env = gym.make("Walker2DBulletEnv-v0")
|
||||||
|
|
||||||
cid = p.connect(p.SHARED_MEMORY) # only show graphics if the browser is already running....
|
cid = p.connect(p.GUI)
|
||||||
if cid < 0:
|
p.configureDebugVisualizer(p.COV_ENABLE_GUI,0)
|
||||||
cid = p.connect(p.DIRECT)
|
|
||||||
|
|
||||||
pi = SmallReactivePolicy(env.observation_space, env.action_space)
|
pi = SmallReactivePolicy(env.observation_space, env.action_space)
|
||||||
|
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_GUI,0)
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||||
|
env.reset()
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||||
|
torsoId = -1
|
||||||
|
for i in range (p.getNumBodies()):
|
||||||
|
print(p.getBodyInfo(i))
|
||||||
|
if (p.getBodyInfo(i)[1].decode() == "walker2d"):
|
||||||
|
torsoId=i
|
||||||
|
print("found torso")
|
||||||
|
print(p.getNumJoints(torsoId))
|
||||||
|
for j in range (p.getNumJoints(torsoId)):
|
||||||
|
print(p.getJointInfo(torsoId,j))#LinkState(torsoId,j))
|
||||||
|
|
||||||
while 1:
|
while 1:
|
||||||
frame = 0
|
frame = 0
|
||||||
score = 0
|
score = 0
|
||||||
@@ -37,11 +49,15 @@ def demo_run():
|
|||||||
obs = env.reset()
|
obs = env.reset()
|
||||||
|
|
||||||
while 1:
|
while 1:
|
||||||
time.sleep(0.01)
|
time.sleep(0.001)
|
||||||
a = pi.act(obs)
|
a = pi.act(obs)
|
||||||
obs, r, done, _ = env.step(a)
|
obs, r, done, _ = env.step(a)
|
||||||
score += r
|
score += r
|
||||||
frame += 1
|
frame += 1
|
||||||
|
distance=5
|
||||||
|
yaw = 0
|
||||||
|
humanPos = p.getLinkState(torsoId,4)[0]
|
||||||
|
p.resetDebugVisualizerCamera(distance,yaw,-20,humanPos);
|
||||||
still_open = env.render("human")
|
still_open = env.render("human")
|
||||||
if still_open==False:
|
if still_open==False:
|
||||||
return
|
return
|
||||||
|
|||||||
@@ -1,5 +1,5 @@
|
|||||||
from scene_stadium import SinglePlayerStadiumScene
|
from .scene_stadium import SinglePlayerStadiumScene
|
||||||
from env_bases import MujocoXmlBaseBulletEnv
|
from .env_bases import MujocoXmlBaseBulletEnv
|
||||||
import numpy as np
|
import numpy as np
|
||||||
from robot_locomotors import Hopper, Walker2D, HalfCheetah, Ant, Humanoid
|
from robot_locomotors import Hopper, Walker2D, HalfCheetah, Ant, Humanoid
|
||||||
|
|
||||||
|
|||||||
@@ -1,5 +1,5 @@
|
|||||||
from scene_abstract import SingleRobotEmptyScene
|
from .scene_abstract import SingleRobotEmptyScene
|
||||||
from env_bases import MujocoXmlBaseBulletEnv
|
from .env_bases import MujocoXmlBaseBulletEnv
|
||||||
from robot_pendula import InvertedPendulum, InvertedPendulumSwingup, InvertedDoublePendulum
|
from robot_pendula import InvertedPendulum, InvertedPendulumSwingup, InvertedDoublePendulum
|
||||||
import gym, gym.spaces, gym.utils, gym.utils.seeding
|
import gym, gym.spaces, gym.utils, gym.utils.seeding
|
||||||
import numpy as np
|
import numpy as np
|
||||||
|
|||||||
@@ -14,6 +14,8 @@ class StadiumScene(Scene):
|
|||||||
# stadium_pose.set_xyz(27, 21, 0) # see RUN_STARTLINE, RUN_RAD constants
|
# stadium_pose.set_xyz(27, 21, 0) # see RUN_STARTLINE, RUN_RAD constants
|
||||||
self.stadium = p.loadSDF("stadium.sdf")
|
self.stadium = p.loadSDF("stadium.sdf")
|
||||||
self.ground_plane_mjcf = p.loadMJCF("mjcf/ground_plane.xml")
|
self.ground_plane_mjcf = p.loadMJCF("mjcf/ground_plane.xml")
|
||||||
|
for i in self.ground_plane_mjcf:
|
||||||
|
p.changeVisualShape(i,-1,rgbaColor=[0,0,0,0])
|
||||||
|
|
||||||
class SinglePlayerStadiumScene(StadiumScene):
|
class SinglePlayerStadiumScene(StadiumScene):
|
||||||
"This scene created by environment, to work in a way as if there was no concept of scene visible to user."
|
"This scene created by environment, to work in a way as if there was no concept of scene visible to user."
|
||||||
|
|||||||
2
setup.py
2
setup.py
@@ -399,7 +399,7 @@ elif _platform == "win32":
|
|||||||
elif _platform == "darwin":
|
elif _platform == "darwin":
|
||||||
print("darwin!")
|
print("darwin!")
|
||||||
os.environ['LDFLAGS'] = '-framework Cocoa -framework OpenGL'
|
os.environ['LDFLAGS'] = '-framework Cocoa -framework OpenGL'
|
||||||
CXX_FLAFS += '-DB3_NO_PYTHON_FRAMEWORK '
|
CXX_FLAGS += '-DB3_NO_PYTHON_FRAMEWORK '
|
||||||
CXX_FLAGS += '-DHAS_SOCKLEN_T '
|
CXX_FLAGS += '-DHAS_SOCKLEN_T '
|
||||||
CXX_FLAGS += '-D_DARWIN '
|
CXX_FLAGS += '-D_DARWIN '
|
||||||
# CXX_FLAGS += '-framework Cocoa '
|
# CXX_FLAGS += '-framework Cocoa '
|
||||||
|
|||||||
Reference in New Issue
Block a user