Merge branch 'master' of https://github.com/erwincoumans/bullet3
This commit is contained in:
25
examples/pybullet/examples/sleeping.py
Normal file
25
examples/pybullet/examples/sleeping.py
Normal file
@@ -0,0 +1,25 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
useMaximalCoordinates=False
|
||||
|
||||
flags = p.URDF_ENABLE_SLEEPING
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||
|
||||
p.loadURDF("plane100.urdf",flags=flags, useMaximalCoordinates=useMaximalCoordinates)
|
||||
#p.loadURDF("cube_small.urdf", [0,0,0.5], flags=flags)
|
||||
for k in range (5):
|
||||
for i in range (5):
|
||||
r2d2=p.loadURDF("r2d2.urdf",[k*2,i*2,1], useMaximalCoordinates=useMaximalCoordinates, flags=p.URDF_ENABLE_CACHED_GRAPHICS_SHAPES+flags)
|
||||
for j in range (p.getNumJoints(r2d2)):
|
||||
p.setJointMotorControl2(r2d2,j,p.VELOCITY_CONTROL,targetVelocity=0)
|
||||
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||
timestep = 1./240.
|
||||
p.setTimeStep(timestep)
|
||||
p.setGravity(0,0,-10)
|
||||
|
||||
while p.isConnected():
|
||||
p.stepSimulation()
|
||||
time.sleep(timestep)
|
||||
@@ -9313,6 +9313,7 @@ initpybullet(void)
|
||||
PyModule_AddIntConstant(m, "URDF_GLOBAL_VELOCITIES_MB", URDF_GLOBAL_VELOCITIES_MB);
|
||||
PyModule_AddIntConstant(m, "MJCF_COLORS_FROM_FILE", MJCF_COLORS_FROM_FILE);
|
||||
PyModule_AddIntConstant(m, "URDF_ENABLE_CACHED_GRAPHICS_SHAPES", URDF_ENABLE_CACHED_GRAPHICS_SHAPES);
|
||||
PyModule_AddIntConstant(m, "URDF_ENABLE_SLEEPING", URDF_ENABLE_SLEEPING);
|
||||
|
||||
|
||||
PyModule_AddIntConstant(m, "URDF_USE_SELF_COLLISION", URDF_USE_SELF_COLLISION);
|
||||
|
||||
Reference in New Issue
Block a user