pybullet: fix calculateInverseKinematics2

This commit is contained in:
Erwin Coumans
2019-08-11 17:02:16 -07:00
parent f9b232b153
commit e0b642d730

View File

@@ -11028,7 +11028,7 @@ static PyObject* pybullet_calculateInverseKinematics2(PyObject* self,
double residualThreshold = -1;
static char* kwlist[] = { "bodyUniqueId", "endEffectorLinkIndices", "targetPositions", "lowerLimits", "upperLimits", "jointRanges", "restPoses", "jointDamping", "solver", "currentPositions", "maxNumIterations", "residualThreshold", "physicsClientId", NULL };
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iOO|OOOOOOiOidi", kwlist, &bodyUniqueId, &endEffectorLinkIndicesObj, &targetPosObj, &lowerLimitsObj, &upperLimitsObj, &jointRangesObj, &restPosesObj, &jointDampingObj, &solver, &currentPositionsObj, &maxNumIterations, &residualThreshold, &physicsClientId))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iOO|OOOOOiOidi", kwlist, &bodyUniqueId, &endEffectorLinkIndicesObj, &targetPosObj, &lowerLimitsObj, &upperLimitsObj, &jointRangesObj, &restPosesObj, &jointDampingObj, &solver, &currentPositionsObj, &maxNumIterations, &residualThreshold, &physicsClientId))
{
return NULL;
}