mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-14 13:50:04 +00:00
bd1620eda8
add missing file to pybullet CMakeLists.txt
37 lines
766 B
Python
37 lines
766 B
Python
import pybullet
|
|
import time
|
|
|
|
#choose connection method: GUI, DIRECT, SHARED_MEMORY
|
|
pybullet.connect(pybullet.GUI)
|
|
|
|
#load URDF, given a relative or absolute file+path
|
|
obj = pybullet.loadURDF("r2d2.urdf")
|
|
|
|
posX=0
|
|
posY=3
|
|
posZ=2
|
|
obj2 = pybullet.loadURDF("kuka_lwr/kuka.urdf",posX,posY,posZ)
|
|
|
|
#query the number of joints of the object
|
|
numJoints = pybullet.getNumJoints(obj)
|
|
|
|
print (numJoints)
|
|
|
|
#set the gravity acceleration
|
|
pybullet.setGravity(0,0,-9.8)
|
|
|
|
#step the simulation for 5 seconds
|
|
t_end = time.time() + 5
|
|
while time.time() < t_end:
|
|
pybullet.stepSimulation()
|
|
posAndOrn = pybullet.getBasePositionAndOrientation(obj)
|
|
print (posAndOrn)
|
|
|
|
print ("finished")
|
|
#remove all objects
|
|
pybullet.resetSimulation()
|
|
|
|
#disconnect from the physics server
|
|
pybullet.disconnect()
|
|
|