Merge remote-tracking branch 'bp/master'
This commit is contained in:
@@ -604,6 +604,49 @@ static PyObject* pybullet_loadMJCF(PyObject* self, PyObject* args, PyObject* key
|
||||
return pylist;
|
||||
}
|
||||
|
||||
static PyObject* pybullet_resetDynamicInfo(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
int bodyUniqueId = -1;
|
||||
int linkIndex = -2;
|
||||
double mass = -1;
|
||||
double lateralFriction = -1;
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
|
||||
int physicsClientId = 0;
|
||||
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "mass", "lateralFriction", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|ddi", kwlist, &bodyUniqueId, &linkIndex,&mass, &lateralFriction, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
|
||||
sm = getPhysicsClient(physicsClientId);
|
||||
if (sm == 0)
|
||||
{
|
||||
PyErr_SetString(SpamError, "Not connected to physics server.");
|
||||
return NULL;
|
||||
}
|
||||
|
||||
{
|
||||
b3SharedMemoryCommandHandle command = b3InitResetDynamicInfo(sm);
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
|
||||
if (mass >= 0)
|
||||
{
|
||||
b3ResetDynamicInfoSetMass(command, bodyUniqueId, linkIndex, mass);
|
||||
}
|
||||
|
||||
if (lateralFriction >= 0)
|
||||
{
|
||||
b3ResetDynamicInfoSetLateralFriction(command, bodyUniqueId, linkIndex, lateralFriction);
|
||||
}
|
||||
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
||||
}
|
||||
|
||||
Py_INCREF(Py_None);
|
||||
return Py_None;
|
||||
}
|
||||
|
||||
static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
double fixedTimeStep = -1;
|
||||
@@ -1843,6 +1886,36 @@ static PyObject* pybullet_getConstraintInfo(PyObject* self, PyObject* args, PyOb
|
||||
return NULL;
|
||||
}
|
||||
|
||||
static PyObject* pybullet_getConstraintUniqueId(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
int physicsClientId = 0;
|
||||
int serialIndex = -1;
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
|
||||
static char* kwlist[] = {"serialIndex", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, &serialIndex, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
sm = getPhysicsClient(physicsClientId);
|
||||
if (sm == 0)
|
||||
{
|
||||
PyErr_SetString(SpamError, "Not connected to physics server.");
|
||||
return NULL;
|
||||
}
|
||||
|
||||
{
|
||||
int userConstraintId = -1;
|
||||
userConstraintId = b3GetUserConstraintId(sm, serialIndex);
|
||||
|
||||
#if PY_MAJOR_VERSION >= 3
|
||||
return PyLong_FromLong(userConstraintId);
|
||||
#else
|
||||
return PyInt_FromLong(userConstraintId);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
static PyObject* pybullet_getNumConstraints(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
int numConstraints = 0;
|
||||
@@ -5430,7 +5503,7 @@ static PyMethodDef SpamMethods[] = {
|
||||
{"getConstraintInfo", (PyCFunction)pybullet_getConstraintInfo, METH_VARARGS | METH_KEYWORDS,
|
||||
"Get the user-created constraint info, given a constraint unique id."},
|
||||
|
||||
{"getConstraintUniqueId", (PyCFunction)pybullet_getBodyUniqueId, METH_VARARGS | METH_KEYWORDS,
|
||||
{"getConstraintUniqueId", (PyCFunction)pybullet_getConstraintUniqueId, METH_VARARGS | METH_KEYWORDS,
|
||||
"Get the unique id of the constraint, given a integer index in range [0.. number of constraints)."},
|
||||
|
||||
{"getBasePositionAndOrientation", (PyCFunction)pybullet_getBasePositionAndOrientation,
|
||||
@@ -5472,6 +5545,9 @@ static PyMethodDef SpamMethods[] = {
|
||||
{"resetJointState", (PyCFunction)pybullet_resetJointState, METH_VARARGS | METH_KEYWORDS,
|
||||
"Reset the state (position, velocity etc) for a joint on a body "
|
||||
"instantaneously, not through physics simulation."},
|
||||
|
||||
{"resetDynamicInfo", (PyCFunction)pybullet_resetDynamicInfo, METH_VARARGS | METH_KEYWORDS,
|
||||
"Reset dynamic information such as mass, lateral friction coefficient."},
|
||||
|
||||
{"setJointMotorControl", (PyCFunction)pybullet_setJointMotorControl, METH_VARARGS,
|
||||
"This (obsolete) method cannot select non-zero physicsClientId, use setJointMotorControl2 instead."
|
||||
|
||||
Reference in New Issue
Block a user