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

@@ -84,10 +84,10 @@ Jacobian::Jacobian(Tree* tree)
Reset();
}
Jacobian::Jacobian(bool useAngularJacobian, int nDof)
Jacobian::Jacobian(bool useAngularJacobian, int nDof, int numEndEffectors)
{
m_tree = 0;
m_nEffector = 1;
m_nEffector = numEndEffectors;
if (useAngularJacobian)
{

View File

@@ -57,7 +57,7 @@ class Jacobian
{
public:
Jacobian(Tree*);
Jacobian(bool useAngularJacobian, int nDof);
Jacobian(bool useAngularJacobian, int nDof, int numEndEffectors);
void ComputeJacobian(VectorR3* targets);
const MatrixRmn& ActiveJacobian() const { return *Jactive; }