Increase mesh allocation for vertices/indices in PyBullet.createCollisionShape

See createMesh.py for an example.

The data has to fit in shared memory, hence the limit on Mac is lower than Windows and Linux:

#ifdef __APPLE__
#define B3_MAX_NUM_VERTICES 8192
#define B3_MAX_NUM_INDICES 32768
#else
#define B3_MAX_NUM_VERTICES 131072
#define B3_MAX_NUM_INDICES 524288
#endif
This commit is contained in:
Erwin Coumans
2019-01-03 16:19:28 -08:00
parent 21d9465d94
commit bf9efffa4b
7 changed files with 199 additions and 44 deletions

View File

@@ -1280,8 +1280,11 @@ B3_SHARED_API int b3CreateCollisionShapeAddMesh(b3SharedMemoryCommandHandle comm
return -1;
}
B3_SHARED_API int b3CreateCollisionShapeAddConvexMesh(b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], const double* vertices, int numVertices)
B3_SHARED_API int b3CreateCollisionShapeAddConvexMesh(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], const double* vertices, int numVertices)
{
PhysicsClient* cl = (PhysicsClient*)physClient;
b3Assert(cl);
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
b3Assert(command);
b3Assert((command->m_type == CMD_CREATE_COLLISION_SHAPE) || (command->m_type == CMD_CREATE_VISUAL_SHAPE));
@@ -1305,12 +1308,7 @@ B3_SHARED_API int b3CreateCollisionShapeAddConvexMesh(b3SharedMemoryCommandHandl
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_numVertices = numVertices;
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_numIndices = 0;
for (i=0;i<numVertices;i++)
{
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_vertices[i*3+0]=vertices[i*3+0];
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_vertices[i*3+1]=vertices[i*3+1];
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_vertices[i*3+2]=vertices[i*3+2];
}
cl->uploadBulletFileToSharedMemory((const char*)vertices, numVertices * sizeof(double)*3);
command->m_createUserShapeArgs.m_numUserShapes++;
return shapeIndex;
}
@@ -1318,8 +1316,10 @@ B3_SHARED_API int b3CreateCollisionShapeAddConvexMesh(b3SharedMemoryCommandHandl
return -1;
}
B3_SHARED_API int b3CreateCollisionShapeAddConcaveMesh(b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], const double* vertices, int numVertices, const int* indices, int numIndices)
B3_SHARED_API int b3CreateCollisionShapeAddConcaveMesh(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], const double* vertices, int numVertices, const int* indices, int numIndices)
{
PhysicsClient* cl = (PhysicsClient*)physClient;
b3Assert(cl);
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
b3Assert(command);
b3Assert((command->m_type == CMD_CREATE_COLLISION_SHAPE) || (command->m_type == CMD_CREATE_VISUAL_SHAPE));
@@ -1342,11 +1342,16 @@ B3_SHARED_API int b3CreateCollisionShapeAddConcaveMesh(b3SharedMemoryCommandHand
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_meshFileName[0]=0;
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_numVertices = numVertices;
int totalUploadSizeInBytes = numVertices * sizeof(double) *3 + numIndices * sizeof(int);
char* data = (char*)malloc(totalUploadSizeInBytes);
double* vertexUpload = (double*)data;
int* indexUpload = (int*)(data + numVertices*sizeof(double)*3);
for (i=0;i<numVertices;i++)
{
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_vertices[i*3+0]=vertices[i*3+0];
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_vertices[i*3+1]=vertices[i*3+1];
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_vertices[i*3+2]=vertices[i*3+2];
vertexUpload[i*3+0]=vertices[i*3+0];
vertexUpload[i*3+1]=vertices[i*3+1];
vertexUpload[i*3+2]=vertices[i*3+2];
}
if (numIndices>B3_MAX_NUM_INDICES)
numIndices = B3_MAX_NUM_INDICES;
@@ -1354,9 +1359,11 @@ B3_SHARED_API int b3CreateCollisionShapeAddConcaveMesh(b3SharedMemoryCommandHand
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_numIndices = numIndices;
for (i=0;i<numIndices;i++)
{
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_indices[i]=indices[i];
indexUpload[i]=indices[i];
}
command->m_createUserShapeArgs.m_numUserShapes++;
cl->uploadBulletFileToSharedMemory(data, totalUploadSizeInBytes);
free(data);
return shapeIndex;
}
}

View File

@@ -466,8 +466,8 @@ extern "C"
B3_SHARED_API int b3CreateCollisionShapeAddCylinder(b3SharedMemoryCommandHandle commandHandle, double radius, double height);
B3_SHARED_API int b3CreateCollisionShapeAddPlane(b3SharedMemoryCommandHandle commandHandle, const double planeNormal[/*3*/], double planeConstant);
B3_SHARED_API int b3CreateCollisionShapeAddMesh(b3SharedMemoryCommandHandle commandHandle, const char* fileName, const double meshScale[/*3*/]);
B3_SHARED_API int b3CreateCollisionShapeAddConvexMesh(b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], const double* vertices, int numVertices);
B3_SHARED_API int b3CreateCollisionShapeAddConcaveMesh(b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], const double* vertices, int numVertices, const int* indices, int numIndices);
B3_SHARED_API int b3CreateCollisionShapeAddConvexMesh(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], const double* vertices, int numVertices);
B3_SHARED_API int b3CreateCollisionShapeAddConcaveMesh(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], const double* vertices, int numVertices, const int* indices, int numIndices);
B3_SHARED_API void b3CreateCollisionSetFlag(b3SharedMemoryCommandHandle commandHandle, int shapeIndex, int flags);
B3_SHARED_API void b3CreateCollisionShapeSetChildTransform(b3SharedMemoryCommandHandle commandHandle, int shapeIndex, const double childPosition[/*3*/], const double childOrientation[/*4*/]);
B3_SHARED_API int b3GetStatusCollisionShapeUniqueId(b3SharedMemoryStatusHandle statusHandle);

View File

@@ -4215,6 +4215,17 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str
if (clientCmd.m_createUserShapeArgs.m_shapes[i].m_numVertices)
{
int numVertices = clientCmd.m_createUserShapeArgs.m_shapes[i].m_numVertices;
int numIndices = clientCmd.m_createUserShapeArgs.m_shapes[i].m_numIndices;
//int totalUploadSizeInBytes = numVertices * sizeof(double) * 3 + numIndices * sizeof(int);
char* data = bufferServerToClient;
double* vertexUpload = (double*)data;
int* indexUpload = (int*)(data + numVertices * sizeof(double)*3);
if (compound == 0)
{
compound = worldImporter->createCompoundShape();
@@ -4231,19 +4242,19 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str
for (int j = 0; j < clientCmd.m_createUserShapeArgs.m_shapes[i].m_numIndices / 3; j++)
{
int i0 = clientCmd.m_createUserShapeArgs.m_shapes[i].m_indices[j*3+0];
int i1 = clientCmd.m_createUserShapeArgs.m_shapes[i].m_indices[j*3+1];
int i2 = clientCmd.m_createUserShapeArgs.m_shapes[i].m_indices[j*3+2];
int i0 = indexUpload[j*3+0];
int i1 = indexUpload[j*3+1];
int i2 = indexUpload[j*3+2];
btVector3 v0( clientCmd.m_createUserShapeArgs.m_shapes[i].m_vertices[i0*3+0],
clientCmd.m_createUserShapeArgs.m_shapes[i].m_vertices[i0*3+1],
clientCmd.m_createUserShapeArgs.m_shapes[i].m_vertices[i0*3+2]);
btVector3 v1( clientCmd.m_createUserShapeArgs.m_shapes[i].m_vertices[i1*3+0],
clientCmd.m_createUserShapeArgs.m_shapes[i].m_vertices[i1*3+1],
clientCmd.m_createUserShapeArgs.m_shapes[i].m_vertices[i1*3+2]);
btVector3 v2( clientCmd.m_createUserShapeArgs.m_shapes[i].m_vertices[i2*3+0],
clientCmd.m_createUserShapeArgs.m_shapes[i].m_vertices[i2*3+1],
clientCmd.m_createUserShapeArgs.m_shapes[i].m_vertices[i2*3+2]);
btVector3 v0(vertexUpload[i0*3+0],
vertexUpload[i0*3+1],
vertexUpload[i0*3+2]);
btVector3 v1(vertexUpload[i1*3+0],
vertexUpload[i1*3+1],
vertexUpload[i1*3+2]);
btVector3 v2(vertexUpload[i2*3+0],
vertexUpload[i2*3+1],
vertexUpload[i2*3+2]);
meshInterface->addTriangle(v0, v1, v2);
}
}
@@ -4274,9 +4285,9 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str
for (int v = 0; v < clientCmd.m_createUserShapeArgs.m_shapes[i].m_numVertices; v++)
{
btVector3 pt( clientCmd.m_createUserShapeArgs.m_shapes[i].m_vertices[v*3+0],
clientCmd.m_createUserShapeArgs.m_shapes[i].m_vertices[v*3+1],
clientCmd.m_createUserShapeArgs.m_shapes[i].m_vertices[v*3+2]);
btVector3 pt(vertexUpload[v*3+0],
vertexUpload[v*3+1],
vertexUpload[v*3+2]);
convexHull->addPoint(pt, false);
}

View File

@@ -928,9 +928,7 @@ struct b3CreateUserShapeData
int m_collisionFlags;
int m_visualFlags;
int m_numVertices;
double m_vertices[B3_MAX_NUM_VERTICES*3];
int m_numIndices;
int m_indices[B3_MAX_NUM_INDICES];
double m_rgbaColor[4];
double m_specularColor[3];
};

View File

@@ -941,8 +941,19 @@ enum eFileIOTypes
eInMemoryFileIO,
};
//limits for vertices/indices in PyBullet::createCollisionShape
#define B3_MAX_NUM_VERTICES 16
#define B3_MAX_NUM_INDICES 16
//Make sure the data fits in SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE
//(numVertices*sizeof(double)*3 + numIndices*sizeof(int)) < SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE
#ifdef __APPLE__
#define B3_MAX_NUM_VERTICES 8192
#define B3_MAX_NUM_INDICES 32768
#else
#define B3_MAX_NUM_VERTICES 131072
#define B3_MAX_NUM_INDICES 524288
#endif
#endif //SHARED_MEMORY_PUBLIC_H