expose PyBullet.calculateInverseKinematics2 that allows to specify multiple IK end effector locations (not multiple orientations)

usage example:
jointPoses = p.calculateInverseKinematics2(bodyUniqueId, [endEffectorLinkIndices], [endEffectorTargetWorldPositions])
This commit is contained in:
Erwin Coumans
2019-07-10 17:21:18 -07:00
parent bb8f621bf9
commit ee9575167d
9 changed files with 546 additions and 80 deletions

View File

@@ -31,6 +31,13 @@ public:
const double* q_old, int numQ, int endEffectorIndex,
double* q_new, int ikMethod, const double* linear_jacobian, const double* angular_jacobian, int jacobian_size, const double dampIk[6]);
bool computeIK2(
const double* endEffectorTargetPositions,
const double* endEffectorCurrentPositions,
int numEndEffectors,
const double* q_current, int numQ,
double* q_new, int ikMethod, const double* linear_jacobians, const double dampIk[6]);
bool computeNullspaceVel(int numQ, const double* q_current, const double* lower_limit, const double* upper_limit, const double* joint_range, const double* rest_pose);
bool setDampingCoeff(int numQ, const double* coeff);
};