texture caching and geometry caching (PhysX) for much faster loading of many same objects, helps benchmarking/comparison.

add command-line args for PhysX (numCores=..., solver=tgs, )
This commit is contained in:
erwincoumans
2019-02-21 19:24:18 -08:00
parent 3bf27cf8f2
commit 71b1191947
10 changed files with 220 additions and 117 deletions

View File

@@ -658,6 +658,7 @@ public:
}
GUIHelperInterface* m_childGuiHelper;
btHashMap<btHashPtr, int> m_cachedTextureIds;
int m_uidGenerator;
const unsigned char* m_texels;
int m_textureWidth;
@@ -856,6 +857,11 @@ public:
virtual int registerTexture(const unsigned char* texels, int width, int height)
{
int* cachedTexture = m_cachedTextureIds[texels];
if (cachedTexture)
{
return *cachedTexture;
}
m_texels = texels;
m_textureWidth = width;
m_textureHeight = height;
@@ -864,7 +870,7 @@ public:
m_cs->setSharedParam(1, eGUIHelperRegisterTexture);
workerThreadWait();
m_cachedTextureIds.insert(texels, m_textureId);
return m_textureId;
}
virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices, int primitiveType, int textureId)
@@ -918,6 +924,7 @@ public:
virtual void removeAllGraphicsInstances()
{
m_cachedTextureIds.clear();
m_cs->lock();
m_cs->setSharedParam(1, eGUIHelperRemoveAllGraphicsInstances);
workerThreadWait();

View File

@@ -4,9 +4,9 @@
#include "PhysXServerCommandProcessor.h"
B3_SHARED_API b3PhysicsClientHandle b3ConnectPhysX()
B3_SHARED_API b3PhysicsClientHandle b3ConnectPhysX(int argc, char* argv[])
{
PhysXServerCommandProcessor* sdk = new PhysXServerCommandProcessor;
PhysXServerCommandProcessor* sdk = new PhysXServerCommandProcessor(argc,argv);
PhysicsDirect* direct = new PhysicsDirect(sdk, true);
bool connected;

View File

@@ -10,7 +10,7 @@ extern "C"
{
#endif
B3_SHARED_API b3PhysicsClientHandle b3ConnectPhysX();
B3_SHARED_API b3PhysicsClientHandle b3ConnectPhysX(int argc, char* argv[]);
#ifdef __cplusplus
}

View File

@@ -9,6 +9,7 @@
#include "Bullet3Common/b3AlignedObjectArray.h"
#include "LinearMath/btMinMax.h"
#include "Bullet3Common/b3FileUtils.h"
#include "Bullet3Common/b3CommandLineArgs.h"
#include "../../Utils/b3ResourcePath.h"
#include "Bullet3Common/b3ResizablePool.h"
#include "PxPhysicsAPI.h"
@@ -216,16 +217,19 @@ struct PhysXServerCommandProcessorInternalData : public physx::PxSimulationEvent
int m_profileTimingLoggingUid;
int m_stateLoggersUniqueId;
std::string m_profileTimingFileName;
b3CommandLineArgs m_commandLineArgs;
PhysXServerCommandProcessorInternalData(PhysXServerCommandProcessor* sdk)
PhysXServerCommandProcessorInternalData(PhysXServerCommandProcessor* sdk, int argc, char* argv[])
: m_isConnected(false),
m_verboseOutput(false),
m_physicsDeltaTime(1. / 240.),
m_numSimulationSubSteps(0),
m_pluginManager(sdk),
m_profileTimingLoggingUid(-1),
m_stateLoggersUniqueId(1)
m_stateLoggersUniqueId(1),
m_commandLineArgs(argc,argv)
{
m_foundation = NULL;
m_physics = NULL;
m_cooking = NULL;
@@ -246,9 +250,10 @@ struct PhysXServerCommandProcessorInternalData : public physx::PxSimulationEvent
}
};
PhysXServerCommandProcessor::PhysXServerCommandProcessor()
PhysXServerCommandProcessor::PhysXServerCommandProcessor(int argc, char* argv[])
{
m_data = new PhysXServerCommandProcessorInternalData(this);
m_data = new PhysXServerCommandProcessorInternalData(this, argc, argv);
}
PhysXServerCommandProcessor::~PhysXServerCommandProcessor()
@@ -290,25 +295,42 @@ bool PhysXServerCommandProcessor::connect()
m_data->m_physics = PxCreatePhysics(PX_PHYSICS_VERSION, *m_data->m_foundation, physx::PxTolerancesScale(), true, 0);
m_data->m_cooking = PxCreateCooking(PX_PHYSICS_VERSION, *m_data->m_foundation, physx::PxCookingParams(physx::PxTolerancesScale()));
physx::PxU32 numCores = 1;//
physx::PxU32 numCores = 1;
m_data->m_commandLineArgs.GetCmdLineArgument("numCores", numCores);
printf("PhysX numCores=%d\n", numCores);
m_data->m_dispatcher = physx::PxDefaultCpuDispatcherCreate(numCores == 0 ? 0 : numCores - 1);
physx::PxSceneDesc sceneDesc(m_data->m_physics->getTolerancesScale());
sceneDesc.gravity = physx::PxVec3(0.0f, -9.81f, 0.0f);
//todo: add some boolean, to pick solver
sceneDesc.solverType = physx::PxSolverType::ePGS;
std::string solver;
m_data->m_commandLineArgs.GetCmdLineArgument("solver", solver);
if (solver=="tgs")
{
sceneDesc.solverType = physx::PxSolverType::eTGS;
//sceneDesc.solverType = physx::PxSolverType::ePGS;
printf("PhysX using TGS\n");
}
else
{
printf("PhysX using PGS\n");
}
sceneDesc.cpuDispatcher = m_data->m_dispatcher;
//todo: add some boolean, to allow enable/disable of this contact filtering
bool enableContactCallback = false;
m_data->m_commandLineArgs.GetCmdLineArgument("enableContactCallback", enableContactCallback);
if (enableContactCallback)
{
sceneDesc.filterShader = MyPhysXFilter;
sceneDesc.simulationEventCallback = this->m_data;
sceneDesc.contactModifyCallback = this->m_data;
printf("PhysX enableContactCallback\n");
}
else
{
@@ -1203,6 +1225,23 @@ bool PhysXServerCommandProcessor::processRequestContactpointInformationCommand(c
return true;
}
bool PhysXServerCommandProcessor::processCreateCollisionShapeCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes)
{
return false;
}
bool PhysXServerCommandProcessor::processSetAdditionalSearchPathCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes)
{
bool hasStatus = true;
BT_PROFILE("CMD_SET_ADDITIONAL_SEARCH_PATH");
b3ResourcePath::setAdditionalSearchPath(clientCmd.m_searchPathArgs.m_path);
serverStatusOut.m_type = CMD_CLIENT_COMMAND_COMPLETED;
return hasStatus;
}
bool PhysXServerCommandProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes)
{
// BT_PROFILE("processCommand");
@@ -1310,6 +1349,17 @@ bool PhysXServerCommandProcessor::processCommand(const struct SharedMemoryComman
break;
}
case CMD_CREATE_COLLISION_SHAPE:
{
hasStatus = processCreateCollisionShapeCommand(clientCmd, serverStatusOut, bufferServerToClient, bufferSizeInBytes);
break;
}
case CMD_SET_ADDITIONAL_SEARCH_PATH:
{
hasStatus = processSetAdditionalSearchPathCommand(clientCmd, serverStatusOut, bufferServerToClient, bufferSizeInBytes);
break;
}
#if 0
case CMD_SET_VR_CAMERA_STATE:
{
@@ -1365,11 +1415,7 @@ bool PhysXServerCommandProcessor::processCommand(const struct SharedMemoryComman
hasStatus = processLoadSDFCommand(clientCmd,serverStatusOut,bufferServerToClient, bufferSizeInBytes);
break;
}
case CMD_CREATE_COLLISION_SHAPE:
{
hasStatus = processCreateCollisionShapeCommand(clientCmd,serverStatusOut,bufferServerToClient, bufferSizeInBytes);
break;
}
case CMD_CREATE_VISUAL_SHAPE:
{
hasStatus = processCreateVisualShapeCommand(clientCmd,serverStatusOut,bufferServerToClient, bufferSizeInBytes);
@@ -1380,11 +1426,7 @@ bool PhysXServerCommandProcessor::processCommand(const struct SharedMemoryComman
hasStatus = processCreateMultiBodyCommand(clientCmd,serverStatusOut,bufferServerToClient, bufferSizeInBytes);
break;
}
case CMD_SET_ADDITIONAL_SEARCH_PATH:
{
hasStatus = processSetAdditionalSearchPathCommand(clientCmd,serverStatusOut,bufferServerToClient, bufferSizeInBytes);
break;
}
case CMD_LOAD_MJCF:
{

View File

@@ -21,13 +21,15 @@ class PhysXServerCommandProcessor : public PhysicsCommandProcessorInterface
bool processChangeDynamicsInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processRequestPhysicsSimulationParametersCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processRequestContactpointInformationCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processCreateCollisionShapeCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processSetAdditionalSearchPathCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processCustomCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
void resetSimulation();
bool processStateLoggingCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
public:
PhysXServerCommandProcessor();
PhysXServerCommandProcessor(int argc, char* argv[]);
virtual ~PhysXServerCommandProcessor();

View File

@@ -294,6 +294,13 @@ int convertLinkPhysXShapes(const URDFImporterInterface& u2b, URDF2PhysXCachedDat
btScalar radius = collision->m_geometry.m_capsuleRadius;
btScalar height = collision->m_geometry.m_capsuleHeight;
//static PxShape* createExclusiveShape(PxRigidActor& actor, const PxGeometry& geometry, PxMaterial*const* materials, PxU16 materialCount,
// PxShapeFlags shapeFlags = PxShapeFlag::eVISUALIZATION | PxShapeFlag::eSCENE_QUERY_SHAPE | PxShapeFlag::eSIMULATION_SHAPE)
//{
physx::PxShapeFlags shapeFlags = physx::PxShapeFlag::eVISUALIZATION | physx::PxShapeFlag::eSCENE_QUERY_SHAPE | physx::PxShapeFlag::eSIMULATION_SHAPE;
//shape = PxGetPhysics().createShape(physx::PxCapsuleGeometry(radius, 0.5*height), &material, 1, false, shapeFlags);
shape = physx::PxRigidActorExt::createExclusiveShape(*linkPtr, physx::PxCapsuleGeometry(radius, 0.5*height), *material);
btTransform childTrans = col.m_linkLocalFrame;
@@ -691,7 +698,8 @@ btTransform ConvertURDF2PhysXInternal(
//Now create the slider and fixed joints...
cache.m_articulation->setSolverIterationCounts(32);//todo: API?
cache.m_articulation->setSolverIterationCounts(4);//todo: API?
//cache.m_articulation->setSolverIterationCounts(32);//todo: API?
cache.m_jointTypes.push_back(physx::PxArticulationJointType::eUNDEFINED);
cache.m_parentLocalPoses.push_back(physx::PxTransform());
@@ -807,8 +815,10 @@ btTransform ConvertURDF2PhysXInternal(
convertLinkPhysXShapes(u2b, cache, creation, urdfLinkIndex, pathPrefix, localInertialFrame, cache.m_articulation, mbLinkIndex, linkPtr);
if (rbLinkPtr)
{
physx::PxRigidBodyExt::updateMassAndInertia(*rbLinkPtr, mass);
}
//base->setMass(massOut);
//base->setMassSpaceInertiaTensor(diagTensor);
@@ -1005,6 +1015,7 @@ physx::PxBase* URDF2PhysX(physx::PxFoundation* foundation, physx::PxPhysics* phy
if (cache.m_rigidStatic)
{
scene->addActor(*cache.m_rigidStatic);
return cache.m_rigidStatic;
}

View File

@@ -72,7 +72,7 @@ struct MyTexture3
struct EGLRendererObjectArray
{
btAlignedObjectArray<TinyRenderObjectData*> m_renderObjects;
btAlignedObjectArray<int> m_graphicsInstanceIds;
int m_objectUniqueId;
int m_linkIndex;
@@ -92,6 +92,33 @@ struct EGLRendererObjectArray
#define START_WIDTH 1024
#define START_HEIGHT 768
struct btHashVisual
{
UrdfShape m_vis;
btTransform m_tr;
int getHash() const
{
if (m_vis.m_geometry.m_meshFileName.length())
{
btHashString s = m_vis.m_geometry.m_meshFileName.c_str();
return s.getHash();
}
return 0;
}
bool equals(const btHashVisual& other) const
{
if ((m_vis.m_geometry.m_type == URDF_GEOM_MESH) &&
(other.m_vis.m_geometry.m_type == URDF_GEOM_MESH))
{
bool sameTr = m_tr == other.m_tr;
bool sameVis = m_vis.m_geometry.m_meshFileName == other.m_vis.m_geometry.m_meshFileName;
bool sameLocalFrame = m_vis.m_linkLocalFrame == other.m_vis.m_linkLocalFrame;
return sameTr&&sameVis&&sameLocalFrame;
}
return false;
}
};
struct EGLRendererVisualShapeConverterInternalData
{
@@ -105,6 +132,8 @@ struct EGLRendererVisualShapeConverterInternalData
btAlignedObjectArray<int> m_graphicsIndexToSegmentationMask;
btHashMap<btHashInt, EGLRendererObjectArray*> m_swRenderInstances;
btHashMap<btHashPtr, int> m_cachedTextureIds;
btHashMap<btHashVisual, int> m_cachedVisualShapes;
btAlignedObjectArray<b3VisualShapeData> m_visualShapes;
@@ -942,7 +971,7 @@ int EGLRendererVisualShapeConverter::convertVisualShapes(
colorIndex &= 3;
btVector4 color;
color = sColors[colorIndex];
float rgbaColor[4] = {(float)color[0], (float)color[1], (float)color[2], (float)color[3]};
float rgbaColor[4] = { (float)color[0], (float)color[1], (float)color[2], (float)color[3] };
//if (colObj->getCollisionShape()->getShapeType()==STATIC_PLANE_PROXYTYPE)
//{
// color.setValue(1,1,1,1);
@@ -1012,20 +1041,39 @@ int EGLRendererVisualShapeConverter::convertVisualShapes(
visualShape.m_rgbaColor[1] = rgbaColor[1];
visualShape.m_rgbaColor[2] = rgbaColor[2];
visualShape.m_rgbaColor[3] = rgbaColor[3];
int shapeIndex = -1;
btHashVisual tmp;
{
B3_PROFILE("convertURDFToVisualShape2");
convertURDFToVisualShape2(vis, pathPrefix, localInertiaFrame.inverse() * childTrans, vertices, indices, textures, visualShape, fileIO, m_data->m_flags);
btTransform tr = localInertiaFrame.inverse() * childTrans;
tmp.m_vis = *vis;
tmp.m_tr = tr;
int* bla = m_data->m_cachedVisualShapes[tmp];
if (bla)
{
shapeIndex = *bla;
}
else
{
convertURDFToVisualShape2(vis, pathPrefix, tr, vertices, indices, textures, visualShape, fileIO, m_data->m_flags);
}
}
m_data->m_visualShapes.push_back(visualShape);
int textureIndex = -1;
if (shapeIndex < 0)
{
if (vertices.size() && indices.size())
{
TinyRenderObjectData* tinyObj = new TinyRenderObjectData(m_data->m_rgbColorBuffer, m_data->m_depthBuffer, &m_data->m_shadowBuffer, &m_data->m_segmentationMaskBuffer, bodyUniqueId, linkIndex);
unsigned char* textureImage1 = 0;
int textureWidth = 0;
int textureHeight = 0;
bool isCached = false;
int textureIndex = -1;
if (textures.size())
{
@@ -1033,24 +1081,32 @@ int EGLRendererVisualShapeConverter::convertVisualShapes(
textureWidth = textures[0].m_width;
textureHeight = textures[0].m_height;
isCached = textures[0].m_isCached;
textureIndex = m_data->m_instancingRenderer->registerTexture(textureImage1, textureWidth, textureHeight);
}
int* bla = m_data->m_cachedTextureIds[textureImage1];
if (bla)
{
B3_PROFILE("registerMeshShape");
tinyObj->registerMeshShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size(), rgbaColor,
textureImage1, textureWidth, textureHeight);
textureIndex = *bla;
}
visuals->m_renderObjects.push_back(tinyObj);
else
{
textureIndex = m_data->m_instancingRenderer->registerTexture(textureImage1, textureWidth, textureHeight);
m_data->m_cachedTextureIds.insert(textureImage1, textureIndex);
}
}
}
}
{
B3_PROFILE("m_instancingRenderer register");
// register mesh to m_instancingRenderer too.
int shapeIndex = m_data->m_instancingRenderer->registerShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size(), B3_GL_TRIANGLES, textureIndex);
double scaling[3] = {1, 1, 1};
if (shapeIndex < 0)
{
shapeIndex = m_data->m_instancingRenderer->registerShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size(), B3_GL_TRIANGLES, textureIndex);
m_data->m_cachedVisualShapes.insert(tmp, shapeIndex);
}
double scaling[3] = { 1, 1, 1 };
int graphicsIndex = m_data->m_instancingRenderer->registerGraphicsInstance(shapeIndex, &visualShape.m_localVisualFrame[0], &visualShape.m_localVisualFrame[3], &visualShape.m_rgbaColor[0], scaling);
int segmentationMask = bodyUniqueId + ((linkIndex + 1) << 24);
@@ -1069,7 +1125,7 @@ int EGLRendererVisualShapeConverter::convertVisualShapes(
m_data->m_instancingRenderer->writeTransforms();
}
}
for (int i = 0; i < textures.size(); i++)
{
if (!textures[i].m_isCached)
@@ -1078,6 +1134,7 @@ int EGLRendererVisualShapeConverter::convertVisualShapes(
}
}
}
}
return orgGraphicsUniqueId;
}
@@ -1163,13 +1220,7 @@ void EGLRendererVisualShapeConverter::changeRGBAColor(int bodyUniqueId, int link
EGLRendererObjectArray* visuals = *ptrptr;
if ((bodyUniqueId == visuals->m_objectUniqueId) && (linkIndex == visuals->m_linkIndex))
{
for (int q = 0; q < visuals->m_renderObjects.size(); q++)
{
if (shapeIndex < 0 || q == shapeIndex)
{
visuals->m_renderObjects[q]->m_model->setColorRGBA(rgba);
}
}
}
}
}
@@ -1502,16 +1553,12 @@ void EGLRendererVisualShapeConverter::removeVisualShape(int collisionObjectUniqu
{
EGLRendererObjectArray* ptr = *ptrptr;
if (ptr)
{
for (int o = 0; o < ptr->m_renderObjects.size(); o++)
{
for (int i = 0; i < ptr->m_graphicsInstanceIds.size(); i++)
{
m_data->m_instancingRenderer->removeGraphicsInstance(ptr->m_graphicsInstanceIds[i]);
}
delete ptr->m_renderObjects[o];
}
}
delete ptr;
m_data->m_swRenderInstances.remove(collisionObjectUniqueId);
@@ -1520,6 +1567,8 @@ void EGLRendererVisualShapeConverter::removeVisualShape(int collisionObjectUniqu
void EGLRendererVisualShapeConverter::resetAll()
{
m_data->m_cachedTextureIds.clear();
for (int i = 0; i < m_data->m_swRenderInstances.size(); i++)
{
EGLRendererObjectArray** ptrptr = m_data->m_swRenderInstances.getAtIndex(i);
@@ -1528,10 +1577,7 @@ void EGLRendererVisualShapeConverter::resetAll()
EGLRendererObjectArray* ptr = *ptrptr;
if (ptr)
{
for (int o = 0; o < ptr->m_renderObjects.size(); o++)
{
delete ptr->m_renderObjects[o];
}
}
delete ptr;
}
@@ -1556,25 +1602,7 @@ void EGLRendererVisualShapeConverter::changeShapeTexture(int objectUniqueId, int
btAssert(textureUniqueId < m_data->m_textures.size());
if (textureUniqueId >= 0 && textureUniqueId < m_data->m_textures.size())
{
for (int n = 0; n < m_data->m_swRenderInstances.size(); n++)
{
EGLRendererObjectArray** visualArrayPtr = m_data->m_swRenderInstances.getAtIndex(n);
if (0 == visualArrayPtr)
continue; //can this ever happen?
EGLRendererObjectArray* visualArray = *visualArrayPtr;
if (visualArray->m_objectUniqueId == objectUniqueId && visualArray->m_linkIndex == jointIndex)
{
for (int v = 0; v < visualArray->m_renderObjects.size(); v++)
{
TinyRenderObjectData* renderObj = visualArray->m_renderObjects[v];
if ((shapeIndex < 0) || (shapeIndex == v))
{
renderObj->m_model->setDiffuseTextureFromData(m_data->m_textures[textureUniqueId].textureData1, m_data->m_textures[textureUniqueId].m_width, m_data->m_textures[textureUniqueId].m_height);
}
}
}
}
}
}

View File

@@ -1,18 +1,27 @@
import pybullet as p
import pybullet_data as pd
import time
import math
usePhysX = True
if usePhysX:
p.connect(p.PhysX)
p.connect(p.PhysX,options="--numCores=1 --solver=pgs")
p.loadPlugin("eglRendererPlugin")
else:
p.connect(p.GUI)
p.loadURDF("plane.urdf")
useMaximalCoordinates = False
p.setAdditionalSearchPath(pd.getDataPath())
p.loadURDF("plane.urdf", useMaximalCoordinates=useMaximalCoordinates)
p.configureDebugVisualizer(p.COV_ENABLE_TINY_RENDERER,0)
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS,"physx_create_dominoes.json")
for j in range (50):
for i in range (100):
sphere = p.loadURDF("domino/domino.urdf",[i*0.04,1+j*.25,0.03], useMaximalCoordinates=useMaximalCoordinates)
print("loaded!")
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
for i in range (10):
sphere = p.loadURDF("marble_cube.urdf",[0,-1,1+i*1], useMaximalCoordinates=False)
p.changeDynamics(sphere ,-1, mass=1000)
door = p.loadURDF("door.urdf",[0,0,1])
@@ -31,7 +40,11 @@ prevTime = time.time()
angle = math.pi*0.5
count=0
while (1):
count+=1
if (count==10):
p.stopStateLogging(logId)
curTime = time.time()
@@ -45,7 +58,7 @@ while (1):
p.setJointMotorControl2(door,1,p.POSITION_CONTROL, targetPosition = angle, positionGain=10.1, velocityGain=1, force=11.001)
else:
p.setJointMotorControl2(door,1,p.VELOCITY_CONTROL, targetVelocity=1, force=1011)
contacts = p.getContactPoints()
print("contacts=",contacts)
#contacts = p.getContactPoints()
#print("contacts=",contacts)
p.stepSimulation()
time.sleep(1./240.)

View File

@@ -456,7 +456,7 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
#ifdef BT_ENABLE_PHYSX
case eCONNECT_PHYSX:
{
sm = b3ConnectPhysX();
sm = b3ConnectPhysX(argc, argv);
break;
}
#endif

View File

@@ -23,7 +23,7 @@ public:
void addArgs(int argc, char **argv)
{
for (int i = 1; i < argc; i++)
for (int i = 0; i < argc; i++)
{
std::string arg = argv[i];