implement accurate inverse kinematics in C++. PyBullet.calculateInverseKinematics gets "maxNumIterations=20", "residualThreshold=1.04" to tune
allow to provide current joint positions in IK, overriding the body joint positions, also IK target will be in local coordinates. expose b3ComputeDofCount in C-API
This commit is contained in:
@@ -34,12 +34,12 @@ t=0.
|
||||
prevPose=[0,0,0]
|
||||
prevPose1=[0,0,0]
|
||||
hasPrevPose = 0
|
||||
useNullSpace = 0
|
||||
useNullSpace = 1
|
||||
|
||||
useOrientation = 1
|
||||
#If we set useSimulation=0, it sets the arm pose to be the IK result directly without using dynamic control.
|
||||
#This can be used to test the IK result accuracy.
|
||||
useSimulation = 1
|
||||
useSimulation = 0
|
||||
useRealTimeSimulation = 1
|
||||
ikSolver = 0
|
||||
p.setRealTimeSimulation(useRealTimeSimulation)
|
||||
@@ -69,7 +69,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,jointDamping=jd,solver=ikSolver)
|
||||
jointPoses = p.calculateInverseKinematics(kukaId,kukaEndEffectorIndex,pos,orn,jointDamping=jd,solver=ikSolver, maxNumIterations=100, residualThreshold=.01)
|
||||
else:
|
||||
jointPoses = p.calculateInverseKinematics(kukaId,kukaEndEffectorIndex,pos,solver=ikSolver)
|
||||
|
||||
|
||||
Reference in New Issue
Block a user