PyBullet: add option to cache graphics shapes for URDF files, handy for benchmarks with many duplicate robots
See https://github.com/erwincoumans/pybullet_robots ANYmal.py for an example. PyBullet: Expose p.setPhysicsEngineParameter(solverResidualThreshold=1e-2) (b3PhysicsParamSetSolverResidualThreshold), increases solver performance a lot PyBullet: Expose p.setPhysicsEngineParameter(contactSlop) Set it to zero, to avoid issues with restitution. PyBullet: Expose isNumpyEnabled, return True is PyBullet was compiled with NUMPY support for 'getCameraImage'. PyBullet: Expose p.ChangeDynamics(objectUid, linkIndex, contactProcessingThreshold), to avoid issues of speculative/predictive contacts with restitution. See also http://twvideo01.ubm-us.net/o1/vault/gdc2012/slides/Programming%20Track/Vincent_ROBERT_Track_ADifferentApproach.pdf
This commit is contained in:
@@ -919,13 +919,15 @@ static PyObject* pybullet_changeDynamicsInfo(PyObject* self, PyObject* args, PyO
|
||||
double contactDamping = -1;
|
||||
double ccdSweptSphereRadius=-1;
|
||||
int frictionAnchor = -1;
|
||||
double contactProcessingThreshold = -1;
|
||||
|
||||
PyObject* localInertiaDiagonalObj=0;
|
||||
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
|
||||
int physicsClientId = 0;
|
||||
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "mass", "lateralFriction", "spinningFriction", "rollingFriction","restitution", "linearDamping", "angularDamping", "contactStiffness", "contactDamping", "frictionAnchor", "localInertiaDiagonal", "ccdSweptSphereRadius", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|dddddddddiOdi", kwlist, &bodyUniqueId, &linkIndex,&mass, &lateralFriction, &spinningFriction, &rollingFriction, &restitution,&linearDamping, &angularDamping, &contactStiffness, &contactDamping, &frictionAnchor, &localInertiaDiagonalObj, &ccdSweptSphereRadius, &physicsClientId))
|
||||
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "mass", "lateralFriction", "spinningFriction", "rollingFriction","restitution", "linearDamping", "angularDamping", "contactStiffness", "contactDamping", "frictionAnchor", "localInertiaDiagonal", "ccdSweptSphereRadius", "contactProcessingThreshold", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|dddddddddiOddi", kwlist, &bodyUniqueId, &linkIndex,&mass, &lateralFriction, &spinningFriction, &rollingFriction, &restitution,&linearDamping, &angularDamping, &contactStiffness, &contactDamping, &frictionAnchor, &localInertiaDiagonalObj, &ccdSweptSphereRadius, &contactProcessingThreshold, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -995,6 +997,10 @@ static PyObject* pybullet_changeDynamicsInfo(PyObject* self, PyObject* args, PyO
|
||||
{
|
||||
b3ChangeDynamicsInfoSetCcdSweptSphereRadius(command,bodyUniqueId,linkIndex, ccdSweptSphereRadius);
|
||||
}
|
||||
if (contactProcessingThreshold >= 0)
|
||||
{
|
||||
b3ChangeDynamicsInfoSetContactProcessingThreshold(command, bodyUniqueId, linkIndex, contactProcessingThreshold);
|
||||
}
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
||||
}
|
||||
|
||||
@@ -1163,12 +1169,14 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
int deterministicOverlappingPairs = -1;
|
||||
int jointFeedbackMode =-1;
|
||||
double solverResidualThreshold = -1;
|
||||
double contactSlop = -1;
|
||||
|
||||
int physicsClientId = 0;
|
||||
static char* kwlist[] = {"fixedTimeStep", "numSolverIterations", "useSplitImpulse", "splitImpulsePenetrationThreshold", "numSubSteps", "collisionFilterMode", "contactBreakingThreshold", "maxNumCmdPer1ms", "enableFileCaching","restitutionVelocityThreshold", "erp", "contactERP", "frictionERP", "enableConeFriction", "deterministicOverlappingPairs", "allowedCcdPenetration", "jointFeedbackMode", "physicsClientId", NULL};
|
||||
static char* kwlist[] = {"fixedTimeStep", "numSolverIterations", "useSplitImpulse", "splitImpulsePenetrationThreshold", "numSubSteps", "collisionFilterMode", "contactBreakingThreshold", "maxNumCmdPer1ms", "enableFileCaching","restitutionVelocityThreshold", "erp", "contactERP", "frictionERP", "enableConeFriction", "deterministicOverlappingPairs", "allowedCcdPenetration", "jointFeedbackMode", "solverResidualThreshold", "contactSlop", "physicsClientId", NULL};
|
||||
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiidiiddddiidii", kwlist, &fixedTimeStep, &numSolverIterations, &useSplitImpulse, &splitImpulsePenetrationThreshold, &numSubSteps,
|
||||
&collisionFilterMode, &contactBreakingThreshold, &maxNumCmdPer1ms, &enableFileCaching, &restitutionVelocityThreshold, &erp, &contactERP, &frictionERP, &enableConeFriction, &deterministicOverlappingPairs, &allowedCcdPenetration, &jointFeedbackMode, &physicsClientId))
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiidiiddddiididdi", kwlist, &fixedTimeStep, &numSolverIterations, &useSplitImpulse, &splitImpulsePenetrationThreshold, &numSubSteps,
|
||||
&collisionFilterMode, &contactBreakingThreshold, &maxNumCmdPer1ms, &enableFileCaching, &restitutionVelocityThreshold, &erp, &contactERP, &frictionERP, &enableConeFriction, &deterministicOverlappingPairs, &allowedCcdPenetration, &jointFeedbackMode, &solverResidualThreshold, &contactSlop, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -1189,6 +1197,11 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
|
||||
b3PhysicsParamSetNumSolverIterations(command, numSolverIterations);
|
||||
}
|
||||
|
||||
if (solverResidualThreshold)
|
||||
{
|
||||
b3PhysicsParamSetSolverResidualThreshold(command, solverResidualThreshold);
|
||||
}
|
||||
|
||||
if (collisionFilterMode >= 0)
|
||||
{
|
||||
b3PhysicsParamSetCollisionFilterMode(command, collisionFilterMode);
|
||||
@@ -1213,6 +1226,12 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
|
||||
{
|
||||
b3PhysicsParamSetContactBreakingThreshold(command, contactBreakingThreshold);
|
||||
}
|
||||
if (contactSlop >= 0)
|
||||
{
|
||||
b3PhysicsParamSetContactSlop(command, contactSlop);
|
||||
}
|
||||
|
||||
|
||||
//-1 is disables the maxNumCmdPer1ms feature, allow it
|
||||
if (maxNumCmdPer1ms >= -1)
|
||||
{
|
||||
@@ -6832,6 +6851,29 @@ static PyObject* pybullet_getContactPointData(PyObject* self, PyObject* args, Py
|
||||
return Py_None;
|
||||
}
|
||||
|
||||
|
||||
static PyObject* pybullet_isNumpyEnabled(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
int physicsClientId = 0;
|
||||
int isNumpyEnabled = 0;
|
||||
int method = 0;
|
||||
PyObject* pylist = 0;
|
||||
PyObject* val = 0;
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
static char* kwlist[] = { "physicsClientId", NULL };
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
|
||||
#ifdef PYBULLET_USE_NUMPY
|
||||
isNumpyEnabled = 1;
|
||||
#endif
|
||||
return PyLong_FromLong(isNumpyEnabled);
|
||||
}
|
||||
|
||||
|
||||
|
||||
/// Render an image from the current timestep of the simulation, width, height are required, other args are optional
|
||||
// getCameraImage(w, h, view[16], projection[16], lightDir[3], lightColor[3], lightDist, hasShadow, lightAmbientCoeff, lightDiffuseCoeff, lightSpecularCoeff, renderer)
|
||||
static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
@@ -8897,6 +8939,10 @@ static PyMethodDef SpamMethods[] = {
|
||||
#endif
|
||||
},
|
||||
|
||||
{ "isNumpyEnabled", (PyCFunction)pybullet_isNumpyEnabled, METH_VARARGS | METH_KEYWORDS,
|
||||
"return True if PyBullet was compiled with NUMPY support. This makes the getCameraImage API faster"
|
||||
},
|
||||
|
||||
{"computeViewMatrix", (PyCFunction)pybullet_computeViewMatrix, METH_VARARGS | METH_KEYWORDS,
|
||||
"Compute a camera viewmatrix from camera eye, target position and up vector "},
|
||||
|
||||
@@ -9261,6 +9307,8 @@ initpybullet(void)
|
||||
PyModule_AddIntConstant(m, "URDF_USE_IMPLICIT_CYLINDER", URDF_USE_IMPLICIT_CYLINDER);
|
||||
PyModule_AddIntConstant(m, "URDF_GLOBAL_VELOCITIES_MB", URDF_GLOBAL_VELOCITIES_MB);
|
||||
PyModule_AddIntConstant(m, "MJCF_COLORS_FROM_FILE", MJCF_COLORS_FROM_FILE);
|
||||
PyModule_AddIntConstant(m, "URDF_ENABLE_CACHED_GRAPHICS_SHAPES", URDF_ENABLE_CACHED_GRAPHICS_SHAPES);
|
||||
|
||||
|
||||
PyModule_AddIntConstant(m, "URDF_USE_SELF_COLLISION", URDF_USE_SELF_COLLISION);
|
||||
PyModule_AddIntConstant(m, "URDF_USE_SELF_COLLISION_EXCLUDE_PARENT", URDF_USE_SELF_COLLISION_EXCLUDE_PARENT);
|
||||
|
||||
Reference in New Issue
Block a user