From 6695268fbaa5f987d2c44bf43f988c3749ea3820 Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Mon, 20 Mar 2017 09:52:24 -0700 Subject: [PATCH] Fix the issue with indentation in pr2 setup. --- examples/pybullet/vr_kuka_pr2_move.py | 16 +++++----------- 1 file changed, 5 insertions(+), 11 deletions(-) diff --git a/examples/pybullet/vr_kuka_pr2_move.py b/examples/pybullet/vr_kuka_pr2_move.py index 22e5730c1..53dbe844d 100644 --- a/examples/pybullet/vr_kuka_pr2_move.py +++ b/examples/pybullet/vr_kuka_pr2_move.py @@ -15,14 +15,8 @@ BUTTONS=6 gripper_max_joint = 0.550569 while True: events = p.getVREvents() - - 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) - \ No newline at end of file + 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) \ No newline at end of file