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:
Erwin Coumans
2018-05-23 13:26:00 +10:00
parent f5952a73e7
commit 77c332bd88
12 changed files with 189 additions and 16 deletions

View File

@@ -861,7 +861,10 @@ void GLInstancingRenderer::rebuildGraphicsInstances()
{
int srcIndex2 = usedObjects[i];
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(srcIndex2);
m_graphicsInstances[pg->m_shapeIndex]->m_tempObjectUids.push_back(srcIndex2);
if (pg && pg->m_shapeIndex < m_graphicsInstances.size() && pg->m_shapeIndex >=0)
{
m_graphicsInstances[pg->m_shapeIndex]->m_tempObjectUids.push_back(srcIndex2);
}
}
int curOffset = 0;