From f20b7bb07c383a26e16219d3744d791673ec0a94 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Tue, 25 Sep 2018 06:22:06 +0000 Subject: [PATCH] tweak pole IK demo --- examples/pybullet/examples/inverse_kinematics_pole.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/pybullet/examples/inverse_kinematics_pole.py b/examples/pybullet/examples/inverse_kinematics_pole.py index f910e7033..471523fc0 100755 --- a/examples/pybullet/examples/inverse_kinematics_pole.py +++ b/examples/pybullet/examples/inverse_kinematics_pole.py @@ -16,7 +16,7 @@ p.resetBasePositionAndOrientation(sawyerId,[0,0,0],[0,0,0,1]) sawyerEndEffectorIndex = 3 numJoints = p.getNumJoints(sawyerId) #joint damping coefficents -jd=[0.01,0.01,0.01,0.01] +jd=[0.1,0.1,0.1,0.1] p.setGravity(0,0,0) t=0. @@ -41,7 +41,7 @@ while 1: for i in range (1): pos = [2.*math.cos(t),2.*math.cos(t),0.+2.*math.sin(t)] - jointPoses = p.calculateInverseKinematics(sawyerId,sawyerEndEffectorIndex,pos,jointDamping=jd,solver=ikSolver) + jointPoses = p.calculateInverseKinematics(sawyerId,sawyerEndEffectorIndex,pos,jointDamping=jd,solver=ikSolver, maxNumIterations=100) #reset the joint state (ignoring all dynamics, not recommended to use during simulation) for i in range (numJoints):