pybullet support for gym.Env, including v0.9.x
This commit is contained in:
@@ -46,8 +46,8 @@ class SimpleHumanoidGymEnv(gym.Env):
|
||||
observationDim = 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)
|
||||
self.action_space = spaces.Discrete(9)
|
||||
self.observation_space = spaces.Box(-observation_high, observation_high)
|
||||
self.viewer = None
|
||||
@@ -57,14 +57,14 @@ class SimpleHumanoidGymEnv(gym.Env):
|
||||
#p.setPhysicsEngineParameter(numSolverIterations=300)
|
||||
p.setTimeStep(self._timeStep)
|
||||
p.loadURDF(os.path.join(self._urdfRoot,"plane.urdf"))
|
||||
|
||||
|
||||
dist = 5 +2.*random.random()
|
||||
ang = 2.*3.1415925438*random.random()
|
||||
|
||||
|
||||
ballx = dist * math.sin(ang)
|
||||
bally = dist * math.cos(ang)
|
||||
ballz = 1
|
||||
|
||||
|
||||
p.setGravity(0,0,-10)
|
||||
self._humanoid = simpleHumanoid.SimpleHumanoid(urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
|
||||
self._envStepCounter = 0
|
||||
@@ -82,7 +82,7 @@ class SimpleHumanoidGymEnv(gym.Env):
|
||||
def getExtendedObservation(self):
|
||||
self._observation = self._humanoid.getObservation()
|
||||
return self._observation
|
||||
|
||||
|
||||
def _step(self, action):
|
||||
self._humanoid.applyAction(action)
|
||||
for i in range(self._actionRepeat):
|
||||
@@ -96,7 +96,7 @@ class SimpleHumanoidGymEnv(gym.Env):
|
||||
reward = self._reward()
|
||||
done = self._termination()
|
||||
#print("len=%r" % len(self._observation))
|
||||
|
||||
|
||||
return np.array(self._observation), reward, done, {}
|
||||
|
||||
def _render(self, mode='human', close=False):
|
||||
@@ -104,8 +104,13 @@ class SimpleHumanoidGymEnv(gym.Env):
|
||||
|
||||
def _termination(self):
|
||||
return self._envStepCounter>1000
|
||||
|
||||
|
||||
def _reward(self):
|
||||
reward=self._humanoid.distance
|
||||
print(reward)
|
||||
return reward
|
||||
|
||||
render = _render
|
||||
reset = _reset
|
||||
seed = _seed
|
||||
step = _step
|
||||
|
||||
Reference in New Issue
Block a user