Merge remote-tracking branch 'bp/master'

This commit is contained in:
erwincoumans
2018-09-09 10:48:58 -07:00
44 changed files with 12921 additions and 9885 deletions

View File

@@ -0,0 +1,146 @@
#make sure to compile pybullet with PYBULLET_USE_NUMPY enabled
#otherwise use testrender.py (slower but compatible without numpy)
#you can also use GUI mode, for faster OpenGL rendering (instead of TinyRender CPU)
import os
import sys
import time
import itertools
import subprocess
import numpy as np
import pybullet
from multiprocessing import Process
camTargetPos = [0,0,0]
cameraUp = [0,0,1]
cameraPos = [1,1,1]
pitch = -10.0
roll=0
upAxisIndex = 2
camDistance = 4
pixelWidth = 84 # 320
pixelHeight = 84 # 200
nearPlane = 0.01
farPlane = 100
fov = 60
import matplotlib.pyplot as plt
class BulletSim():
def __init__(self, connection_mode, *argv):
self.connection_mode = connection_mode
self.argv = argv
def __enter__(self):
print("connecting")
optionstring='--width={} --height={}'.format(pixelWidth,pixelHeight)
optionstring += ' --window_backend=2 --render_device=0'
print(self.connection_mode, optionstring,*self.argv)
cid = pybullet.connect(self.connection_mode, options=optionstring,*self.argv)
if cid < 0:
raise ValueError
print("connected")
pybullet.configureDebugVisualizer(pybullet.COV_ENABLE_GUI,0)
pybullet.configureDebugVisualizer(pybullet.COV_ENABLE_SEGMENTATION_MARK_PREVIEW,0)
pybullet.configureDebugVisualizer(pybullet.COV_ENABLE_DEPTH_BUFFER_PREVIEW,0)
pybullet.configureDebugVisualizer(pybullet.COV_ENABLE_RGB_BUFFER_PREVIEW,0)
pybullet.resetSimulation()
pybullet.loadURDF("plane.urdf",[0,0,-1])
pybullet.loadURDF("r2d2.urdf")
pybullet.loadURDF("duck_vhacd.urdf")
pybullet.setGravity(0,0,-10)
def __exit__(self,*_,**__):
pybullet.disconnect()
def test(num_runs=300, shadow=1, log=True, plot=False):
if log:
logId = pybullet.startStateLogging(pybullet.STATE_LOGGING_PROFILE_TIMINGS, "renderTimings")
if plot:
plt.ion()
img = np.random.rand(200, 320)
#img = [tandard_normal((50,100))
image = plt.imshow(img,interpolation='none',animated=True,label="blah")
ax = plt.gca()
times = np.zeros(num_runs)
yaw_gen = itertools.cycle(range(0,360,10))
for i, yaw in zip(range(num_runs),yaw_gen):
pybullet.stepSimulation()
start = time.time()
viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex)
aspect = pixelWidth / pixelHeight;
projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane);
img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,
projectionMatrix, shadow=shadow,lightDirection=[1,1,1],
renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
#renderer=pybullet.ER_TINY_RENDERER)
stop = time.time()
duration = (stop - start)
if (duration):
fps = 1./duration
#print("fps=",fps)
else:
fps=0
#print("fps=",fps)
#print("duraction=",duration)
#print("fps=",fps)
times[i] = fps
if plot:
rgb = img_arr[2]
image.set_data(rgb)#np_img_arr)
ax.plot([0])
#plt.draw()
#plt.show()
plt.pause(0.01)
mean_time = float(np.mean(times))
print("mean: {0} for {1} runs".format(mean_time, num_runs))
print("")
if log:
pybullet.stopStateLogging(logId)
return mean_time
if __name__ == "__main__":
res = []
with BulletSim(pybullet.DIRECT):
print("\nTesting DIRECT")
mean_time = test(log=False,plot=True)
res.append(("tiny",mean_time))
with BulletSim(pybullet.DIRECT):
plugin_fn = os.path.join(pybullet.__file__.split("bullet3")[0],"bullet3/build/lib.linux-x86_64-3.5/eglRenderer.cpython-35m-x86_64-linux-gnu.so")
plugin = pybullet.loadPlugin(plugin_fn,"_tinyRendererPlugin")
if plugin < 0:
print("\nPlugin Failed to load!\n")
sys.exit()
print("\nTesting DIRECT+OpenGL")
mean_time = test(log=True)
res.append(("plugin",mean_time))
with BulletSim(pybullet.GUI):
print("\nTesting GUI")
mean_time = test(log=False)
res.append(("egl",mean_time))
print()
print("rendertest.py")
print("back nenv fps fps_tot")
for r in res:
print(r[0],"\t",1,round(r[1]),"\t",round(r[1]))

View File

@@ -0,0 +1,142 @@
#!/usr/bin/env python
import os, logging, gym
from baselines import logger
from baselines.common import set_global_seeds
from baselines.common.misc_util import boolean_flag
from baselines import bench
from baselines.a2c.a2c import learn
from baselines.common.vec_env.subproc_vec_env import SubprocVecEnv
from baselines.common.vec_env.vec_frame_stack import VecFrameStack
import time
import gym
from gym import spaces
import pybullet as p
from itertools import cycle
import numpy as np
camTargetPos = [0,0,0]
cameraUp = [0,0,1]
cameraPos = [1,1,1]
pitch = -10.0
roll=0
upAxisIndex = 2
camDistance = 4
pixelWidth = 320
pixelHeight = 200
nearPlane = 0.01
farPlane = 100
fov = 60
class TestEnv(gym.Env):
def __init__(self,
renderer = 'tiny', # ('tiny', 'egl', 'debug')
):
self.action_space = spaces.Discrete(2)
self.iter = cycle(range(0,360,10))
# how we want to show
assert renderer in ('tiny', 'egl', 'debug','plugin')
self._renderer = renderer
self._render_width = 84
self._render_height = 84
# connecting
if self._renderer == "tiny" or self._renderer == "plugin":
optionstring='--width={} --height={}'.format(self._render_width,self._render_height)
p.connect(p.DIRECT, options=optionstring)
if self._renderer == "plugin":
plugin_fn = os.path.join(p.__file__.split("bullet3")[0],"bullet3/build/lib.linux-x86_64-3.5/eglRenderer.cpython-35m-x86_64-linux-gnu.so")
plugin = p.loadPlugin(plugin_fn,"_tinyRendererPlugin")
if plugin < 0:
print("\nPlugin Failed to load! Try installing via `pip install -e .`\n")
sys.exit()
print("plugin =",plugin)
elif self._renderer == "egl":
optionstring='--width={} --height={}'.format(self._render_width,self._render_height)
optionstring += ' --window_backend=2 --render_device=0'
p.connect(p.GUI, options=optionstring)
elif self._renderer == "debug":
#print("Connection: SHARED_MEMORY")
#cid = p.connect(p.SHARED_MEMORY)
#if (cid<0):
cid = p.connect(p.GUI)
p.resetDebugVisualizerCamera(1.3,180,-41,[0.52,-0.2,-0.33])
p.configureDebugVisualizer(p.COV_ENABLE_GUI,0)
p.configureDebugVisualizer(p.COV_ENABLE_SEGMENTATION_MARK_PREVIEW,0)
p.configureDebugVisualizer(p.COV_ENABLE_DEPTH_BUFFER_PREVIEW,0)
p.configureDebugVisualizer(p.COV_ENABLE_RGB_BUFFER_PREVIEW,0)
def __del__(self):
p.disconnect()
def reset(self):
pass
def step(self,action):
p.stepSimulation()
start = time.time()
yaw = next(self.iter)
viewMatrix = p.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex)
aspect = pixelWidth / pixelHeight;
projectionMatrix = p.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane);
img_arr = p.getCameraImage(pixelWidth, pixelHeight, viewMatrix,
projectionMatrix, shadow=1,lightDirection=[1,1,1],
renderer=p.ER_BULLET_HARDWARE_OPENGL)
#renderer=pybullet.ER_TINY_RENDERER)
self._observation = img_arr[2]
return np.array(self._observation), 0, 0, {}
def seed(self, seed=None):
pass
def train(env_id, num_timesteps=300, seed=0,num_env=2,renderer='tiny'):
def make_env(rank):
def _thunk():
if env_id == "TestEnv":
env = TestEnv(renderer=renderer) #gym.make(env_id)
else:
env = gym.make(env_id)
env.seed(seed + rank)
env = bench.Monitor(env, logger.get_dir() and os.path.join(logger.get_dir(), str(rank)))
gym.logger.setLevel(logging.WARN)
# only clip rewards when not evaluating
return env
return _thunk
set_global_seeds(seed)
env = SubprocVecEnv([make_env(i) for i in range(num_env)])
env.reset()
start = time.time()
for i in range(num_timesteps):
action = [env.action_space.sample() for _ in range(num_env)]
env.step(action)
stop = time.time()
duration = (stop - start)
if (duration):
fps = num_timesteps/duration
else:
fps=0
env.close()
return num_env, fps
if __name__ == "__main__":
env_id = "TestEnv"
res = []
for renderer in ('tiny','plugin', 'egl'):
for i in (1,8):
tmp = train(env_id,num_env=i,renderer=renderer)
print(renderer,tmp)
res.append((renderer,tmp))
print()
print("rendertest_sync.py")
print("back nenv fps fps_tot")
for renderer,i in res:
print(renderer,'\t', i[0],round(i[1]),'\t',round(i[0]*i[1]))

View File

@@ -105,7 +105,7 @@ class Pusher(MJCFBasedRobot):
self.shoulder_lift_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
self.upper_arm_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
self.elbow_flex_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
self.upper_arm_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
self.forearm_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
self.wrist_flex_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
self.wrist_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
@@ -115,7 +115,7 @@ class Pusher(MJCFBasedRobot):
self.shoulder_lift_joint.set_motor_torque(0.05 * float(np.clip(a[1], -1, +1)))
self.upper_arm_roll_joint.set_motor_torque(0.05 * float(np.clip(a[2], -1, +1)))
self.elbow_flex_joint.set_motor_torque(0.05 * float(np.clip(a[3], -1, +1)))
self.upper_arm_roll_joint.set_motor_torque(0.05 * float(np.clip(a[4], -1, +1)))
self.forearm_roll_joint.set_motor_torque(0.05 * float(np.clip(a[4], -1, +1)))
self.wrist_flex_joint.set_motor_torque(0.05 * float(np.clip(a[5], -1, +1)))
self.wrist_roll_joint.set_motor_torque(0.05 * float(np.clip(a[6], -1, +1)))
@@ -165,7 +165,7 @@ class Striker(MJCFBasedRobot):
self.shoulder_lift_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
self.upper_arm_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
self.elbow_flex_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
self.upper_arm_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
self.forearm_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
self.wrist_flex_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
self.wrist_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
@@ -205,7 +205,7 @@ class Striker(MJCFBasedRobot):
self.shoulder_lift_joint.set_motor_torque(0.05 * float(np.clip(a[1], -1, +1)))
self.upper_arm_roll_joint.set_motor_torque(0.05 * float(np.clip(a[2], -1, +1)))
self.elbow_flex_joint.set_motor_torque(0.05 * float(np.clip(a[3], -1, +1)))
self.upper_arm_roll_joint.set_motor_torque(0.05 * float(np.clip(a[4], -1, +1)))
self.forearm_roll_joint.set_motor_torque(0.05 * float(np.clip(a[4], -1, +1)))
self.wrist_flex_joint.set_motor_torque(0.05 * float(np.clip(a[5], -1, +1)))
self.wrist_roll_joint.set_motor_torque(0.05 * float(np.clip(a[6], -1, +1)))
@@ -254,7 +254,7 @@ class Thrower(MJCFBasedRobot):
self.shoulder_lift_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
self.upper_arm_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
self.elbow_flex_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
self.upper_arm_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
self.forearm_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
self.wrist_flex_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
self.wrist_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
@@ -294,7 +294,7 @@ class Thrower(MJCFBasedRobot):
self.shoulder_lift_joint.set_motor_torque(0.05 * float(np.clip(a[1], -1, +1)))
self.upper_arm_roll_joint.set_motor_torque(0.05 * float(np.clip(a[2], -1, +1)))
self.elbow_flex_joint.set_motor_torque(0.05 * float(np.clip(a[3], -1, +1)))
self.upper_arm_roll_joint.set_motor_torque(0.05 * float(np.clip(a[4], -1, +1)))
self.forearm_roll_joint.set_motor_torque(0.05 * float(np.clip(a[4], -1, +1)))
self.wrist_flex_joint.set_motor_torque(0.05 * float(np.clip(a[5], -1, +1)))
self.wrist_roll_joint.set_motor_torque(0.05 * float(np.clip(a[6], -1, +1)))