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:
@@ -649,6 +649,18 @@ B3_SHARED_API int b3RequestActualStateCommandComputeLinkVelocity(b3SharedMemoryC
|
||||
return 0;
|
||||
}
|
||||
|
||||
B3_SHARED_API int b3RequestActualStateCommandComputeForwardKinematics(b3SharedMemoryCommandHandle commandHandle, int computeForwardKinematics)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
btAssert(command->m_type == CMD_REQUEST_ACTUAL_STATE);
|
||||
if (computeForwardKinematics && command->m_type == CMD_REQUEST_ACTUAL_STATE)
|
||||
{
|
||||
command->m_updateFlags |= ACTUAL_STATE_COMPUTE_FORWARD_KINEMATICS;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
B3_SHARED_API int b3GetJointState(b3PhysicsClientHandle physClient, b3SharedMemoryStatusHandle statusHandle, int jointIndex, b3JointSensorState *state)
|
||||
{
|
||||
|
||||
Reference in New Issue
Block a user