Fix formating issues

This commit is contained in:
Antonin RAFFIN 2018-12-31 12:48:42 +01:00
parent 0df3527884
commit 1c61b629e3
3 changed files with 24 additions and 28 deletions

View File

@ -250,12 +250,12 @@ class HumanoidDeepMimicGymEnv(gym.Env):
def configure(self, args): def configure(self, args):
pass pass
if parse_version(gym.__version__)>=parse_version('0.9.6'): if parse_version(gym.__version__) < parse_version('0.9.6'):
close = _close _render = render
render = _render _reset = reset
reset = _reset _seed = seed
seed = _seed _step = step
step = _step _close = close
@property @property

View File

@ -47,7 +47,7 @@ class MJCFBaseBulletEnv(gym.Env):
self.ownsPhysicsClient = True self.ownsPhysicsClient = True
if self.isRender: if self.isRender:
self._p = bullet_client.BulletClient(connection_mode=pybullet.GUI) self._p = bullet_client.BulletClient(connection_mode=pybullet.GUI)
else: else:
self._p = bullet_client.BulletClient() self._p = bullet_client.BulletClient()
@ -69,7 +69,7 @@ class MJCFBaseBulletEnv(gym.Env):
self.potential = self.robot.calc_potential() self.potential = self.robot.calc_potential()
return s return s
def render(self, mode, close=False): def render(self, mode='human'):
if mode == "human": if mode == "human":
self.isRender = True self.isRender = True
if mode != "rgb_array": if mode != "rgb_array":

View File

@ -68,9 +68,9 @@ class PyBulletSimGymEnv(gym.Env):
self._cam_pitch = -35 self._cam_pitch = -35
self._hard_reset = True self._hard_reset = True
self._last_frame_time = 0.0 self._last_frame_time = 0.0
optionstring='--width={} --height={}'.format(render_width,render_height) optionstring='--width={} --height={}'.format(render_width,render_height)
print("urdf_root=" + self._urdf_root) print("urdf_root=" + self._urdf_root)
if self._is_render: if self._is_render:
@ -78,7 +78,7 @@ class PyBulletSimGymEnv(gym.Env):
connection_mode=pybullet.GUI, options=optionstring) connection_mode=pybullet.GUI, options=optionstring)
else: else:
self._pybullet_client = bullet_client.BulletClient() self._pybullet_client = bullet_client.BulletClient()
if (debug_visualization==False): if (debug_visualization==False):
self._pybullet_client.configureDebugVisualizer(flag=self._pybullet_client.COV_ENABLE_GUI,enable=0) self._pybullet_client.configureDebugVisualizer(flag=self._pybullet_client.COV_ENABLE_GUI,enable=0)
self._pybullet_client.configureDebugVisualizer(flag=self._pybullet_client.COV_ENABLE_RGB_BUFFER_PREVIEW,enable=0) self._pybullet_client.configureDebugVisualizer(flag=self._pybullet_client.COV_ENABLE_RGB_BUFFER_PREVIEW,enable=0)
@ -100,22 +100,22 @@ class PyBulletSimGymEnv(gym.Env):
action_high = np.array([self._action_bound] * action_dim) action_high = np.array([self._action_bound] * action_dim)
self.action_space = spaces.Box(-action_high, action_high) self.action_space = spaces.Box(-action_high, action_high)
self.observation_space = spaces.Box(observation_low, observation_high) self.observation_space = spaces.Box(observation_low, observation_high)
self.viewer = None self.viewer = None
self._hard_reset = hard_reset # This assignment need to be after reset() self._hard_reset = hard_reset # This assignment need to be after reset()
def configure(self, args): def configure(self, args):
self._args = args self._args = args
def reset(self): def reset(self):
if self._hard_reset: if self._hard_reset:
self._pybullet_client.resetSimulation() self._pybullet_client.resetSimulation()
self._pybullet_client.setPhysicsEngineParameter( self._pybullet_client.setPhysicsEngineParameter(
numSolverIterations=int(self._num_bullet_solver_iterations)) numSolverIterations=int(self._num_bullet_solver_iterations))
self._pybullet_client.setTimeStep(self._time_step) self._pybullet_client.setTimeStep(self._time_step)
self._example_sim = self._pybullet_sim_factory.CreateSim( self._example_sim = self._pybullet_sim_factory.CreateSim(
pybullet_client=self._pybullet_client, pybullet_client=self._pybullet_client,
urdf_root=self._urdf_root, urdf_root=self._urdf_root,
@ -124,7 +124,7 @@ class PyBulletSimGymEnv(gym.Env):
self._example_sim.Reset(reload_urdf=False) self._example_sim.Reset(reload_urdf=False)
self._env_step_counter = 0 self._env_step_counter = 0
#self._pybullet_client.resetDebugVisualizerCamera( #self._pybullet_client.resetDebugVisualizerCamera(
# self._cam_dist, self._cam_yaw, self._cam_pitch, [0, 0, 0]) # self._cam_dist, self._cam_yaw, self._cam_pitch, [0, 0, 0])
@ -158,12 +158,12 @@ class PyBulletSimGymEnv(gym.Env):
time_to_sleep = self._action_repeat * self._time_step - time_spent time_to_sleep = self._action_repeat * self._time_step - time_spent
if time_to_sleep > 0: if time_to_sleep > 0:
time.sleep(time_to_sleep) time.sleep(time_to_sleep)
#base_pos = self.minitaur.GetBasePosition() #base_pos = self.minitaur.GetBasePosition()
#self._pybullet_client.resetDebugVisualizerCamera( #self._pybullet_client.resetDebugVisualizerCamera(
# self._cam_dist, self._cam_yaw, self._cam_pitch, base_pos) # self._cam_dist, self._cam_yaw, self._cam_pitch, base_pos)
for _ in range(self._action_repeat): for _ in range(self._action_repeat):
self._example_sim.ApplyAction(action) self._example_sim.ApplyAction(action)
self._pybullet_client.stepSimulation() self._pybullet_client.stepSimulation()
@ -196,8 +196,6 @@ class PyBulletSimGymEnv(gym.Env):
rgb_array = rgb_array[:, :, :3] rgb_array = rgb_array[:, :, :3]
return rgb_array return rgb_array
def _termination(self): def _termination(self):
terminate=self._example_sim.Termination() terminate=self._example_sim.Termination()
return terminate return terminate
@ -206,14 +204,12 @@ class PyBulletSimGymEnv(gym.Env):
reward = 0 reward = 0
return reward return reward
def _get_observation(self): def _get_observation(self):
self._observation = self._example_sim.GetObservation() self._observation = self._example_sim.GetObservation()
return self._observation return self._observation
if parse_version(gym.__version__) < parse_version('0.9.6'):
if parse_version(gym.__version__)>=parse_version('0.9.6'): _render = render
render = _render _reset = reset
reset = _reset _seed = seed
seed = _seed _step = step
step = _step