more fixes in pybullet_envs: fix path, add missing data resources

This commit is contained in:
Erwin Coumans
2017-08-22 08:59:39 -07:00
parent 21f9d1b816
commit e064d4b837
48 changed files with 28328 additions and 12 deletions

View File

@@ -5,7 +5,7 @@ from gym.utils import seeding
import numpy as np
import time
import pybullet as p
import minitaur_new
from . import minitaur_new
class MinitaurGymEnv(gym.Env):
metadata = {

View File

@@ -1,3 +1,4 @@
import os
import pybullet as p
import numpy as np
import copy
@@ -11,7 +12,7 @@ class Racecar:
self.reset()
def reset(self):
self.racecarUniqueId = p.loadURDF("racecar/racecar.urdf", [0,0,.2])
self.racecarUniqueId = p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","racecar/racecar.urdf"), [0,0,.2])
self.maxForce = 20
self.nMotors = 2
self.motorizedwheels=[2]
@@ -54,4 +55,4 @@ class Racecar:
p.setJointMotorControl2(self.racecarUniqueId,motor,p.VELOCITY_CONTROL,targetVelocity=targetVelocity,force=self.maxForce)
for steer in self.steeringLinks:
p.setJointMotorControl2(self.racecarUniqueId,steer,p.POSITION_CONTROL,targetPosition=steeringAngle)

View File

@@ -1,3 +1,4 @@
import os
import math
import gym
from gym import spaces
@@ -48,8 +49,8 @@ class RacecarGymEnv(gym.Env):
p.resetSimulation()
#p.setPhysicsEngineParameter(numSolverIterations=300)
p.setTimeStep(self._timeStep)
#p.loadURDF("%splane.urdf" % self._urdfRoot)
stadiumobjects = p.loadSDF("%sstadium.sdf" % self._urdfRoot)
#p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","plane.urdf"))
stadiumobjects = p.loadSDF(os.path.join(os.path.dirname(__file__),"../data","stadium.sdf"))
#move the stadium objects slightly above 0
for i in stadiumobjects:
pos,orn = p.getBasePositionAndOrientation(i)
@@ -63,7 +64,7 @@ class RacecarGymEnv(gym.Env):
bally = dist * math.cos(ang)
ballz = 1
self._ballUniqueId = p.loadURDF("sphere2.urdf",[ballx,bally,ballz])
self._ballUniqueId = p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","sphere2.urdf"),[ballx,bally,ballz])
p.setGravity(0,0,-10)
self._racecar = racecar.Racecar(urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
self._envStepCounter = 0

View File

@@ -1,3 +1,4 @@
import os
import math
import gym
from gym import spaces
@@ -50,8 +51,8 @@ class RacecarZEDGymEnv(gym.Env):
p.resetSimulation()
#p.setPhysicsEngineParameter(numSolverIterations=300)
p.setTimeStep(self._timeStep)
#p.loadURDF("%splane.urdf" % self._urdfRoot)
stadiumobjects = p.loadSDF("%sstadium.sdf" % self._urdfRoot)
#p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","plane.urdf"))
stadiumobjects = p.loadSDF(os.path.join(os.path.dirname(__file__),"../data","stadium.sdf"))
#move the stadium objects slightly above 0
for i in stadiumobjects:
pos,orn = p.getBasePositionAndOrientation(i)
@@ -65,7 +66,7 @@ class RacecarZEDGymEnv(gym.Env):
bally = dist * math.cos(ang)
ballz = 1
self._ballUniqueId = p.loadURDF("sphere2red.urdf",[ballx,bally,ballz])
self._ballUniqueId = p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","sphere2red.urdf"),[ballx,bally,ballz])
p.setGravity(0,0,-10)
self._racecar = racecar.Racecar(urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
self._envStepCounter = 0

View File

@@ -1,3 +1,4 @@
import os
import pybullet as p
import numpy as np
import copy
@@ -18,7 +19,7 @@ class SimpleHumanoid:
def reset(self):
self.initial_z = None
objs = p.loadMJCF("mjcf/humanoid_symmetric_no_ground.xml",flags = p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS)
objs = p.loadMJCF(os.path.join(os.path.dirname(__file__),"../data","mjcf/humanoid_symmetric_no_ground.xml"),flags = p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS)
self.human = objs[0]
self.jdict = {}
self.ordered_joints = []

View File

@@ -1,3 +1,4 @@
import os
import math
import gym
from gym import spaces
@@ -47,7 +48,7 @@ class SimpleHumanoidGymEnv(gym.Env):
p.resetSimulation()
#p.setPhysicsEngineParameter(numSolverIterations=300)
p.setTimeStep(self._timeStep)
p.loadURDF("%splane.urdf" % self._urdfRoot)
p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","plane.urdf"))
dist = 5 +2.*random.random()
ang = 2.*3.1415925438*random.random()
@@ -99,4 +100,4 @@ class SimpleHumanoidGymEnv(gym.Env):
def _reward(self):
reward=self._humanoid.distance
print(reward)
return reward
return reward