pybullet vr_kuka_setup.py: add a gear joint, to keep the gripper centered,

vr_kuka_control.py: control all joints, use analogue button to close gripper
remove some debug warnings/prints
pybullet, avoid crash in changeUserConstraint if not passing a [list]
allow some gym environments (pybullet_pendulum and locomotors) to re-use an existing physics client connection.
This commit is contained in:
erwincoumans
2017-11-12 10:36:30 -08:00
parent 99f9584a2c
commit 6be7e34dd6
10 changed files with 101 additions and 81 deletions

View File

@@ -48,6 +48,10 @@ for jointIndex in range (p.getNumJoints(kuka_gripper)):
kuka_cid = p.createConstraint(kuka, 6, kuka_gripper,0,p.JOINT_FIXED, [0,0,0], [0,0,0.05],[0,0,0])
pr2_cid2 = p.createConstraint(kuka_gripper,4,kuka_gripper,6,jointType=p.JOINT_GEAR,jointAxis =[1,1,1],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
p.changeConstraint(pr2_cid2,gearRatio=-1, erp=0.5, relativePositionTarget=0, maxForce=100)
objects = [p.loadURDF("jenga/jenga.urdf", 1.300000,-0.700000,0.750000,0.000000,0.707107,0.000000,0.707107)]
objects = [p.loadURDF("jenga/jenga.urdf", 1.200000,-0.700000,0.750000,0.000000,0.707107,0.000000,0.707107)]
objects = [p.loadURDF("jenga/jenga.urdf", 1.100000,-0.700000,0.750000,0.000000,0.707107,0.000000,0.707107)]