fixes in kuka/racecar environment. kuka still doesn't train well, work-in-progress
This commit is contained in:
@@ -15,6 +15,9 @@ from . import racecar
|
||||
import random
|
||||
import pybullet_data
|
||||
|
||||
RENDER_HEIGHT = 720
|
||||
RENDER_WIDTH = 960
|
||||
|
||||
class RacecarZEDGymEnv(gym.Env):
|
||||
metadata = {
|
||||
'render.modes': ['human', 'rgb_array'],
|
||||
@@ -151,7 +154,26 @@ class RacecarZEDGymEnv(gym.Env):
|
||||
return np.array(self._observation), reward, done, {}
|
||||
|
||||
def _render(self, mode='human', close=False):
|
||||
return
|
||||
if mode != "rgb_array":
|
||||
return np.array([])
|
||||
base_pos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
|
||||
view_matrix = self._p.computeViewMatrixFromYawPitchRoll(
|
||||
cameraTargetPosition=base_pos,
|
||||
distance=self._cam_dist,
|
||||
yaw=self._cam_yaw,
|
||||
pitch=self._cam_pitch,
|
||||
roll=0,
|
||||
upAxisIndex=2)
|
||||
proj_matrix = self._p.computeProjectionMatrixFOV(
|
||||
fov=60, aspect=float(RENDER_WIDTH)/RENDER_HEIGHT,
|
||||
nearVal=0.1, farVal=100.0)
|
||||
(_, _, px, _, _) = self._p.getCameraImage(
|
||||
width=RENDER_WIDTH, height=RENDER_HEIGHT, viewMatrix=view_matrix,
|
||||
projectionMatrix=proj_matrix, renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
|
||||
rgb_array = np.array(px)
|
||||
rgb_array = rgb_array[:, :, :3]
|
||||
return rgb_array
|
||||
|
||||
|
||||
def _termination(self):
|
||||
return self._envStepCounter>1000
|
||||
|
||||
Reference in New Issue
Block a user