Merge remote-tracking branch 'upstream/master'
This commit is contained in:
@@ -693,8 +693,9 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
|
||||
static PyObject* pybullet_loadURDF(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
int physicsClientId = 0;
|
||||
int flags = 0;
|
||||
|
||||
static char* kwlist[] = {"fileName", "basePosition", "baseOrientation", "useMaximalCoordinates", "useFixedBase", "physicsClientId", NULL};
|
||||
static char* kwlist[] = {"fileName", "basePosition", "baseOrientation", "useMaximalCoordinates", "useFixedBase", "flags","physicsClientId", NULL};
|
||||
|
||||
static char* kwlistBackwardCompatible4[] = {"fileName", "startPosX", "startPosY", "startPosZ", NULL};
|
||||
static char* kwlistBackwardCompatible8[] = {"fileName", "startPosX", "startPosY", "startPosZ", "startOrnX", "startOrnY", "startOrnZ", "startOrnW", NULL};
|
||||
@@ -741,7 +742,7 @@ static PyObject* pybullet_loadURDF(PyObject* self, PyObject* args, PyObject* key
|
||||
double basePos[3];
|
||||
double baseOrn[4];
|
||||
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|OOiii", kwlist, &urdfFileName, &basePosObj, &baseOrnObj, &useMaximalCoordinates, &useFixedBase, &physicsClientId))
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|OOiiii", kwlist, &urdfFileName, &basePosObj, &baseOrnObj, &useMaximalCoordinates, &useFixedBase, &flags, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -790,6 +791,8 @@ static PyObject* pybullet_loadURDF(PyObject* self, PyObject* args, PyObject* key
|
||||
b3SharedMemoryCommandHandle command =
|
||||
b3LoadUrdfCommandInit(sm, urdfFileName);
|
||||
|
||||
b3LoadUrdfCommandSetFlags(command,flags);
|
||||
|
||||
// setting the initial position, orientation and other arguments are
|
||||
// optional
|
||||
b3LoadUrdfCommandSetStartPosition(command, startPosX, startPosY, startPosZ);
|
||||
@@ -2076,7 +2079,7 @@ static PyObject* pybullet_getJointInfo(PyObject* self, PyObject* args, PyObject*
|
||||
|
||||
int bodyUniqueId = -1;
|
||||
int jointIndex = -1;
|
||||
int jointInfoSize = 8; // size of struct b3JointInfo
|
||||
int jointInfoSize = 12; // size of struct b3JointInfo
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
int physicsClientId = 0;
|
||||
static char* kwlist[] = {"bodyUniqueId", "jointIndex", "physicsClientId", NULL};
|
||||
@@ -2120,6 +2123,15 @@ static PyObject* pybullet_getJointInfo(PyObject* self, PyObject* args, PyObject*
|
||||
PyFloat_FromDouble(info.m_jointDamping));
|
||||
PyTuple_SetItem(pyListJointInfo, 7,
|
||||
PyFloat_FromDouble(info.m_jointFriction));
|
||||
PyTuple_SetItem(pyListJointInfo, 8,
|
||||
PyFloat_FromDouble(info.m_jointLowerLimit));
|
||||
PyTuple_SetItem(pyListJointInfo, 9,
|
||||
PyFloat_FromDouble(info.m_jointUpperLimit));
|
||||
PyTuple_SetItem(pyListJointInfo, 10,
|
||||
PyFloat_FromDouble(info.m_jointMaxForce));
|
||||
PyTuple_SetItem(pyListJointInfo, 11,
|
||||
PyFloat_FromDouble(info.m_jointMaxVelocity));
|
||||
|
||||
return pyListJointInfo;
|
||||
}
|
||||
else
|
||||
@@ -2247,17 +2259,21 @@ static PyObject* pybullet_getLinkState(PyObject* self, PyObject* args, PyObject*
|
||||
PyObject* pyLinkStateLocalInertialOrientation;
|
||||
PyObject* pyLinkStateWorldLinkFramePosition;
|
||||
PyObject* pyLinkStateWorldLinkFrameOrientation;
|
||||
PyObject* pyLinkStateWorldLinkLinearVelocity;
|
||||
PyObject* pyLinkStateWorldLinkAngularVelocity;
|
||||
|
||||
struct b3LinkState linkState;
|
||||
|
||||
int bodyUniqueId = -1;
|
||||
int linkIndex = -1;
|
||||
int computeLinkVelocity = 0;
|
||||
|
||||
int i;
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
|
||||
int physicsClientId = 0;
|
||||
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|i", kwlist, &bodyUniqueId, &linkIndex, &physicsClientId))
|
||||
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "computeLinkVelocity", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|ii", kwlist, &bodyUniqueId, &linkIndex,&computeLinkVelocity, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -2287,6 +2303,12 @@ static PyObject* pybullet_getLinkState(PyObject* self, PyObject* args, PyObject*
|
||||
|
||||
cmd_handle =
|
||||
b3RequestActualStateCommandInit(sm, bodyUniqueId);
|
||||
|
||||
if (computeLinkVelocity)
|
||||
{
|
||||
b3RequestActualStateCommandComputeLinkVelocity(cmd_handle,computeLinkVelocity);
|
||||
}
|
||||
|
||||
status_handle =
|
||||
b3SubmitClientCommandAndWaitStatus(sm, cmd_handle);
|
||||
|
||||
@@ -2341,7 +2363,16 @@ static PyObject* pybullet_getLinkState(PyObject* self, PyObject* args, PyObject*
|
||||
PyFloat_FromDouble(linkState.m_worldLinkFrameOrientation[i]));
|
||||
}
|
||||
|
||||
pyLinkState = PyTuple_New(6);
|
||||
|
||||
|
||||
if (computeLinkVelocity)
|
||||
{
|
||||
pyLinkState = PyTuple_New(8);
|
||||
} else
|
||||
{
|
||||
pyLinkState = PyTuple_New(6);
|
||||
}
|
||||
|
||||
PyTuple_SetItem(pyLinkState, 0, pyLinkStateWorldPosition);
|
||||
PyTuple_SetItem(pyLinkState, 1, pyLinkStateWorldOrientation);
|
||||
PyTuple_SetItem(pyLinkState, 2, pyLinkStateLocalInertialPosition);
|
||||
@@ -2349,6 +2380,20 @@ static PyObject* pybullet_getLinkState(PyObject* self, PyObject* args, PyObject*
|
||||
PyTuple_SetItem(pyLinkState, 4, pyLinkStateWorldLinkFramePosition);
|
||||
PyTuple_SetItem(pyLinkState, 5, pyLinkStateWorldLinkFrameOrientation);
|
||||
|
||||
if (computeLinkVelocity)
|
||||
{
|
||||
pyLinkStateWorldLinkLinearVelocity = PyTuple_New(3);
|
||||
pyLinkStateWorldLinkAngularVelocity = PyTuple_New(3);
|
||||
for (i = 0; i < 3; ++i)
|
||||
{
|
||||
PyTuple_SetItem(pyLinkStateWorldLinkLinearVelocity, i,
|
||||
PyFloat_FromDouble(linkState.m_worldLinearVelocity[i]));
|
||||
PyTuple_SetItem(pyLinkStateWorldLinkAngularVelocity, i,
|
||||
PyFloat_FromDouble(linkState.m_worldAngularVelocity[i]));
|
||||
}
|
||||
PyTuple_SetItem(pyLinkState, 6, pyLinkStateWorldLinkLinearVelocity);
|
||||
PyTuple_SetItem(pyLinkState, 7, pyLinkStateWorldLinkAngularVelocity);
|
||||
}
|
||||
return pyLinkState;
|
||||
}
|
||||
}
|
||||
@@ -3875,15 +3920,13 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
|
||||
b3RequestCameraImageSetLightDiffuseCoeff(command, lightDiffuseCoeff);
|
||||
b3RequestCameraImageSetLightSpecularCoeff(command, lightSpecularCoeff);
|
||||
|
||||
b3RequestCameraImageSelectRenderer(command, renderer);
|
||||
b3RequestCameraImageSelectRenderer(command, renderer);//renderer could be ER_BULLET_HARDWARE_OPENGL
|
||||
|
||||
if (b3CanSubmitCommand(sm))
|
||||
{
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
|
||||
// b3RequestCameraImageSelectRenderer(command,ER_BULLET_HARDWARE_OPENGL);
|
||||
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
if (statusType == CMD_CAMERA_IMAGE_COMPLETED)
|
||||
@@ -4308,7 +4351,6 @@ static PyObject* pybullet_renderImageObsolete(PyObject* self, PyObject* args)
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
|
||||
// b3RequestCameraImageSelectRenderer(command,ER_BULLET_HARDWARE_OPENGL);
|
||||
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
@@ -5381,6 +5423,8 @@ initpybullet(void)
|
||||
PyModule_AddIntConstant(m, "ER_TINY_RENDERER", ER_TINY_RENDERER);
|
||||
PyModule_AddIntConstant(m, "ER_BULLET_HARDWARE_OPENGL", ER_BULLET_HARDWARE_OPENGL);
|
||||
|
||||
PyModule_AddIntConstant(m, "URDF_USE_INERTIA_FROM_FILE", URDF_USE_INERTIA_FROM_FILE);
|
||||
|
||||
PyModule_AddIntConstant(m, "B3G_F1", B3G_F1);
|
||||
PyModule_AddIntConstant(m, "B3G_F2", B3G_F2);
|
||||
PyModule_AddIntConstant(m, "B3G_F3", B3G_F3);
|
||||
|
||||
Reference in New Issue
Block a user