enable continuous action space for racecarZEDGymEnv

disable SHARED_MEMORY connection (it was just some debug test)
This commit is contained in:
Erwin Coumans
2017-09-11 17:34:06 -07:00
parent b7e7415b46
commit 3891602784
5 changed files with 21 additions and 12 deletions

View File

@@ -8,7 +8,7 @@ class BulletClient(object):
def __init__(self, connection_mode=pybullet.DIRECT):
"""Create a simulation and connect to it."""
self._client = pybullet.connect(pybullet.SHARED_MEMORY)
self._client = -1 #pybullet.connect(pybullet.SHARED_MEMORY)
if(self._client<0):
self._client = pybullet.connect(connection_mode)
self._shapes = {}

View File

@@ -37,7 +37,7 @@ class KukaGymEnv(gym.Env):
self.terminated = 0
self._p = p
if self._renders:
cid = p.connect(p.SHARED_MEMORY)
cid = -1 #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])

View File

@@ -25,7 +25,7 @@ class RacecarZEDGymEnv(gym.Env):
urdfRoot=pybullet_data.getDataPath(),
actionRepeat=10,
isEnableSelfCollision=True,
isDiscrete=True,
isDiscrete=False,
renders=True):
print("init")
self._timeStep = 0.01
@@ -52,7 +52,13 @@ class RacecarZEDGymEnv(gym.Env):
#print(observationDim)
observation_high = np.array([np.finfo(np.float32).max] * observationDim)
self.action_space = spaces.Discrete(9)
if (isDiscrete):
self.action_space = spaces.Discrete(9)
else:
action_dim = 2
self._action_bound = 1
action_high = np.array([self._action_bound] * action_dim)
self.action_space = spaces.Box(-action_high, action_high)
self.observation_space = spaces.Box(low=0, high=255, shape=(self._height, self._width, 4))
self.viewer = None
@@ -119,11 +125,14 @@ class RacecarZEDGymEnv(gym.Env):
basePos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
#self._p.resetDebugVisualizerCamera(1, 30, -40, basePos)
fwd = [-1,-1,-1,0,0,0,1,1,1]
steerings = [-0.6,0,0.6,-0.6,0,0.6,-0.6,0,0.6]
forward = fwd[action]
steer = steerings[action]
realaction = [forward,steer]
if (self._isDiscrete):
fwd = [-1,-1,-1,0,0,0,1,1,1]
steerings = [-0.6,0,0.6,-0.6,0,0.6,-0.6,0,0.6]
forward = fwd[action]
steer = steerings[action]
realaction = [forward,steer]
else:
realaction = action
self._racecar.applyAction(realaction)
for i in range(self._actionRepeat):