[pybullet] implement addUserDebugParameter / readUserDebugParameter

fix inertial frame for door.urdf
allow picking of links of multi-bodies with a fixed base
This commit is contained in:
Erwin Coumans
2017-01-17 15:42:32 -08:00
parent 966ebb04fe
commit 52761f5578
14 changed files with 270 additions and 13 deletions

View File

@@ -9,7 +9,7 @@ cubeId = p.loadURDF("cube_small.urdf",0,0,1)
p.setGravity(0,0,-10)
p.setRealTimeSimulation(1)
cid = p.createConstraint(cubeId,-1,-1,-1,p.JOINT_FIXED,[0,0,0],[0,0,0],[0,0,1])
prev=[0,0,1]
a=-math.pi
while 1:
a=a+0.01
@@ -19,6 +19,6 @@ while 1:
p.setGravity(0,0,-10)
pivot=[a,0,1]
orn = p.getQuaternionFromEuler([a,0,0])
p.changeConstraint(cid,pivot,jointChildFrameOrientation=orn)
p.changeConstraint(cid,pivot,jointChildFrameOrientation=orn, maxForce=50)
p.removeConstraint(cid)