From 577ddd4f5582224713faa9985ef6a6a04ebc71a0 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Wed, 23 Aug 2017 23:58:53 -0700 Subject: [PATCH 1/3] remote 'data' from MANIFEST.in --- MANIFEST.in | 1 - 1 file changed, 1 deletion(-) diff --git a/MANIFEST.in b/MANIFEST.in index 35db1b38e..0d31466ce 100644 --- a/MANIFEST.in +++ b/MANIFEST.in @@ -5,7 +5,6 @@ recursive-include Extras *.h recursive-include Extras *.hpp recursive-include src *.h recursive-include src *.hpp -recursive-include data *.* recursive-include examples/pybullet/gym *.* include examples/ThirdPartyLibs/enet/unix.c include examples/OpenGLWindow/X11OpenGLWindow.cpp From cb6914fa4ce0a3a0b0d9a35830341cf76ac45467 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Thu, 24 Aug 2017 13:33:45 -0700 Subject: [PATCH 2/3] use better defauls values for minitaur --- .../pybullet/gym/pybullet_envs/bullet/minitaur_gym_env.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/examples/pybullet/gym/pybullet_envs/bullet/minitaur_gym_env.py b/examples/pybullet/gym/pybullet_envs/bullet/minitaur_gym_env.py index 754287426..dcdcc5aa5 100644 --- a/examples/pybullet/gym/pybullet_envs/bullet/minitaur_gym_env.py +++ b/examples/pybullet/gym/pybullet_envs/bullet/minitaur_gym_env.py @@ -48,13 +48,13 @@ class MinitaurBulletEnv(gym.Env): observation_noise_stdev=0.0, self_collision_enabled=True, motor_velocity_limit=np.inf, - pd_control_enabled=False, + pd_control_enabled=False,#not needed to be true if accurate motor model is enabled (has its own better PD) leg_model_enabled=True, - accurate_motor_model_enabled=False, + accurate_motor_model_enabled=True, motor_kp=1.0, motor_kd=0.02, torque_control_enabled=False, - motor_overheat_protection=False, + motor_overheat_protection=True, hard_reset=True, on_rack=False, render=False, From 1fc148d5d03a80dc7c1ecd02e4bad48341541e45 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Thu, 24 Aug 2017 22:01:45 -0700 Subject: [PATCH 3/3] fixes in racecarGymEnv: implement 'render' rgb image, fix in naming, fix in observation bounds. --- examples/pybullet/gym/pybullet_envs/__init__.py | 2 +- .../gym/pybullet_envs/bullet/racecarGymEnv.py | 17 +++++++++++++++-- .../examples/enjoy_pybullet_racecar.py | 2 +- .../pybullet_envs/examples/racecarGymEnvTest.py | 2 +- 4 files changed, 18 insertions(+), 5 deletions(-) diff --git a/examples/pybullet/gym/pybullet_envs/__init__.py b/examples/pybullet/gym/pybullet_envs/__init__.py index 369fc0f87..f681b2d99 100644 --- a/examples/pybullet/gym/pybullet_envs/__init__.py +++ b/examples/pybullet/gym/pybullet_envs/__init__.py @@ -18,7 +18,7 @@ register( register( id='RacecarBulletEnv-v0', - entry_point='pybullet_envs.bullet:RacecarBulletEnv', + entry_point='pybullet_envs.bullet:RacecarGymEnv', timestep_limit=1000, reward_threshold=5.0, ) diff --git a/examples/pybullet/gym/pybullet_envs/bullet/racecarGymEnv.py b/examples/pybullet/gym/pybullet_envs/bullet/racecarGymEnv.py index 458d265bd..1d4074262 100644 --- a/examples/pybullet/gym/pybullet_envs/bullet/racecarGymEnv.py +++ b/examples/pybullet/gym/pybullet_envs/bullet/racecarGymEnv.py @@ -43,7 +43,8 @@ class RacecarGymEnv(gym.Env): observationDim = 2 #len(self.getExtendedObservation()) #print("observationDim") #print(observationDim) - observation_high = np.array([np.finfo(np.float32).max] * observationDim) + # observation_high = np.array([np.finfo(np.float32).max] * observationDim) + observation_high = np.ones(observationDim) * 1000 #np.inf if (isDiscrete): self.action_space = spaces.Discrete(9) else: @@ -130,7 +131,19 @@ class RacecarGymEnv(gym.Env): return np.array(self._observation), reward, done, {} def _render(self, mode='human', close=False): - return + width=320 + height=200 + img_arr = self._p.getCameraImage(width,height) + w=img_arr[0] + h=img_arr[1] + rgb=img_arr[2] + dep=img_arr[3] + #print 'width = %d height = %d' % (w,h) + # reshape creates np array + np_img_arr = np.reshape(rgb, (h, w, 4)) + # remove alpha channel + np_img_arr = np_img_arr[:, :, :3] + return np_img_arr def _termination(self): return self._envStepCounter>1000 diff --git a/examples/pybullet/gym/pybullet_envs/examples/enjoy_pybullet_racecar.py b/examples/pybullet/gym/pybullet_envs/examples/enjoy_pybullet_racecar.py index 717d82343..ce3e74358 100644 --- a/examples/pybullet/gym/pybullet_envs/examples/enjoy_pybullet_racecar.py +++ b/examples/pybullet/gym/pybullet_envs/examples/enjoy_pybullet_racecar.py @@ -12,7 +12,7 @@ from baselines import deepq def main(): - env = RacecarGymEnv(renders=False,isDiscrete=True) + env = RacecarGymEnv(renders=True,isDiscrete=True) act = deepq.load("racecar_model.pkl") print(act) while True: diff --git a/examples/pybullet/gym/pybullet_envs/examples/racecarGymEnvTest.py b/examples/pybullet/gym/pybullet_envs/examples/racecarGymEnvTest.py index a2ef5a855..fb439042d 100644 --- a/examples/pybullet/gym/pybullet_envs/examples/racecarGymEnvTest.py +++ b/examples/pybullet/gym/pybullet_envs/examples/racecarGymEnvTest.py @@ -5,7 +5,7 @@ parentdir = os.path.dirname(os.path.dirname(currentdir)) os.sys.path.insert(0,parentdir) from pybullet_envs.bullet.racecarGymEnv import RacecarGymEnv -isDiscrete = True +isDiscrete = False environment = RacecarGymEnv(renders=True, isDiscrete=isDiscrete) environment.reset()