Merge branch 'master' of https://github.com/erwincoumans/bullet3
This commit is contained in:
@@ -49,5 +49,8 @@ for i in range (p.getNumJoints(sphereUid)):
|
||||
p.getJointInfo(sphereUid,i)
|
||||
|
||||
while (1):
|
||||
keys = p.getKeyboardEvents()
|
||||
print(keys)
|
||||
|
||||
time.sleep(0.01)
|
||||
|
||||
@@ -4,7 +4,11 @@ import time
|
||||
useMaximalCoordinates = 0
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.loadSDF("stadium.sdf",useMaximalCoordinates=useMaximalCoordinates)
|
||||
#p.loadSDF("stadium.sdf",useMaximalCoordinates=useMaximalCoordinates)
|
||||
monastryId = concaveEnv =p.createCollisionShape(p.GEOM_MESH,fileName="samurai_monastry.obj",flags=p.GEOM_FORCE_CONCAVE_TRIMESH)
|
||||
orn = p.getQuaternionFromEuler([1.5707963,0,0])
|
||||
p.createMultiBody (0,monastryId, baseOrientation=orn)
|
||||
|
||||
sphereRadius = 0.05
|
||||
colSphereId = p.createCollisionShape(p.GEOM_SPHERE,radius=sphereRadius)
|
||||
colBoxId = p.createCollisionShape(p.GEOM_BOX,halfExtents=[sphereRadius,sphereRadius,sphereRadius])
|
||||
@@ -28,5 +32,7 @@ p.setGravity(0,0,-10)
|
||||
p.setRealTimeSimulation(1)
|
||||
|
||||
while (1):
|
||||
keys = p.getKeyboardEvents()
|
||||
#print(keys)
|
||||
time.sleep(0.01)
|
||||
|
||||
@@ -22,10 +22,14 @@ class CartPoleBulletEnv(gym.Env):
|
||||
'video.frames_per_second' : 50
|
||||
}
|
||||
|
||||
def __init__(self):
|
||||
def __init__(self, renders=True):
|
||||
# start the bullet physics server
|
||||
p.connect(p.GUI)
|
||||
#p.connect(p.DIRECT)
|
||||
self._renders = renders
|
||||
if (renders):
|
||||
p.connect(p.GUI)
|
||||
else:
|
||||
p.connect(p.DIRECT)
|
||||
|
||||
observation_high = np.array([
|
||||
np.finfo(np.float32).max,
|
||||
np.finfo(np.float32).max,
|
||||
@@ -33,7 +37,7 @@ class CartPoleBulletEnv(gym.Env):
|
||||
np.finfo(np.float32).max])
|
||||
action_high = np.array([0.1])
|
||||
|
||||
self.action_space = spaces.Discrete(5)
|
||||
self.action_space = spaces.Discrete(9)
|
||||
self.observation_space = spaces.Box(-observation_high, observation_high)
|
||||
|
||||
self.theta_threshold_radians = 1
|
||||
@@ -56,8 +60,8 @@ class CartPoleBulletEnv(gym.Env):
|
||||
self.state = p.getJointState(self.cartpole, 1)[0:2] + p.getJointState(self.cartpole, 0)[0:2]
|
||||
theta, theta_dot, x, x_dot = self.state
|
||||
|
||||
dv = 0.4
|
||||
deltav = [-2.*dv, -dv, 0, dv, 2.*dv][action]
|
||||
dv = 0.1
|
||||
deltav = [-10.*dv,-5.*dv, -2.*dv, -0.1*dv, 0, 0.1*dv, 2.*dv,5.*dv, 10.*dv][action]
|
||||
|
||||
p.setJointMotorControl2(self.cartpole, 0, p.VELOCITY_CONTROL, targetVelocity=(deltav + self.state[3]))
|
||||
|
||||
|
||||
@@ -12,7 +12,7 @@ def callback(lcl, glb):
|
||||
|
||||
def main():
|
||||
|
||||
env = gym.make('CartPoleBulletEnv-v0')
|
||||
env = CartPoleBulletEnv(renders=False)
|
||||
model = deepq.models.mlp([64])
|
||||
act = deepq.learn(
|
||||
env,
|
||||
|
||||
@@ -5008,7 +5008,7 @@ static PyObject* pybullet_createCollisionShape(PyObject* self, PyObject* args, P
|
||||
pybullet_internalSetVectord(planeNormalObj,planeNormal);
|
||||
shapeIndex = b3CreateCollisionShapeAddPlane(commandHandle, planeNormal, planeConstant);
|
||||
}
|
||||
if (shapeIndex && flags)
|
||||
if (shapeIndex>=0 && flags)
|
||||
{
|
||||
b3CreateCollisionSetFlag(commandHandle,shapeIndex,flags);
|
||||
}
|
||||
@@ -7275,6 +7275,8 @@ initpybullet(void)
|
||||
PyModule_AddIntConstant(m, "GEOM_PLANE", GEOM_PLANE);
|
||||
PyModule_AddIntConstant(m, "GEOM_CAPSULE", GEOM_CAPSULE);
|
||||
|
||||
PyModule_AddIntConstant(m, "GEOM_FORCE_CONCAVE_TRIMESH", GEOM_FORCE_CONCAVE_TRIMESH);
|
||||
|
||||
|
||||
|
||||
SpamError = PyErr_NewException("pybullet.error", NULL, NULL);
|
||||
|
||||
Reference in New Issue
Block a user