PyBullet: allow createVisualShape to pass vertices, indices, normals and uv coordinates. This can be combined with changeVisualShape to set the texture.
This commit is contained in:
@@ -1377,6 +1377,9 @@ B3_SHARED_API int b3CreateCollisionShapeAddConcaveMesh(b3PhysicsClientHandle phy
|
||||
{
|
||||
indexUpload[i]=indices[i];
|
||||
}
|
||||
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_numNormals = 0;
|
||||
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_numUVs = 0;
|
||||
|
||||
command->m_createUserShapeArgs.m_numUserShapes++;
|
||||
cl->uploadBulletFileToSharedMemory(data, totalUploadSizeInBytes);
|
||||
delete [] data;
|
||||
@@ -1386,6 +1389,82 @@ B3_SHARED_API int b3CreateCollisionShapeAddConcaveMesh(b3PhysicsClientHandle phy
|
||||
return -1;
|
||||
}
|
||||
|
||||
B3_SHARED_API int b3CreateVisualShapeAddMesh2(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], const double* vertices, int numVertices, const int* indices, int numIndices, const double* normals, int numNormals, const double* uvs, int numUVs)
|
||||
{
|
||||
if (numUVs == 0 && numNormals == 0)
|
||||
{
|
||||
return b3CreateCollisionShapeAddConcaveMesh(physClient, commandHandle, meshScale, vertices, numVertices, indices, 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));
|
||||
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;
|
||||
|
||||
int totalUploadSizeInBytes = numVertices * sizeof(double) * 3 + numIndices * sizeof(int) + numNormals*sizeof(double)*3+numUVs*sizeof(double)*2;
|
||||
char* data = new char[totalUploadSizeInBytes];
|
||||
double* vertexUpload = (double*)data;
|
||||
int* indexUpload = (int*)(data + numVertices * sizeof(double) * 3);
|
||||
double* normalUpload = (double*)(data + numVertices * sizeof(double) * 3 + numIndices * sizeof(int));
|
||||
double* uvUpload = (double*)(data + numVertices * sizeof(double) * 3 + numIndices * sizeof(int)+ numNormals * sizeof(double) * 3);
|
||||
for (i = 0; i<numVertices; i++)
|
||||
{
|
||||
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;
|
||||
|
||||
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_numIndices = numIndices;
|
||||
for (i = 0; i<numIndices; i++)
|
||||
{
|
||||
indexUpload[i] = indices[i];
|
||||
}
|
||||
|
||||
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_numNormals = numNormals;
|
||||
for (i = 0; i < numNormals; i++)
|
||||
{
|
||||
normalUpload[i * 3 + 0] = normals[i * 3 + 0];
|
||||
normalUpload[i * 3 + 1] = normals[i * 3 + 1];
|
||||
normalUpload[i * 3 + 2] = normals[i * 3 + 2];
|
||||
}
|
||||
|
||||
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_numUVs = numUVs;
|
||||
for (i = 0; i < numUVs; i++)
|
||||
{
|
||||
uvUpload[i * 2 + 0] = uvs[i * 2 + 0];
|
||||
uvUpload[i * 2 + 1] = uvs[i * 2 + 1];
|
||||
}
|
||||
command->m_createUserShapeArgs.m_numUserShapes++;
|
||||
cl->uploadBulletFileToSharedMemory(data, totalUploadSizeInBytes);
|
||||
delete[] data;
|
||||
return shapeIndex;
|
||||
}
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
|
||||
|
||||
B3_SHARED_API int b3CreateVisualShapeAddMesh(b3SharedMemoryCommandHandle commandHandle, const char* fileName, const double meshScale[/*3*/])
|
||||
{
|
||||
return b3CreateCollisionShapeAddMesh(commandHandle, fileName, meshScale);
|
||||
|
||||
@@ -486,6 +486,9 @@ extern "C"
|
||||
B3_SHARED_API int b3CreateVisualShapeAddCylinder(b3SharedMemoryCommandHandle commandHandle, double radius, double height);
|
||||
B3_SHARED_API int b3CreateVisualShapeAddPlane(b3SharedMemoryCommandHandle commandHandle, const double planeNormal[/*3*/], double planeConstant);
|
||||
B3_SHARED_API int b3CreateVisualShapeAddMesh(b3SharedMemoryCommandHandle commandHandle, const char* fileName, const double meshScale[/*3*/]);
|
||||
B3_SHARED_API int b3CreateVisualShapeAddMesh2(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], const double* vertices, int numVertices, const int* indices, int numIndices, const double* normals, int numNormals, const double* uvs, int numUVs);
|
||||
|
||||
|
||||
B3_SHARED_API void b3CreateVisualSetFlag(b3SharedMemoryCommandHandle commandHandle, int shapeIndex, int flags);
|
||||
B3_SHARED_API void b3CreateVisualShapeSetChildTransform(b3SharedMemoryCommandHandle commandHandle, int shapeIndex, const double childPosition[/*3*/], const double childOrientation[/*4*/]);
|
||||
B3_SHARED_API void b3CreateVisualShapeSetSpecularColor(b3SharedMemoryCommandHandle commandHandle, int shapeIndex, const double specularColor[/*3*/]);
|
||||
|
||||
@@ -2520,7 +2520,8 @@ struct ProgrammaticUrdfInterface : public URDFImporterInterface
|
||||
if (m_data->m_pluginManager.getRenderInterface())
|
||||
{
|
||||
CommonFileIOInterface* fileIO = m_data->m_pluginManager.getFileIOInterface();
|
||||
m_data->m_pluginManager.getRenderInterface()->convertVisualShapes(linkIndex, pathPrefix, localInertiaFrame, &link, &model, colObj->getBroadphaseHandle()->getUid(), bodyUniqueId, fileIO);
|
||||
int visualShapeUniqueid = m_data->m_pluginManager.getRenderInterface()->convertVisualShapes(linkIndex, pathPrefix, localInertiaFrame, &link, &model, colObj->getBroadphaseHandle()->getUid(), bodyUniqueId, fileIO);
|
||||
colObj->setUserIndex3(visualShapeUniqueid);
|
||||
}
|
||||
}
|
||||
virtual void setBodyUniqueId(int bodyId)
|
||||
@@ -4706,18 +4707,68 @@ bool PhysicsServerCommandProcessor::processCreateVisualShapeCommand(const struct
|
||||
case URDF_GEOM_MESH:
|
||||
{
|
||||
std::string fileName = clientCmd.m_createUserShapeArgs.m_shapes[userShapeIndex].m_meshFileName;
|
||||
const std::string& error_message_prefix = "";
|
||||
std::string out_found_filename;
|
||||
int out_type;
|
||||
if (fileIO->findResourcePath(fileName.c_str(), relativeFileName, 1024))
|
||||
if (fileName.length())
|
||||
{
|
||||
b3FileUtils::extractPath(relativeFileName, pathPrefix, 1024);
|
||||
const std::string& error_message_prefix = "";
|
||||
std::string out_found_filename;
|
||||
int out_type;
|
||||
if (fileIO->findResourcePath(fileName.c_str(), relativeFileName, 1024))
|
||||
{
|
||||
b3FileUtils::extractPath(relativeFileName, pathPrefix, 1024);
|
||||
}
|
||||
|
||||
bool foundFile = UrdfFindMeshFile(fileIO, pathPrefix, relativeFileName, error_message_prefix, &out_found_filename, &out_type);
|
||||
if (foundFile)
|
||||
{
|
||||
visualShape.m_geometry.m_meshFileType = out_type;
|
||||
visualShape.m_geometry.m_meshFileName = fileName;
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
visualShape.m_geometry.m_meshFileType = UrdfGeometry::MEMORY_VERTICES;
|
||||
int numVertices = clientCmd.m_createUserShapeArgs.m_shapes[userShapeIndex].m_numVertices;
|
||||
int numIndices = clientCmd.m_createUserShapeArgs.m_shapes[userShapeIndex].m_numIndices;
|
||||
int numUVs = clientCmd.m_createUserShapeArgs.m_shapes[userShapeIndex].m_numUVs;
|
||||
int numNormals = clientCmd.m_createUserShapeArgs.m_shapes[userShapeIndex].m_numNormals;
|
||||
|
||||
bool foundFile = UrdfFindMeshFile(fileIO, pathPrefix, relativeFileName, error_message_prefix, &out_found_filename, &out_type);
|
||||
visualShape.m_geometry.m_meshFileType = out_type;
|
||||
visualShape.m_geometry.m_meshFileName = fileName;
|
||||
if (numVertices > 0 && numIndices >0)
|
||||
{
|
||||
char* data = bufferServerToClient;
|
||||
double* vertexUpload = (double*)data;
|
||||
int* indexUpload = (int*)(data + numVertices * sizeof(double) * 3);
|
||||
double* normalUpload = (double*)(data + numVertices * sizeof(double) * 3 + numIndices * sizeof(int));
|
||||
double* uvUpload = (double*)(data + numVertices * sizeof(double) * 3 + numIndices * sizeof(int)+numNormals*sizeof(double)*3);
|
||||
|
||||
for (int i = 0; i < numIndices; i++)
|
||||
{
|
||||
visualShape.m_geometry.m_indices.push_back(indexUpload[i]);
|
||||
}
|
||||
for (int i = 0; i < numVertices; i++)
|
||||
{
|
||||
btVector3 v0(vertexUpload[i * 3 + 0],
|
||||
vertexUpload[i * 3 + 1],
|
||||
vertexUpload[i * 3 + 2]);
|
||||
visualShape.m_geometry.m_vertices.push_back(v0);
|
||||
}
|
||||
for (int i = 0; i < numNormals; i++)
|
||||
{
|
||||
btVector3 normal(normalUpload[i * 3 + 0],
|
||||
normalUpload[i * 3 + 1],
|
||||
normalUpload[i * 3 + 2]);
|
||||
visualShape.m_geometry.m_normals.push_back(normal);
|
||||
}
|
||||
for (int i = 0; i < numUVs; i++)
|
||||
{
|
||||
btVector3 uv(uvUpload[i * 2 + 0], uvUpload[i * 2 + 1],0);
|
||||
visualShape.m_geometry.m_uvs.push_back(uv);
|
||||
}
|
||||
}
|
||||
}
|
||||
visualShape.m_geometry.m_meshScale.setValue(clientCmd.m_createUserShapeArgs.m_shapes[userShapeIndex].m_meshScale[0],
|
||||
clientCmd.m_createUserShapeArgs.m_shapes[userShapeIndex].m_meshScale[1],
|
||||
clientCmd.m_createUserShapeArgs.m_shapes[userShapeIndex].m_meshScale[2]);
|
||||
|
||||
@@ -932,6 +932,8 @@ struct b3CreateUserShapeData
|
||||
int m_visualFlags;
|
||||
int m_numVertices;
|
||||
int m_numIndices;
|
||||
int m_numUVs;
|
||||
int m_numNormals;
|
||||
double m_rgbaColor[4];
|
||||
double m_specularColor[3];
|
||||
};
|
||||
|
||||
@@ -361,6 +361,49 @@ static void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPa
|
||||
{
|
||||
case UrdfGeometry::MEMORY_VERTICES:
|
||||
{
|
||||
glmesh = new GLInstanceGraphicsShape;
|
||||
// int index = 0;
|
||||
glmesh->m_indices = new b3AlignedObjectArray<int>();
|
||||
glmesh->m_vertices = new b3AlignedObjectArray<GLInstanceVertex>();
|
||||
glmesh->m_vertices->resize(visual->m_geometry.m_vertices.size());
|
||||
glmesh->m_indices->resize(visual->m_geometry.m_indices.size());
|
||||
|
||||
for (int i = 0; i < visual->m_geometry.m_vertices.size(); i++)
|
||||
{
|
||||
glmesh->m_vertices->at(i).xyzw[0] = visual->m_geometry.m_vertices[i].x();
|
||||
glmesh->m_vertices->at(i).xyzw[1] = visual->m_geometry.m_vertices[i].y();
|
||||
glmesh->m_vertices->at(i).xyzw[2] = visual->m_geometry.m_vertices[i].z();
|
||||
glmesh->m_vertices->at(i).xyzw[3] = 1;
|
||||
btVector3 normal(visual->m_geometry.m_vertices[i]);
|
||||
if (visual->m_geometry.m_normals.size() == visual->m_geometry.m_vertices.size())
|
||||
{
|
||||
normal = visual->m_geometry.m_normals[i];
|
||||
}
|
||||
else
|
||||
{
|
||||
normal.safeNormalize();
|
||||
}
|
||||
|
||||
btVector3 uv(0.5, 0.5, 0);
|
||||
if (visual->m_geometry.m_uvs.size() == visual->m_geometry.m_vertices.size())
|
||||
{
|
||||
uv = visual->m_geometry.m_uvs[i];
|
||||
}
|
||||
glmesh->m_vertices->at(i).normal[0] = normal[0];
|
||||
glmesh->m_vertices->at(i).normal[1] = normal[1];
|
||||
glmesh->m_vertices->at(i).normal[2] = normal[2];
|
||||
glmesh->m_vertices->at(i).uv[0] = uv[0];
|
||||
glmesh->m_vertices->at(i).uv[1] = uv[1];
|
||||
|
||||
}
|
||||
for (int i = 0; i < visual->m_geometry.m_indices.size(); i++)
|
||||
{
|
||||
glmesh->m_indices->at(i) = visual->m_geometry.m_indices[i];
|
||||
|
||||
}
|
||||
glmesh->m_numIndices = visual->m_geometry.m_indices.size();
|
||||
glmesh->m_numvertices = visual->m_geometry.m_vertices.size();
|
||||
|
||||
break;
|
||||
}
|
||||
case UrdfGeometry::FILE_OBJ:
|
||||
|
||||
Reference in New Issue
Block a user