Merge remote-tracking branch 'upstream/master'
This commit is contained in:
@@ -1864,11 +1864,13 @@ static PyObject* pybullet_resetJointState(PyObject* self, PyObject* args, PyObje
|
||||
int bodyUniqueId;
|
||||
int jointIndex;
|
||||
double targetValue;
|
||||
double targetVelocity = 0;
|
||||
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
|
||||
int physicsClientId = 0;
|
||||
static char* kwlist[] = {"bodyUniqueId", "jointIndex", "targetValue", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iid|i", kwlist, &bodyUniqueId, &jointIndex, &targetValue, &physicsClientId))
|
||||
static char* kwlist[] = {"bodyUniqueId", "jointIndex", "targetValue", "targetVelocity", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iid|di", kwlist, &bodyUniqueId, &jointIndex, &targetValue, &targetVelocity, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -1896,6 +1898,9 @@ static PyObject* pybullet_resetJointState(PyObject* self, PyObject* args, PyObje
|
||||
b3CreatePoseCommandSetJointPosition(sm, commandHandle, jointIndex,
|
||||
targetValue);
|
||||
|
||||
b3CreatePoseCommandSetJointVelocity(sm, commandHandle, jointIndex,
|
||||
targetVelocity);
|
||||
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
|
||||
}
|
||||
}
|
||||
@@ -2975,8 +2980,6 @@ static PyObject* pybullet_setVRCameraState(PyObject* self, PyObject* args, PyObj
|
||||
static PyObject* pybullet_getKeyboardEvents(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
b3SharedMemoryCommandHandle commandHandle;
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
int physicsClientId = 0;
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
struct b3KeyboardEventsData keyboardEventsData;
|
||||
@@ -5434,6 +5437,7 @@ initpybullet(void)
|
||||
PyModule_AddIntConstant(m, "STATE_LOGGING_MINITAUR", STATE_LOGGING_MINITAUR);
|
||||
PyModule_AddIntConstant(m, "STATE_LOGGING_GENERIC_ROBOT", STATE_LOGGING_GENERIC_ROBOT);
|
||||
PyModule_AddIntConstant(m, "STATE_LOGGING_VR_CONTROLLERS", STATE_LOGGING_VR_CONTROLLERS);
|
||||
PyModule_AddIntConstant(m, "STATE_LOGGING_VIDEO_MP4", STATE_LOGGING_VIDEO_MP4);
|
||||
|
||||
PyModule_AddIntConstant(m, "COV_ENABLE_GUI", COV_ENABLE_GUI);
|
||||
PyModule_AddIntConstant(m, "COV_ENABLE_SHADOWS", COV_ENABLE_SHADOWS);
|
||||
|
||||
Reference in New Issue
Block a user