[pybullet] Add calculateJacobian.

* Add the calculateJacobian method to the pybullet API.
* Adjust the shared memory interface to handle fixed/floating bases
  in the calculateJacobian method.
* Fix a few comments.
This commit is contained in:
Jeffrey Bingham
2017-09-23 19:58:59 -07:00
parent a506879d6c
commit 1727e47beb
7 changed files with 241 additions and 64 deletions

View File

@@ -988,7 +988,8 @@ bool b3RobotSimulatorClientAPI::getBodyJacobian(int bodyUniqueId, int linkIndex,
if (b3GetStatusType(statusHandle) == CMD_CALCULATED_JACOBIAN_COMPLETED)
{
b3GetStatusJacobian(statusHandle, linearJacobian, angularJacobian);
int dofCount;
b3GetStatusJacobian(statusHandle, &dofCount, linearJacobian, angularJacobian);
return true;
}
return false;