add pybullet.getBasePositionAndOrientation

add missing file to pybullet CMakeLists.txt
This commit is contained in:
Erwin Coumans
2016-05-24 15:29:26 -07:00
parent ef19248daf
commit bd1620eda8
3 changed files with 111 additions and 16 deletions

View File

@@ -2,7 +2,7 @@ import pybullet
import time
#choose connection method: GUI, DIRECT, SHARED_MEMORY
pybullet.connect(pybullet.SHARED_MEMORY)
pybullet.connect(pybullet.GUI)
#load URDF, given a relative or absolute file+path
obj = pybullet.loadURDF("r2d2.urdf")
@@ -24,6 +24,8 @@ pybullet.setGravity(0,0,-9.8)
t_end = time.time() + 5
while time.time() < t_end:
pybullet.stepSimulation()
posAndOrn = pybullet.getBasePositionAndOrientation(obj)
print (posAndOrn)
print ("finished")
#remove all objects