bump up shared memory version number
add option to recompute forward kinematics, to be consistent with link velocities in pybullet.getLinkState (..., computeForwardKinematics=0/1), thanks to Jeff Bingham for bringing up this inconsistency
This commit is contained in:
@@ -3126,13 +3126,14 @@ static PyObject* pybullet_getLinkState(PyObject* self, PyObject* args, PyObject*
|
||||
int bodyUniqueId = -1;
|
||||
int linkIndex = -1;
|
||||
int computeLinkVelocity = 0;
|
||||
int computeForwardKinematics = 0;
|
||||
|
||||
int i;
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
|
||||
int physicsClientId = 0;
|
||||
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "computeLinkVelocity", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|ii", kwlist, &bodyUniqueId, &linkIndex,&computeLinkVelocity, &physicsClientId))
|
||||
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "computeLinkVelocity", "computeForwardKinematics", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|iii", kwlist, &bodyUniqueId, &linkIndex,&computeLinkVelocity,&computeForwardKinematics,&physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -3168,6 +3169,11 @@ static PyObject* pybullet_getLinkState(PyObject* self, PyObject* args, PyObject*
|
||||
b3RequestActualStateCommandComputeLinkVelocity(cmd_handle,computeLinkVelocity);
|
||||
}
|
||||
|
||||
if (computeForwardKinematics)
|
||||
{
|
||||
b3RequestActualStateCommandComputeForwardKinematics(cmd_handle,computeForwardKinematics);
|
||||
}
|
||||
|
||||
status_handle =
|
||||
b3SubmitClientCommandAndWaitStatus(sm, cmd_handle);
|
||||
|
||||
|
||||
Reference in New Issue
Block a user