Modify controller constraint in the pybullet vr gripper setup.
This commit is contained in:
@@ -9,14 +9,19 @@ pr2_cid = 1
|
||||
CONTROLLER_ID = 0
|
||||
POSITION=1
|
||||
ORIENTATION=2
|
||||
ANALOG=3
|
||||
BUTTONS=6
|
||||
|
||||
while True:
|
||||
events = p.getVREvents()
|
||||
|
||||
for e in (events):
|
||||
if (e[BUTTONS][33]&p.VR_BUTTON_IS_DOWN):
|
||||
p.changeConstraint(pr2_cid,e[POSITION],e[ORIENTATION], maxForce=50)
|
||||
#todo
|
||||
#p.setJointMotorControl2(pr2_gripper,0)
|
||||
for e in (events):
|
||||
if e[CONTROLLER_ID] == 3: # To make sure we only get the value for one of the remotes
|
||||
p.changeConstraint(pr2_cid, e[POSITION], e[ORIENTATION], maxForce=500)
|
||||
p.setJointMotorControl2(pr2_gripper, 0, controlMode=p.POSITION_CONTROL,
|
||||
targetPosition=gripper_max_joint - e[ANALOG] * gripper_max_joint,
|
||||
force=1.0)
|
||||
p.setJointMotorControl2(pr2_gripper, 2, controlMode=p.POSITION_CONTROL,
|
||||
targetPosition=gripper_max_joint - e[ANALOG] * gripper_max_joint,
|
||||
force=1.1)
|
||||
|
||||
Reference in New Issue
Block a user