PyBullet: allow to pass vertices (for convex) and vertices+indices (for concave) to createCollisionShape

See createObstacleCourse.py for an example use. At the moment a limit of 1024 vertices and 1024 indices.
Will be lifted once we implement the streaming version (soon).
This commit is contained in:
erwincoumans
2018-10-26 10:18:51 -07:00
parent 9c1db5fb34
commit a44df2b0a6
9 changed files with 318 additions and 11 deletions

View File

@@ -1192,6 +1192,92 @@ B3_SHARED_API int b3CreateCollisionShapeAddMesh(b3SharedMemoryCommandHandle comm
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_meshScale[1] = meshScale[1];
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_meshScale[2] = meshScale[2];
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_meshFileType = 0;
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_numVertices = 0;
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_numIndices = 0;
command->m_createUserShapeArgs.m_numUserShapes++;
return shapeIndex;
}
}
return -1;
}
B3_SHARED_API int b3CreateCollisionShapeAddConvexMesh(b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], const double* vertices, int numVertices)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
b3Assert(command);
b3Assert((command->m_type == CMD_CREATE_COLLISION_SHAPE) || (command->m_type == CMD_CREATE_VISUAL_SHAPE));
if ((command->m_type == CMD_CREATE_COLLISION_SHAPE) || (command->m_type == CMD_CREATE_VISUAL_SHAPE))
{
int shapeIndex = command->m_createUserShapeArgs.m_numUserShapes;
if (shapeIndex < MAX_COMPOUND_COLLISION_SHAPES && numVertices >= 0)
{
int i=0;
if (numVertices>B3_MAX_NUM_VERTICES)
numVertices=B3_MAX_NUM_VERTICES;
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_type = GEOM_MESH;
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_collisionFlags = 0;
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_visualFlags = 0;
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_hasChildTransform = 0;
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_meshScale[0] = meshScale[0];
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_meshScale[1] = meshScale[1];
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_meshScale[2] = meshScale[2];
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_meshFileType = 0;
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_meshFileName[0]=0;
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];
}
command->m_createUserShapeArgs.m_numUserShapes++;
return shapeIndex;
}
}
return -1;
}
B3_SHARED_API int b3CreateCollisionShapeAddConcaveMesh(b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], const double* vertices, int numVertices, const int* indices, int numIndices)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
b3Assert(command);
b3Assert((command->m_type == CMD_CREATE_COLLISION_SHAPE) || (command->m_type == CMD_CREATE_VISUAL_SHAPE));
if ((command->m_type == CMD_CREATE_COLLISION_SHAPE) || (command->m_type == CMD_CREATE_VISUAL_SHAPE))
{
int shapeIndex = command->m_createUserShapeArgs.m_numUserShapes;
if (shapeIndex < MAX_COMPOUND_COLLISION_SHAPES && numVertices >= 0 && numIndices >=0)
{
int i=0;
if (numVertices>B3_MAX_NUM_VERTICES)
numVertices=B3_MAX_NUM_VERTICES;
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_type = GEOM_MESH;
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_collisionFlags = GEOM_FORCE_CONCAVE_TRIMESH;
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_visualFlags = 0;
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_hasChildTransform = 0;
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_meshScale[0] = meshScale[0];
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_meshScale[1] = meshScale[1];
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_meshScale[2] = meshScale[2];
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_meshFileType = 0;
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_meshFileName[0]=0;
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_numVertices = numVertices;
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];
}
if (numIndices>B3_MAX_NUM_INDICES)
numIndices = B3_MAX_NUM_INDICES;
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];
}
command->m_createUserShapeArgs.m_numUserShapes++;
return shapeIndex;
}

View File

@@ -460,6 +460,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 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

@@ -4193,6 +4193,80 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str
std::string out_found_filename;
int out_type;
if (clientCmd.m_createUserShapeArgs.m_shapes[i].m_numVertices)
{
if (compound == 0)
{
compound = worldImporter->createCompoundShape();
}
compound->setMargin(m_data->m_defaultCollisionMargin);
if (clientCmd.m_createUserShapeArgs.m_shapes[i].m_numIndices)
{
BT_PROFILE("convert trimesh2");
btTriangleMesh* meshInterface = new btTriangleMesh();
this->m_data->m_meshInterfaces.push_back(meshInterface);
{
BT_PROFILE("convert vertices2");
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];
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]);
meshInterface->addTriangle(v0, v1, v2);
}
}
{
BT_PROFILE("create btBvhTriangleMeshShape");
btBvhTriangleMeshShape* trimesh = new btBvhTriangleMeshShape(meshInterface, true, true);
m_data->m_collisionShapes.push_back(trimesh);
if (clientCmd.m_createUserShapeArgs.m_shapes[i].m_collisionFlags & GEOM_CONCAVE_INTERNAL_EDGE)
{
btTriangleInfoMap* triangleInfoMap = new btTriangleInfoMap();
btGenerateInternalEdgeInfo(trimesh, triangleInfoMap);
}
shape = trimesh;
if (compound)
{
compound->addChildShape(childTransform, shape);
shape->setMargin(m_data->m_defaultCollisionMargin);
}
}
}
else
{
btConvexHullShape* convexHull = worldImporter->createConvexHullShape();
convexHull->setMargin(m_data->m_defaultCollisionMargin);
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]);
convexHull->addPoint(pt, false);
}
convexHull->recalcLocalAabb();
convexHull->optimizeConvexHull();
compound->addChildShape(childTransform, convexHull);
}
urdfColObj.m_geometry.m_meshFileType = UrdfGeometry::MEMORY_VERTICES;
break;
}
bool foundFile = UrdfFindMeshFile(fileIO, pathPrefix, relativeFileName, error_message_prefix, &out_found_filename, &out_type);
if (foundFile)

View File

@@ -38,6 +38,7 @@ typedef unsigned long long int smUint64_t;
#define MAX_NUM_LINKS MAX_DEGREE_OF_FREEDOM
#define MAX_USER_DATA_KEY_LENGTH MAX_URDF_FILENAME_LENGTH
struct TmpFloat3
{
float m_x;
@@ -925,7 +926,10 @@ struct b3CreateUserShapeData
double m_meshScale[3];
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

@@ -7,7 +7,8 @@
//Please don't replace an existing magic number:
//instead, only ADD a new one at the top, comment-out previous one
#define SHARED_MEMORY_MAGIC_NUMBER 2018090300
#define SHARED_MEMORY_MAGIC_NUMBER 201810250
//#define SHARED_MEMORY_MAGIC_NUMBER 201809030
//#define SHARED_MEMORY_MAGIC_NUMBER 201809010
//#define SHARED_MEMORY_MAGIC_NUMBER 201807040
//#define SHARED_MEMORY_MAGIC_NUMBER 201806150
@@ -925,4 +926,8 @@ enum eFileIOTypes
eCNSFileIO,
};
//limits for vertices/indices in PyBullet::createCollisionShape
#define B3_MAX_NUM_VERTICES 1024
#define B3_MAX_NUM_INDICES 1024
#endif //SHARED_MEMORY_PUBLIC_H

View File

@@ -320,6 +320,10 @@ static void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPa
switch (visual->m_geometry.m_meshFileType)
{
case UrdfGeometry::MEMORY_VERTICES:
{
break;
}
case UrdfGeometry::FILE_OBJ:
{
//glmesh = LoadMeshFromObj(fullPath,visualPathPrefix);
@@ -442,8 +446,10 @@ static void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPa
}
default:
// should never get here (findExistingMeshFile returns false if it doesn't recognize extension)
btAssert(0);
{
// should never get here (findExistingMeshFile returns false if it doesn't recognize extension)
btAssert(0);
}
}
if (glmesh && glmesh->m_vertices && (glmesh->m_numvertices > 0))
@@ -458,7 +464,10 @@ static void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPa
}
else
{
b3Warning("issue extracting mesh from COLLADA/STL file %s\n", visual->m_geometry.m_meshFileName.c_str());
if (visual->m_geometry.m_meshFileType !=UrdfGeometry::MEMORY_VERTICES)
{
b3Warning("issue extracting mesh from COLLADA/STL file %s\n", visual->m_geometry.m_meshFileName.c_str());
}
}
break;
} // case mesh