Merge branch 'master' into bullet-gym
This commit is contained in:
43
examples/pybullet/examples/changeTexture.py
Normal file
43
examples/pybullet/examples/changeTexture.py
Normal file
@@ -0,0 +1,43 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
p.connect(p.GUI)
|
||||
planeUidA = p.loadURDF("plane_transparent.urdf",[0,0,0])
|
||||
planeUid = p.loadURDF("plane_transparent.urdf",[0,0,-1])
|
||||
|
||||
texUid = p.loadTexture("tex256.png")
|
||||
|
||||
p.changeVisualShape(planeUidA,-1,rgbaColor=[1,1,1,0.5])
|
||||
p.changeVisualShape(planeUid,-1,rgbaColor=[1,1,1,0.5])
|
||||
p.changeVisualShape(planeUid,-1, textureUniqueId = texUid)
|
||||
|
||||
width = 256
|
||||
height = 256
|
||||
pixels = [255]*width*height*3
|
||||
colorR = 0
|
||||
colorG = 0
|
||||
colorB = 0
|
||||
|
||||
|
||||
#p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||
#p.configureDebugVisualizer(p.COV_ENABLE_GUI,0)
|
||||
|
||||
blue=0
|
||||
logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "renderbench.json")
|
||||
for i in range (100000):
|
||||
p.stepSimulation()
|
||||
for i in range (width):
|
||||
for j in range(height):
|
||||
pixels[(i+j*width)*3+0]=i
|
||||
pixels[(i+j*width)*3+1]=(j+blue)%256
|
||||
pixels[(i+j*width)*3+2]=blue
|
||||
blue=blue+1
|
||||
p.changeTexture(texUid, pixels,width,height)
|
||||
start = time.time()
|
||||
p.getCameraImage(300,300,renderer=p.ER_BULLET_HARDWARE_OPENGL)
|
||||
end = time.time()
|
||||
print("rendering duraction")
|
||||
print(end-start)
|
||||
p.stopStateLogging(logId)
|
||||
#p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||
#p.configureDebugVisualizer(p.COV_ENABLE_GUI,1)
|
||||
|
||||
@@ -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)
|
||||
|
||||
93
examples/pybullet/examples/createObstacleCourse.py
Normal file
93
examples/pybullet/examples/createObstacleCourse.py
Normal file
@@ -0,0 +1,93 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import math
|
||||
|
||||
p.connect(p.GUI)
|
||||
#don't create a ground plane, to allow for gaps etc
|
||||
p.resetSimulation()
|
||||
#p.createCollisionShape(p.GEOM_PLANE)
|
||||
#p.createMultiBody(0,0)
|
||||
#p.resetDebugVisualizerCamera(5,75,-26,[0,0,1]);
|
||||
p.resetDebugVisualizerCamera(15,-346,-16,[-15,0,1]);
|
||||
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||
|
||||
sphereRadius = 0.05
|
||||
colSphereId = p.createCollisionShape(p.GEOM_SPHERE,radius=sphereRadius)
|
||||
stoneId = p.createCollisionShape(p.GEOM_MESH,fileName="stone.obj")
|
||||
|
||||
boxHalfLength = 0.5
|
||||
boxHalfWidth = 2.5
|
||||
boxHalfHeight = 0.1
|
||||
segmentLength = 5
|
||||
|
||||
colBoxId = p.createCollisionShape(p.GEOM_BOX,halfExtents=[boxHalfLength,boxHalfWidth,boxHalfHeight])
|
||||
|
||||
mass = 1
|
||||
visualShapeId = -1
|
||||
|
||||
segmentStart = 0
|
||||
|
||||
for i in range (segmentLength):
|
||||
p.createMultiBody(baseMass=0,baseCollisionShapeIndex = colBoxId,basePosition = [segmentStart,0,-0.1])
|
||||
segmentStart=segmentStart-1
|
||||
|
||||
for i in range (segmentLength):
|
||||
height = 0
|
||||
if (i%2):
|
||||
height=1
|
||||
p.createMultiBody(baseMass=0,baseCollisionShapeIndex = colBoxId,basePosition = [segmentStart,0,-0.1+height])
|
||||
segmentStart=segmentStart-1
|
||||
|
||||
baseOrientation = p.getQuaternionFromEuler([math.pi/2.,0,math.pi/2.])
|
||||
|
||||
for i in range (segmentLength):
|
||||
p.createMultiBody(baseMass=0,baseCollisionShapeIndex = colBoxId,basePosition = [segmentStart,0,-0.1])
|
||||
segmentStart=segmentStart-1
|
||||
if (i%2):
|
||||
p.createMultiBody(baseMass=0,baseCollisionShapeIndex = colBoxId,basePosition = [segmentStart,i%3,-0.1+height+boxHalfWidth],baseOrientation=baseOrientation)
|
||||
|
||||
for i in range (segmentLength):
|
||||
p.createMultiBody(baseMass=0,baseCollisionShapeIndex = colBoxId,basePosition = [segmentStart,0,-0.1])
|
||||
width=4
|
||||
for j in range (width):
|
||||
p.createMultiBody(baseMass=0,baseCollisionShapeIndex = stoneId,basePosition = [segmentStart,0.5*(i%2)+j-width/2.,0])
|
||||
segmentStart=segmentStart-1
|
||||
|
||||
|
||||
link_Masses=[1]
|
||||
linkCollisionShapeIndices=[colBoxId]
|
||||
linkVisualShapeIndices=[-1]
|
||||
linkPositions=[[0,0,0]]
|
||||
linkOrientations=[[0,0,0,1]]
|
||||
linkInertialFramePositions=[[0,0,0]]
|
||||
linkInertialFrameOrientations=[[0,0,0,1]]
|
||||
indices=[0]
|
||||
jointTypes=[p.JOINT_REVOLUTE]
|
||||
axis=[[1,0,0]]
|
||||
|
||||
baseOrientation = [0,0,0,1]
|
||||
for i in range (segmentLength):
|
||||
boxId = p.createMultiBody(0,colSphereId,-1,[segmentStart,0,-0.1],baseOrientation,linkMasses=link_Masses,linkCollisionShapeIndices=linkCollisionShapeIndices,linkVisualShapeIndices=linkVisualShapeIndices,linkPositions=linkPositions,linkOrientations=linkOrientations,linkInertialFramePositions=linkInertialFramePositions, linkInertialFrameOrientations=linkInertialFrameOrientations,linkParentIndices=indices,linkJointTypes=jointTypes,linkJointAxis=axis)
|
||||
p.changeDynamics(boxId,-1,spinningFriction=0.001, rollingFriction=0.001,linearDamping=0.0)
|
||||
print(p.getNumJoints(boxId))
|
||||
for joint in range (p.getNumJoints(boxId)):
|
||||
targetVelocity = 1
|
||||
if (i%2):
|
||||
targetVelocity =-1
|
||||
p.setJointMotorControl2(boxId,joint,p.VELOCITY_CONTROL,targetVelocity=targetVelocity,force=10)
|
||||
segmentStart=segmentStart-1.1
|
||||
|
||||
|
||||
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||
while (1):
|
||||
camData = p.getDebugVisualizerCamera()
|
||||
viewMat = camData[2]
|
||||
projMat = camData[3]
|
||||
p.getCameraImage(256,256,viewMatrix=viewMat, projectionMatrix=projMat, renderer=p.ER_BULLET_HARDWARE_OPENGL)
|
||||
keys = p.getKeyboardEvents()
|
||||
p.stepSimulation()
|
||||
#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)
|
||||
|
||||
28
examples/pybullet/examples/loadingBench.py
Normal file
28
examples/pybullet/examples/loadingBench.py
Normal file
@@ -0,0 +1,28 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
p.connect(p.GUI)
|
||||
|
||||
p.resetSimulation()
|
||||
timinglog = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "loadingBenchVR.json")
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||
print("load plane.urdf")
|
||||
p.loadURDF("plane.urdf")
|
||||
print("load r2d2.urdf")
|
||||
|
||||
p.loadURDF("r2d2.urdf",0,0,1)
|
||||
print("load kitchen/1.sdf")
|
||||
p.loadSDF("kitchens/1.sdf")
|
||||
print("load 100 times plate.urdf")
|
||||
for i in range (100):
|
||||
p.loadURDF("dinnerware/plate.urdf",0,i,1)
|
||||
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||
|
||||
p.stopStateLogging(timinglog)
|
||||
print("stopped state logging")
|
||||
p.getCameraImage(320,200)
|
||||
|
||||
while (1):
|
||||
p.stepSimulation()
|
||||
|
||||
|
||||
@@ -7,16 +7,15 @@ if (cid<0):
|
||||
|
||||
p.resetSimulation()
|
||||
p.setGravity(0,0,-10)
|
||||
p.setPhysicsEngineParameter(numSolverIterations=1000)
|
||||
useRealTimeSim = 1
|
||||
|
||||
#for video recording (works best on Mac and Linux, not well on Windows)
|
||||
#p.startStateLogging(p.STATE_LOGGING_VIDEO_MP4, "racecar.mp4")
|
||||
p.setRealTimeSimulation(useRealTimeSim) # either this
|
||||
#p.loadURDF("plane.urdf")
|
||||
p.loadSDF("stadium.sdf")
|
||||
p.loadURDF("plane.urdf")
|
||||
#p.loadSDF("stadium.sdf")
|
||||
|
||||
car = p.loadURDF("racecar/racecar_differential.urdf")#, [0,0,2],useFixedBase=True)
|
||||
car = p.loadURDF("racecar/racecar_differential.urdf") #, [0,0,2],useFixedBase=True)
|
||||
for i in range (p.getNumJoints(car)):
|
||||
print (p.getJointInfo(car,i))
|
||||
for wheel in range(p.getNumJoints(car)):
|
||||
@@ -27,7 +26,6 @@ wheels = [8,15]
|
||||
print("----------------")
|
||||
|
||||
#p.setJointMotorControl2(car,10,p.VELOCITY_CONTROL,targetVelocity=1,force=10)
|
||||
|
||||
c = p.createConstraint(car,9,car,11,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=1, maxForce=10000)
|
||||
|
||||
@@ -40,12 +38,17 @@ p.changeConstraint(c,gearRatio=-1, maxForce=10000)
|
||||
c = p.createConstraint(car,16,car,18,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=1, maxForce=10000)
|
||||
|
||||
c = p.createConstraint(car,17,car,19,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=-1, maxForce=10000)
|
||||
|
||||
c = p.createConstraint(car,16,car,19,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=-1, maxForce=10000)
|
||||
|
||||
c = p.createConstraint(car,17,car,19,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=-1, maxForce=10000)
|
||||
|
||||
c = p.createConstraint(car,1,car,18,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=-1, gearAuxLink = 15, maxForce=10000)
|
||||
c = p.createConstraint(car,3,car,19,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=-1, gearAuxLink = 15,maxForce=10000)
|
||||
|
||||
|
||||
steering = [0,2]
|
||||
|
||||
18
examples/pybullet/examples/transparent.py
Normal file
18
examples/pybullet/examples/transparent.py
Normal file
@@ -0,0 +1,18 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
p.connect(p.GUI)
|
||||
p.loadURDF("plane.urdf")
|
||||
sphereUid = p.loadURDF("sphere_transparent.urdf",[0,0,2])
|
||||
|
||||
redSlider = p.addUserDebugParameter("red",0,1,1)
|
||||
greenSlider = p.addUserDebugParameter("green",0,1,0)
|
||||
blueSlider = p.addUserDebugParameter("blue",0,1,0)
|
||||
alphaSlider = p.addUserDebugParameter("alpha",0,1,0.5)
|
||||
|
||||
while (1):
|
||||
red = p.readUserDebugParameter(redSlider)
|
||||
green = p.readUserDebugParameter(greenSlider)
|
||||
blue = p.readUserDebugParameter(blueSlider)
|
||||
alpha = p.readUserDebugParameter(alphaSlider)
|
||||
p.changeVisualShape(sphereUid,-1,rgbaColor=[red,green,blue,alpha])
|
||||
time.sleep(0.01)
|
||||
93
examples/pybullet/examples/vr_racecar_differential.py
Normal file
93
examples/pybullet/examples/vr_racecar_differential.py
Normal file
@@ -0,0 +1,93 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
CONTROLLER_ID = 0
|
||||
POSITION=1
|
||||
ORIENTATION=2
|
||||
BUTTONS=6
|
||||
|
||||
|
||||
cid = p.connect(p.SHARED_MEMORY)
|
||||
if (cid<0):
|
||||
p.connect(p.GUI)
|
||||
|
||||
p.resetSimulation()
|
||||
p.setGravity(0,0,-10)
|
||||
useRealTimeSim = 1
|
||||
|
||||
#for video recording (works best on Mac and Linux, not well on Windows)
|
||||
#p.startStateLogging(p.STATE_LOGGING_VIDEO_MP4, "racecar.mp4")
|
||||
p.setRealTimeSimulation(useRealTimeSim) # either this
|
||||
p.loadURDF("plane.urdf")
|
||||
#p.loadSDF("stadium.sdf")
|
||||
|
||||
car = p.loadURDF("racecar/racecar_differential.urdf") #, [0,0,2],useFixedBase=True)
|
||||
for i in range (p.getNumJoints(car)):
|
||||
print (p.getJointInfo(car,i))
|
||||
for wheel in range(p.getNumJoints(car)):
|
||||
p.setJointMotorControl2(car,wheel,p.VELOCITY_CONTROL,targetVelocity=0,force=0)
|
||||
p.getJointInfo(car,wheel)
|
||||
|
||||
wheels = [8,15]
|
||||
print("----------------")
|
||||
|
||||
#p.setJointMotorControl2(car,10,p.VELOCITY_CONTROL,targetVelocity=1,force=10)
|
||||
c = p.createConstraint(car,9,car,11,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=1, maxForce=10000)
|
||||
|
||||
c = p.createConstraint(car,10,car,13,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=-1, maxForce=10000)
|
||||
|
||||
c = p.createConstraint(car,9,car,13,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=-1, maxForce=10000)
|
||||
|
||||
c = p.createConstraint(car,16,car,18,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=1, maxForce=10000)
|
||||
|
||||
|
||||
c = p.createConstraint(car,16,car,19,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=-1, maxForce=10000)
|
||||
|
||||
c = p.createConstraint(car,17,car,19,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=-1, maxForce=10000)
|
||||
|
||||
c = p.createConstraint(car,1,car,18,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=-1, gearAuxLink = 15, maxForce=10000)
|
||||
c = p.createConstraint(car,3,car,19,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=-1, gearAuxLink = 15,maxForce=10000)
|
||||
|
||||
|
||||
steering = [0,2]
|
||||
|
||||
targetVelocitySlider = p.addUserDebugParameter("wheelVelocity",-50,50,0)
|
||||
maxForceSlider = p.addUserDebugParameter("maxForce",0,50,20)
|
||||
steeringSlider = p.addUserDebugParameter("steering",-1,1,0)
|
||||
activeController = -1
|
||||
|
||||
while (True):
|
||||
|
||||
|
||||
maxForce = p.readUserDebugParameter(maxForceSlider)
|
||||
targetVelocity = p.readUserDebugParameter(targetVelocitySlider)
|
||||
steeringAngle = p.readUserDebugParameter(steeringSlider)
|
||||
#print(targetVelocity)
|
||||
events = p.getVREvents()
|
||||
for e in events:
|
||||
if (e[BUTTONS][33]&p.VR_BUTTON_WAS_TRIGGERED):
|
||||
activeController = e[CONTROLLER_ID]
|
||||
if (activeController == e[CONTROLLER_ID]):
|
||||
orn = e[2]
|
||||
eul = p.getEulerFromQuaternion(orn)
|
||||
steeringAngle=eul[0]
|
||||
|
||||
targetVelocity = 20.0*e[3]
|
||||
|
||||
for wheel in wheels:
|
||||
p.setJointMotorControl2(car,wheel,p.VELOCITY_CONTROL,targetVelocity=targetVelocity,force=maxForce)
|
||||
|
||||
for steer in steering:
|
||||
p.setJointMotorControl2(car,steer,p.POSITION_CONTROL,targetPosition=-steeringAngle)
|
||||
|
||||
steering
|
||||
if (useRealTimeSim==0):
|
||||
p.stepSimulation()
|
||||
time.sleep(0.01)
|
||||
21
examples/pybullet/examples/widows.py
Normal file
21
examples/pybullet/examples/widows.py
Normal file
@@ -0,0 +1,21 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.loadURDF("table/table.urdf", 0.5000000,0.00000,-.820000,0.000000,0.000000,0.0,1.0)
|
||||
p.setGravity(0,0,-10)
|
||||
arm = p.loadURDF("widowx/widowx.urdf",useFixedBase=True)
|
||||
|
||||
p.resetBasePositionAndOrientation(arm,[-0.098612,-0.000726,-0.194018],[0.000000,0.000000,0.000000,1.000000])
|
||||
|
||||
|
||||
while (1):
|
||||
p.stepSimulation()
|
||||
time.sleep(0.01)
|
||||
#p.saveWorld("test.py")
|
||||
viewMat = p.getDebugVisualizerCamera()[2]
|
||||
#projMatrix = [0.7499999403953552, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, -1.0000200271606445, -1.0, 0.0, 0.0, -0.02000020071864128, 0.0]
|
||||
projMatrix = p.getDebugVisualizerCamera()[3]
|
||||
width=640
|
||||
height=480
|
||||
img_arr = p.getCameraImage(width=width,height=height,viewMatrix=viewMat,projectionMatrix=projMatrix)
|
||||
@@ -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,
|
||||
|
||||
@@ -1433,7 +1433,7 @@ static PyObject* pybullet_setJointMotorControlArray(PyObject* self, PyObject* ar
|
||||
int i;
|
||||
for (i = 0; i < numControlledDofs; i++)
|
||||
{
|
||||
int jointIndex = pybullet_internalGetFloatFromSequence(jointIndicesSeq, i);
|
||||
int jointIndex = pybullet_internalGetIntFromSequence(jointIndicesSeq, i);
|
||||
if ((jointIndex >= numJoints) || (jointIndex < 0))
|
||||
{
|
||||
Py_DECREF(jointIndicesSeq);
|
||||
@@ -4551,6 +4551,75 @@ static PyObject* pybullet_changeVisualShape(PyObject* self, PyObject* args, PyOb
|
||||
return Py_None;
|
||||
}
|
||||
|
||||
|
||||
static PyObject* pybullet_changeTexture(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
b3SharedMemoryCommandHandle commandHandle = 0;
|
||||
b3SharedMemoryStatusHandle statusHandle=0;
|
||||
int statusType = -1;
|
||||
int textureUniqueId = -1;
|
||||
int physicsClientId = 0;
|
||||
int width=-1;
|
||||
int height=-1;
|
||||
|
||||
PyObject* pixelsObj = 0;
|
||||
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
static char* kwlist[] = {"textureUniqueId", "pixels", "width", "height", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iOii|i", kwlist, &textureUniqueId, &pixelsObj, &width, &height, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
sm = getPhysicsClient(physicsClientId);
|
||||
if (sm == 0)
|
||||
{
|
||||
PyErr_SetString(SpamError, "Not connected to physics server.");
|
||||
return NULL;
|
||||
}
|
||||
|
||||
if (textureUniqueId>=0 && width>=0 && height>=0 && pixelsObj)
|
||||
{
|
||||
PyObject* seqPixels = PySequence_Fast(pixelsObj, "expected a sequence");
|
||||
PyObject* item;
|
||||
int i;
|
||||
int numPixels = width*height;
|
||||
unsigned char* pixelBuffer = (unsigned char*) malloc (numPixels*3);
|
||||
if (PyList_Check(seqPixels))
|
||||
{
|
||||
for (i=0;i<numPixels*3;i++)
|
||||
{
|
||||
item = PyList_GET_ITEM(seqPixels, i);
|
||||
pixelBuffer[i] = PyLong_AsLong(item);
|
||||
}
|
||||
} else
|
||||
{
|
||||
for (i=0;i<numPixels*3;i++)
|
||||
{
|
||||
item = PyTuple_GET_ITEM(seqPixels, i);
|
||||
pixelBuffer[i] = PyLong_AsLong(item);
|
||||
}
|
||||
}
|
||||
|
||||
commandHandle = b3CreateChangeTextureCommandInit(sm,textureUniqueId, width,height,(const char*) pixelBuffer);
|
||||
free(pixelBuffer);
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
if (statusType == CMD_CLIENT_COMMAND_COMPLETED)
|
||||
{
|
||||
Py_INCREF(Py_None);
|
||||
return Py_None;
|
||||
} else
|
||||
{
|
||||
PyErr_SetString(SpamError, "Error processing changeTexture.");
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
|
||||
PyErr_SetString(SpamError, "Error: invalid arguments in changeTexture.");
|
||||
return NULL;
|
||||
}
|
||||
|
||||
|
||||
static PyObject* pybullet_loadTexture(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
const char* filename = 0;
|
||||
@@ -4578,16 +4647,14 @@ static PyObject* pybullet_loadTexture(PyObject* self, PyObject* args, PyObject*
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
if (statusType == CMD_LOAD_TEXTURE_COMPLETED)
|
||||
{
|
||||
}
|
||||
else
|
||||
{
|
||||
PyErr_SetString(SpamError, "Error loading texture");
|
||||
return NULL;
|
||||
PyObject* item;
|
||||
item = PyInt_FromLong(b3GetStatusTextureUniqueId(statusHandle));
|
||||
return item;
|
||||
}
|
||||
}
|
||||
|
||||
Py_INCREF(Py_None);
|
||||
return Py_None;
|
||||
PyErr_SetString(SpamError, "Error loading texture");
|
||||
return NULL;
|
||||
}
|
||||
|
||||
static PyObject* MyConvertContactPoint(struct b3ContactInformation* contactPointPtr)
|
||||
@@ -4804,11 +4871,12 @@ static PyObject* pybullet_getClosestPointData(PyObject* self, PyObject* args, Py
|
||||
|
||||
static PyObject* pybullet_changeUserConstraint(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
static char* kwlist[] = {"userConstraintUniqueId", "jointChildPivot", "jointChildFrameOrientation", "maxForce", "gearRatio", "physicsClientId", NULL};
|
||||
static char* kwlist[] = {"userConstraintUniqueId", "jointChildPivot", "jointChildFrameOrientation", "maxForce", "gearRatio", "gearAuxLink", "physicsClientId", NULL};
|
||||
int userConstraintUniqueId = -1;
|
||||
b3SharedMemoryCommandHandle commandHandle;
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
int gearAuxLink = -1;
|
||||
int physicsClientId = 0;
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
PyObject* jointChildPivotObj = 0;
|
||||
@@ -4817,7 +4885,7 @@ static PyObject* pybullet_changeUserConstraint(PyObject* self, PyObject* args, P
|
||||
double jointChildFrameOrn[4];
|
||||
double maxForce = -1;
|
||||
double gearRatio = 0;
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|OOddi", kwlist, &userConstraintUniqueId, &jointChildPivotObj, &jointChildFrameOrnObj, &maxForce, &gearRatio, &physicsClientId))
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|OOddii", kwlist, &userConstraintUniqueId, &jointChildPivotObj, &jointChildFrameOrnObj, &maxForce, &gearRatio, &gearAuxLink, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -4847,6 +4915,10 @@ static PyObject* pybullet_changeUserConstraint(PyObject* self, PyObject* args, P
|
||||
{
|
||||
b3InitChangeUserConstraintSetGearRatio(commandHandle,gearRatio);
|
||||
}
|
||||
if (gearAuxLink>=0)
|
||||
{
|
||||
b3InitChangeUserConstraintSetGearAuxLink(commandHandle,gearAuxLink);
|
||||
}
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
Py_INCREF(Py_None);
|
||||
@@ -5008,7 +5080,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);
|
||||
}
|
||||
@@ -5180,14 +5252,16 @@ static PyObject* pybullet_createMultiBody(PyObject* self, PyObject* args, PyObje
|
||||
double linkJointAxis[3];
|
||||
double linkInertialFramePosition[3];
|
||||
double linkInertialFrameOrientation[4];
|
||||
|
||||
int linkParentIndex;
|
||||
int linkJointType;
|
||||
|
||||
pybullet_internalGetVector3FromSequence(seqLinkInertialFramePositions,i,linkInertialFramePosition);
|
||||
pybullet_internalGetVector4FromSequence(linkInertialFrameOrientationObj,i,linkInertialFrameOrientation);
|
||||
pybullet_internalGetVector3FromSequence(seqLinkPositions,i,linkPosition);
|
||||
pybullet_internalGetVector4FromSequence(seqLinkOrientations,i,linkOrientation);
|
||||
pybullet_internalGetVector3FromSequence(seqLinkJoinAxis,i,linkJointAxis);
|
||||
int linkParentIndex = pybullet_internalGetIntFromSequence(seqLinkParentIndices,i);
|
||||
int linkJointType = pybullet_internalGetIntFromSequence(seqLinkJointTypes,i);
|
||||
linkParentIndex = pybullet_internalGetIntFromSequence(seqLinkParentIndices,i);
|
||||
linkJointType = pybullet_internalGetIntFromSequence(seqLinkJointTypes,i);
|
||||
|
||||
b3CreateMultiBodyLink(commandHandle,
|
||||
linkMass,
|
||||
@@ -7019,6 +7093,9 @@ static PyMethodDef SpamMethods[] = {
|
||||
{"loadTexture", (PyCFunction)pybullet_loadTexture, METH_VARARGS | METH_KEYWORDS,
|
||||
"Load texture file."},
|
||||
|
||||
{"changeTexture", (PyCFunction)pybullet_changeTexture, METH_VARARGS | METH_KEYWORDS,
|
||||
"Change a texture file."},
|
||||
|
||||
{"getQuaternionFromEuler", pybullet_getQuaternionFromEuler, METH_VARARGS,
|
||||
"Convert Euler [roll, pitch, yaw] as in URDF/SDF convention, to "
|
||||
"quaternion [x,y,z,w]"},
|
||||
@@ -7147,14 +7224,22 @@ PyMODINIT_FUNC
|
||||
#if PY_MAJOR_VERSION >= 3
|
||||
PyInit_pybullet(void)
|
||||
#else
|
||||
#ifdef BT_USE_EGL
|
||||
initpybullet_egl(void)
|
||||
#else
|
||||
initpybullet(void)
|
||||
#endif //BT_USE_EGL
|
||||
#endif
|
||||
{
|
||||
PyObject* m;
|
||||
#if PY_MAJOR_VERSION >= 3
|
||||
m = PyModule_Create(&moduledef);
|
||||
#else
|
||||
#ifdef BT_USE_EGL
|
||||
m = Py_InitModule3("pybullet_egl", SpamMethods, "Python bindings for Bullet");
|
||||
#else
|
||||
m = Py_InitModule3("pybullet", SpamMethods, "Python bindings for Bullet");
|
||||
#endif //BT_USE_EGL
|
||||
#endif
|
||||
|
||||
#if PY_MAJOR_VERSION >= 3
|
||||
@@ -7275,6 +7360,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