2019-04-27 14:31:15 +00:00
|
|
|
import os, inspect
|
2017-08-28 01:08:46 +00:00
|
|
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
|
|
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
2019-04-27 14:31:15 +00:00
|
|
|
os.sys.path.insert(0, parentdir)
|
2017-08-28 01:08:46 +00:00
|
|
|
|
2017-06-09 02:45:48 +00:00
|
|
|
import math
|
|
|
|
import gym
|
2018-12-28 13:30:05 +00:00
|
|
|
import time
|
2017-06-09 02:45:48 +00:00
|
|
|
from gym import spaces
|
|
|
|
from gym.utils import seeding
|
|
|
|
import numpy as np
|
2017-08-24 01:22:20 +00:00
|
|
|
import pybullet
|
2017-06-09 02:45:48 +00:00
|
|
|
from . import racecar
|
2017-06-10 02:26:07 +00:00
|
|
|
import random
|
2019-12-09 01:10:12 +00:00
|
|
|
import pybullet_utils.bullet_client as bc
|
2017-08-28 01:08:46 +00:00
|
|
|
import pybullet_data
|
2018-02-06 18:20:41 +00:00
|
|
|
from pkg_resources import parse_version
|
2017-06-09 02:45:48 +00:00
|
|
|
|
2017-11-02 01:06:47 +00:00
|
|
|
RENDER_HEIGHT = 720
|
|
|
|
RENDER_WIDTH = 960
|
|
|
|
|
2019-04-27 14:31:15 +00:00
|
|
|
|
2017-06-09 02:45:48 +00:00
|
|
|
class RacecarGymEnv(gym.Env):
|
2019-04-27 14:31:15 +00:00
|
|
|
metadata = {'render.modes': ['human', 'rgb_array'], 'video.frames_per_second': 50}
|
2017-06-09 02:45:48 +00:00
|
|
|
|
|
|
|
def __init__(self,
|
2017-08-28 01:08:46 +00:00
|
|
|
urdfRoot=pybullet_data.getDataPath(),
|
2017-06-11 01:46:36 +00:00
|
|
|
actionRepeat=50,
|
2017-06-09 02:45:48 +00:00
|
|
|
isEnableSelfCollision=True,
|
2017-08-24 06:12:26 +00:00
|
|
|
isDiscrete=False,
|
2017-08-24 01:22:20 +00:00
|
|
|
renders=False):
|
2017-06-09 02:45:48 +00:00
|
|
|
print("init")
|
|
|
|
self._timeStep = 0.01
|
|
|
|
self._urdfRoot = urdfRoot
|
|
|
|
self._actionRepeat = actionRepeat
|
|
|
|
self._isEnableSelfCollision = isEnableSelfCollision
|
|
|
|
self._observation = []
|
|
|
|
self._ballUniqueId = -1
|
|
|
|
self._envStepCounter = 0
|
2017-06-11 01:46:36 +00:00
|
|
|
self._renders = renders
|
2017-08-24 06:12:26 +00:00
|
|
|
self._isDiscrete = isDiscrete
|
2017-06-11 01:46:36 +00:00
|
|
|
if self._renders:
|
2019-12-09 01:10:12 +00:00
|
|
|
self._p = bc.BulletClient(connection_mode=pybullet.GUI)
|
2017-06-09 02:45:48 +00:00
|
|
|
else:
|
2019-12-09 01:10:12 +00:00
|
|
|
self._p = bc.BulletClient()
|
2017-08-24 01:22:20 +00:00
|
|
|
|
2018-12-28 13:30:05 +00:00
|
|
|
self.seed()
|
2017-08-24 01:22:20 +00:00
|
|
|
#self.reset()
|
2019-04-27 14:31:15 +00:00
|
|
|
observationDim = 2 #len(self.getExtendedObservation())
|
2017-06-10 02:26:07 +00:00
|
|
|
#print("observationDim")
|
2018-02-03 17:51:43 +00:00
|
|
|
#print(observationDim)
|
|
|
|
# observation_high = np.array([np.finfo(np.float32).max] * observationDim)
|
2019-04-27 14:31:15 +00:00
|
|
|
observation_high = np.ones(observationDim) * 1000 #np.inf
|
2017-08-24 06:12:26 +00:00
|
|
|
if (isDiscrete):
|
|
|
|
self.action_space = spaces.Discrete(9)
|
|
|
|
else:
|
2019-04-27 14:31:15 +00:00
|
|
|
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, dtype=np.float32)
|
2018-12-28 13:30:05 +00:00
|
|
|
self.observation_space = spaces.Box(-observation_high, observation_high, dtype=np.float32)
|
2017-06-09 02:45:48 +00:00
|
|
|
self.viewer = None
|
|
|
|
|
2018-12-28 13:30:05 +00:00
|
|
|
def reset(self):
|
2017-08-24 01:22:20 +00:00
|
|
|
self._p.resetSimulation()
|
2017-06-09 02:45:48 +00:00
|
|
|
#p.setPhysicsEngineParameter(numSolverIterations=300)
|
2017-08-24 01:22:20 +00:00
|
|
|
self._p.setTimeStep(self._timeStep)
|
2017-08-28 01:08:46 +00:00
|
|
|
#self._p.loadURDF(os.path.join(self._urdfRoot,"plane.urdf"))
|
2019-04-27 14:31:15 +00:00
|
|
|
stadiumobjects = self._p.loadSDF(os.path.join(self._urdfRoot, "stadium.sdf"))
|
2017-06-11 01:46:36 +00:00
|
|
|
#move the stadium objects slightly above 0
|
2017-08-24 06:12:26 +00:00
|
|
|
#for i in stadiumobjects:
|
|
|
|
# pos,orn = self._p.getBasePositionAndOrientation(i)
|
|
|
|
# newpos = [pos[0],pos[1],pos[2]-0.1]
|
|
|
|
# self._p.resetBasePositionAndOrientation(i,newpos,orn)
|
2018-02-03 17:51:43 +00:00
|
|
|
|
2019-04-27 14:31:15 +00:00
|
|
|
dist = 5 + 2. * random.random()
|
|
|
|
ang = 2. * 3.1415925438 * random.random()
|
2018-02-03 17:51:43 +00:00
|
|
|
|
2017-06-10 02:26:07 +00:00
|
|
|
ballx = dist * math.sin(ang)
|
|
|
|
bally = dist * math.cos(ang)
|
|
|
|
ballz = 1
|
2018-02-03 17:51:43 +00:00
|
|
|
|
2019-04-27 14:31:15 +00:00
|
|
|
self._ballUniqueId = self._p.loadURDF(os.path.join(self._urdfRoot, "sphere2.urdf"),
|
|
|
|
[ballx, bally, ballz])
|
|
|
|
self._p.setGravity(0, 0, -10)
|
|
|
|
self._racecar = racecar.Racecar(self._p, urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
|
2017-06-09 02:45:48 +00:00
|
|
|
self._envStepCounter = 0
|
|
|
|
for i in range(100):
|
2017-08-24 01:22:20 +00:00
|
|
|
self._p.stepSimulation()
|
2017-06-10 02:26:07 +00:00
|
|
|
self._observation = self.getExtendedObservation()
|
|
|
|
return np.array(self._observation)
|
2017-06-09 02:45:48 +00:00
|
|
|
|
|
|
|
def __del__(self):
|
2017-08-24 01:22:20 +00:00
|
|
|
self._p = 0
|
2017-06-09 02:45:48 +00:00
|
|
|
|
2018-12-28 13:30:05 +00:00
|
|
|
def seed(self, seed=None):
|
2017-06-09 02:45:48 +00:00
|
|
|
self.np_random, seed = seeding.np_random(seed)
|
|
|
|
return [seed]
|
|
|
|
|
2017-06-10 02:26:07 +00:00
|
|
|
def getExtendedObservation(self):
|
2019-04-27 14:31:15 +00:00
|
|
|
self._observation = [] #self._racecar.getObservation()
|
|
|
|
carpos, carorn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
|
|
|
|
ballpos, ballorn = self._p.getBasePositionAndOrientation(self._ballUniqueId)
|
|
|
|
invCarPos, invCarOrn = self._p.invertTransform(carpos, carorn)
|
|
|
|
ballPosInCar, ballOrnInCar = self._p.multiplyTransforms(invCarPos, invCarOrn, ballpos, ballorn)
|
2018-02-03 17:51:43 +00:00
|
|
|
|
2019-04-27 14:31:15 +00:00
|
|
|
self._observation.extend([ballPosInCar[0], ballPosInCar[1]])
|
|
|
|
return self._observation
|
2018-02-03 17:51:43 +00:00
|
|
|
|
2018-12-28 13:30:05 +00:00
|
|
|
def step(self, action):
|
2017-06-11 01:46:36 +00:00
|
|
|
if (self._renders):
|
2019-04-27 14:31:15 +00:00
|
|
|
basePos, orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
|
2017-08-24 01:22:20 +00:00
|
|
|
#self._p.resetDebugVisualizerCamera(1, 30, -40, basePos)
|
2018-02-03 17:51:43 +00:00
|
|
|
|
2017-08-24 06:12:26 +00:00
|
|
|
if (self._isDiscrete):
|
2019-04-27 14:31:15 +00:00
|
|
|
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]
|
2017-08-24 06:12:26 +00:00
|
|
|
else:
|
|
|
|
realaction = action
|
|
|
|
|
2017-06-10 02:26:07 +00:00
|
|
|
self._racecar.applyAction(realaction)
|
2017-06-09 02:45:48 +00:00
|
|
|
for i in range(self._actionRepeat):
|
2017-08-24 01:22:20 +00:00
|
|
|
self._p.stepSimulation()
|
2017-06-11 01:46:36 +00:00
|
|
|
if self._renders:
|
2017-06-09 02:45:48 +00:00
|
|
|
time.sleep(self._timeStep)
|
2017-06-10 02:26:07 +00:00
|
|
|
self._observation = self.getExtendedObservation()
|
2018-02-03 17:51:43 +00:00
|
|
|
|
2017-06-09 02:45:48 +00:00
|
|
|
if self._termination():
|
|
|
|
break
|
|
|
|
self._envStepCounter += 1
|
|
|
|
reward = self._reward()
|
|
|
|
done = self._termination()
|
2017-06-10 02:26:07 +00:00
|
|
|
#print("len=%r" % len(self._observation))
|
2018-02-03 17:51:43 +00:00
|
|
|
|
2017-06-09 02:45:48 +00:00
|
|
|
return np.array(self._observation), reward, done, {}
|
|
|
|
|
2018-12-28 13:30:05 +00:00
|
|
|
def render(self, mode='human', close=False):
|
2017-11-02 01:06:47 +00:00
|
|
|
if mode != "rgb_array":
|
|
|
|
return np.array([])
|
2019-04-27 14:31:15 +00:00
|
|
|
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)
|
2017-11-02 01:06:47 +00:00
|
|
|
rgb_array = np.array(px)
|
|
|
|
rgb_array = rgb_array[:, :, :3]
|
|
|
|
return rgb_array
|
2017-06-09 02:45:48 +00:00
|
|
|
|
|
|
|
def _termination(self):
|
2019-04-27 14:31:15 +00:00
|
|
|
return self._envStepCounter > 1000
|
2018-02-03 17:51:43 +00:00
|
|
|
|
2017-06-09 02:45:48 +00:00
|
|
|
def _reward(self):
|
2019-04-27 14:31:15 +00:00
|
|
|
closestPoints = self._p.getClosestPoints(self._racecar.racecarUniqueId, self._ballUniqueId,
|
|
|
|
10000)
|
2018-02-03 17:51:43 +00:00
|
|
|
|
2017-06-09 02:45:48 +00:00
|
|
|
numPt = len(closestPoints)
|
2019-04-27 14:31:15 +00:00
|
|
|
reward = -1000
|
2017-06-10 02:26:07 +00:00
|
|
|
#print(numPt)
|
2019-04-27 14:31:15 +00:00
|
|
|
if (numPt > 0):
|
2017-06-10 02:26:07 +00:00
|
|
|
#print("reward:")
|
|
|
|
reward = -closestPoints[0][8]
|
|
|
|
#print(reward)
|
2017-06-09 02:45:48 +00:00
|
|
|
return reward
|
2018-02-03 17:51:43 +00:00
|
|
|
|
2018-12-28 13:30:05 +00:00
|
|
|
if parse_version(gym.__version__) < parse_version('0.9.6'):
|
|
|
|
_render = render
|
|
|
|
_reset = reset
|
|
|
|
_seed = seed
|
|
|
|
_step = step
|