This commit is contained in:
Erwin Coumans
2017-09-11 21:49:58 -07:00
12 changed files with 70 additions and 27 deletions

View File

@@ -1204,10 +1204,13 @@ void OpenGLExampleBrowser::updateGraphics()
void OpenGLExampleBrowser::update(float deltaTime)
{
if (!gEnableRenderLoop)
return;
b3ChromeUtilsEnableProfiling();
b3ChromeUtilsEnableProfiling();
if (!gEnableRenderLoop)
{
sCurrentDemo->updateGraphics();
return;
}
B3_PROFILE("OpenGLExampleBrowser::update");
assert(glGetError()==GL_NO_ERROR);

View File

@@ -91,7 +91,7 @@ void* PosixSharedMemory::allocateSharedMemory(int key, int size, bool allowCr
int id = shmget((key_t) key, (size_t) size,flags);
if (id < 0)
{
b3Error("shmget error");
b3Warning("shmget error");
} else
{
btPointerCaster result;

View File

@@ -74,4 +74,5 @@ for i in range (p.getNumJoints(r2d2)):
while(1):
a=0
a=0
p.stepSimulation()

View File

@@ -6,10 +6,10 @@ p.setPhysicsEngineParameter(numSolverIterations=5)
p.setPhysicsEngineParameter(fixedTimeStep=1./240.)
p.setPhysicsEngineParameter(numSubSteps=1)
p.loadURDF("plane.urdf")
objects = p.loadMJCF("mjcf/humanoid_symmetric.xml")
ob = objects[0]
p.resetBasePositionAndOrientation(ob,[0.000000,0.000000,0.000000],[0.000000,0.000000,0.000000,1.000000])
ob = objects[1]
p.resetBasePositionAndOrientation(ob,[0.789351,0.962124,0.113124],[0.710965,0.218117,0.519402,-0.420923])
jointPositions=[ -0.200226, 0.123925, 0.000000, -0.224016, 0.000000, -0.022247, 0.099119, -0.041829, 0.000000, -0.344372, 0.000000, 0.000000, 0.090687, -0.578698, 0.044461, 0.000000, -0.185004, 0.000000, 0.000000, 0.039517, -0.131217, 0.000000, 0.083382, 0.000000, -0.165303, -0.140802, 0.000000, -0.007374, 0.000000 ]
for jointIndex in range (p.getNumJoints(ob)):
@@ -24,9 +24,13 @@ p.setRealTimeSimulation(0)
#now do a benchmark
print("Starting benchmark")
logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS,"pybullet_humanoid_timings.json")
fileName = "pybullet_humanoid_timings.json"
logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS,fileName)
for i in range(1000):
p.stepSimulation()
p.stopStateLogging(logId)
print("ended benchmark")
print("ended benchmark")
print("Use Chrome browser, visit about://tracing, and load the %s file" % fileName)

View File

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

View File

@@ -37,7 +37,9 @@ class KukaGymEnv(gym.Env):
self.terminated = 0
self._p = p
if self._renders:
p.connect(p.GUI)
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])
else:
p.connect(p.DIRECT)

View File

@@ -166,6 +166,9 @@ class MinitaurBulletEnv(gym.Env):
def set_env_randomizer(self, env_randomizer):
self._env_randomizer = env_randomizer
def configure(self, args):
self._args = args
def _reset(self):
if self._hard_reset:
self._pybullet_client.resetSimulation()

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):

View File

@@ -39,13 +39,13 @@ class MJCFBaseBulletEnv(gym.Env):
def _reset(self):
if (self.physicsClientId<0):
if (self.isRender):
self.physicsClientId = p.connect(p.SHARED_MEMORY)
if (self.physicsClientId<0):
self.physicsClientId = -1 #p.connect(p.SHARED_MEMORY)
if (self.physicsClientId<0):
if (self.isRender):
self.physicsClientId = p.connect(p.GUI)
else:
self.physicsClientId = p.connect(p.DIRECT)
#p.configureDebugVisualizer(p.COV_ENABLE_GUI,0)
else:
self.physicsClientId = p.connect(p.DIRECT)
p.configureDebugVisualizer(p.COV_ENABLE_GUI,0)
if self.scene is None:
self.scene = self.create_single_player_scene()

View File

@@ -8,7 +8,7 @@ from pybullet_envs.bullet.racecarZEDGymEnv import RacecarZEDGymEnv
def main():
environment = RacecarZEDGymEnv(renders=True)
environment = RacecarZEDGymEnv(renders=True, isDiscrete=True)
targetVelocitySlider = environment._p.addUserDebugParameter("wheelVelocity",-1,1,0)
steeringSlider = environment._p.addUserDebugParameter("steering",-1,1,0)
@@ -37,4 +37,4 @@ def main():
print(obs)
if __name__=="__main__":
main()
main()

View File

@@ -0,0 +1,18 @@
#add parent dir to find package. Only needed for source code build, pip install doesn't need it.
import os
import inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(currentdir))
os.sys.path.insert(0,parentdir)
import pybullet_data
import pybullet as p
import time
p.connect(p.GUI_SERVER)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
while(1):
time.sleep(0.01)
p.getNumBodies()