diff --git a/examples/pybullet/inverse_kinematics.py b/examples/pybullet/inverse_kinematics.py index f71707097..4c85ec48c 100644 --- a/examples/pybullet/inverse_kinematics.py +++ b/examples/pybullet/inverse_kinematics.py @@ -22,6 +22,8 @@ ul=[.967,2 ,2.96,2.29,2.96,2.09,3.05] jr=[5.8,4,5.8,4,5.8,4,6] #restposes for null space rp=[0,0,0,0.5*math.pi,0,-math.pi*0.5*0.66,0] +#joint damping coefficents +jd=[0.1,0.1,0.1,0.1,0.1,0.1,0.1] for i in range (numJoints): p.resetJointState(kukaId,i,rp[i]) @@ -64,7 +66,7 @@ while 1: jointPoses = p.calculateInverseKinematics(kukaId,kukaEndEffectorIndex,pos,lowerLimits=ll, upperLimits=ul, jointRanges=jr, restPoses=rp) else: if (useOrientation==1): - jointPoses = p.calculateInverseKinematics(kukaId,kukaEndEffectorIndex,pos,orn) + jointPoses = p.calculateInverseKinematics(kukaId,kukaEndEffectorIndex,pos,orn,jointDamping=jd) else: jointPoses = p.calculateInverseKinematics(kukaId,kukaEndEffectorIndex,pos)