Improve PyBullet ports of Roboschool envs: fix reset (it kept adding stadium objects, causing slowdown), now reset uses saveState/restoreState and reset becomes a few orders of magnitude faster.

Use python -m pybullet_envs.examples.testEnv --env AntBulletEnv-v0 --render=1 --steps 1000 --resetbenchmark=1

Added environments: HumanoidFlagrunBulletEnv-v0, HumanoidFlagrunHarderBulletEnv-v0, StrikerBulletEnv-v0, ThrowerBulletEnv-v0, PusherBulletEnv-v0, ReacherBulletEnv-v0, CartPoleBulletEnv-v0 and register them to OpenAI Gym.
Allow numpy/humanoid_running.py to use abtch or non-batch update (setJointMotorControl2/setJointMotorControlArray)
This commit is contained in:
erwincoumans
2018-01-15 12:48:32 -08:00
parent 9ffb05eb3b
commit 851ca5bfb3
22 changed files with 2173 additions and 102 deletions

View File

@@ -3,16 +3,28 @@ from .env_bases import MJCFBaseBulletEnv
from robot_pendula import InvertedPendulum, InvertedPendulumSwingup, InvertedDoublePendulum
import gym, gym.spaces, gym.utils, gym.utils.seeding
import numpy as np
import pybullet as p
import os, sys
class InvertedPendulumBulletEnv(MJCFBaseBulletEnv):
def __init__(self):
self.robot = InvertedPendulum()
MJCFBaseBulletEnv.__init__(self, self.robot)
self.stateId=-1
def create_single_player_scene(self):
return SingleRobotEmptyScene(gravity=9.8, timestep=0.0165, frame_skip=1)
def _reset(self):
if (self.stateId>=0):
#print("InvertedPendulumBulletEnv reset p.restoreState(",self.stateId,")")
p.restoreState(self.stateId)
r = MJCFBaseBulletEnv._reset(self)
if (self.stateId<0):
self.stateId = p.saveState()
#print("InvertedPendulumBulletEnv reset self.stateId=",self.stateId)
return r
def _step(self, a):
self.robot.apply_action(a)
self.scene.global_step()
@@ -35,15 +47,24 @@ class InvertedPendulumSwingupBulletEnv(InvertedPendulumBulletEnv):
def __init__(self):
self.robot = InvertedPendulumSwingup()
MJCFBaseBulletEnv.__init__(self, self.robot)
self.stateId=-1
class InvertedDoublePendulumBulletEnv(MJCFBaseBulletEnv):
def __init__(self):
self.robot = InvertedDoublePendulum()
MJCFBaseBulletEnv.__init__(self, self.robot)
self.stateId = -1
def create_single_player_scene(self):
return SingleRobotEmptyScene(gravity=9.8, timestep=0.0165, frame_skip=1)
def _reset(self):
if (self.stateId>=0):
p.restoreState(self.stateId)
r = MJCFBaseBulletEnv._reset(self)
if (self.stateId<0):
self.stateId = p.saveState()
return r
def _step(self, a):
self.robot.apply_action(a)
self.scene.global_step()