bullet3/examples/pybullet/test.py

37 lines
766 B
Python
Raw Normal View History

import pybullet
import time
#choose connection method: GUI, DIRECT, SHARED_MEMORY
pybullet.connect(pybullet.GUI)
#load URDF, given a relative or absolute file+path
2016-05-10 08:28:45 +00:00
obj = pybullet.loadURDF("r2d2.urdf")
2016-05-10 08:26:13 +00:00
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
2016-05-10 08:24:40 +00:00
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()