PyBullet: allow to update an existing heightfield shape
Also, use flags = p.GEOM_CONCAVE_INTERNAL_EDGE to enable internal edge filtering for heightfield (disabled by default) See https://github.com/bulletphysics/bullet3/blob/master/examples/pybullet/examples/heightfield.py
This commit is contained in:
@@ -1340,6 +1340,8 @@ B3_SHARED_API int b3CreateCollisionShapeAddHeightfield(b3SharedMemoryCommandHand
|
||||
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_heightfieldTextureScaling = textureScaling;
|
||||
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_numHeightfieldRows = -1;
|
||||
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_numHeightfieldColumns = -1;
|
||||
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_replaceHeightfieldIndex = -1;
|
||||
|
||||
command->m_createUserShapeArgs.m_numUserShapes++;
|
||||
return shapeIndex;
|
||||
}
|
||||
@@ -1347,7 +1349,7 @@ B3_SHARED_API int b3CreateCollisionShapeAddHeightfield(b3SharedMemoryCommandHand
|
||||
return -1;
|
||||
}
|
||||
|
||||
B3_SHARED_API int b3CreateCollisionShapeAddHeightfield2(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], double textureScaling, float* heightfieldData, int numHeightfieldRows, int numHeightfieldColumns)
|
||||
B3_SHARED_API int b3CreateCollisionShapeAddHeightfield2(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], double textureScaling, float* heightfieldData, int numHeightfieldRows, int numHeightfieldColumns, int replaceHeightfieldIndex)
|
||||
{
|
||||
PhysicsClient* cl = (PhysicsClient*)physClient;
|
||||
b3Assert(cl);
|
||||
@@ -1370,6 +1372,8 @@ B3_SHARED_API int b3CreateCollisionShapeAddHeightfield2(b3PhysicsClientHandle ph
|
||||
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_heightfieldTextureScaling = textureScaling;
|
||||
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_numHeightfieldRows = numHeightfieldRows;
|
||||
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_numHeightfieldColumns = numHeightfieldColumns;
|
||||
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_replaceHeightfieldIndex = replaceHeightfieldIndex;
|
||||
|
||||
cl->uploadBulletFileToSharedMemory((const char*)heightfieldData, numHeightfieldRows*numHeightfieldColumns* sizeof(float));
|
||||
command->m_createUserShapeArgs.m_numUserShapes++;
|
||||
return shapeIndex;
|
||||
|
||||
@@ -490,7 +490,7 @@ extern "C"
|
||||
B3_SHARED_API int b3CreateCollisionShapeAddCapsule(b3SharedMemoryCommandHandle commandHandle, double radius, double height);
|
||||
B3_SHARED_API int b3CreateCollisionShapeAddCylinder(b3SharedMemoryCommandHandle commandHandle, double radius, double height);
|
||||
B3_SHARED_API int b3CreateCollisionShapeAddHeightfield(b3SharedMemoryCommandHandle commandHandle, const char* fileName, const double meshScale[/*3*/], double textureScaling);
|
||||
B3_SHARED_API int b3CreateCollisionShapeAddHeightfield2(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], double textureScaling, float* heightfieldData, int numHeightfieldRows, int numHeightfieldColumns);
|
||||
B3_SHARED_API int b3CreateCollisionShapeAddHeightfield2(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], double textureScaling, float* heightfieldData, int numHeightfieldRows, int numHeightfieldColumns, int replaceHeightfieldIndex);
|
||||
|
||||
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*/]);
|
||||
|
||||
@@ -4428,6 +4428,37 @@ static unsigned char* MyGetRawHeightfieldData(CommonFileIOInterface& fileIO, PHY
|
||||
return 0;
|
||||
}
|
||||
|
||||
class MyTriangleCollector4 : public btTriangleCallback
|
||||
{
|
||||
public:
|
||||
btAlignedObjectArray<GLInstanceVertex>* m_pVerticesOut;
|
||||
btAlignedObjectArray<int>* m_pIndicesOut;
|
||||
|
||||
MyTriangleCollector4()
|
||||
{
|
||||
m_pVerticesOut = 0;
|
||||
m_pIndicesOut = 0;
|
||||
}
|
||||
|
||||
virtual void processTriangle(btVector3* tris, int partId, int triangleIndex)
|
||||
{
|
||||
for (int k = 0; k < 3; k++)
|
||||
{
|
||||
GLInstanceVertex v;
|
||||
v.xyzw[3] = 0;
|
||||
v.uv[0] = v.uv[1] = 0.5f;
|
||||
btVector3 normal = (tris[0] - tris[1]).cross(tris[0] - tris[2]);
|
||||
normal.safeNormalize();
|
||||
for (int l = 0; l < 3; l++)
|
||||
{
|
||||
v.xyzw[l] = tris[k][l];
|
||||
v.normal[l] = normal[l];
|
||||
}
|
||||
m_pIndicesOut->push_back(m_pVerticesOut->size());
|
||||
m_pVerticesOut->push_back(v);
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes)
|
||||
{
|
||||
@@ -4571,43 +4602,109 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str
|
||||
if (heightfieldData)
|
||||
{
|
||||
|
||||
btScalar gridSpacing = 0.5;
|
||||
btScalar gridHeightScale = 1. / 256.;
|
||||
//replace heightfield data or create new heightfield
|
||||
if (clientCmd.m_createUserShapeArgs.m_shapes[i].m_replaceHeightfieldIndex >=0)
|
||||
{
|
||||
int collisionShapeUid = clientCmd.m_createUserShapeArgs.m_shapes[i].m_replaceHeightfieldIndex;
|
||||
|
||||
bool flipQuadEdges = false;
|
||||
int upAxis = 2;
|
||||
/*btHeightfieldTerrainShape* heightfieldShape = worldImporter->createHeightfieldShape( width, height,
|
||||
heightfieldData,
|
||||
InternalCollisionShapeHandle* handle = m_data->m_userCollisionShapeHandles.getHandle(collisionShapeUid);
|
||||
if (handle && handle->m_collisionShape && handle->m_collisionShape->getShapeType() == TERRAIN_SHAPE_PROXYTYPE)
|
||||
{
|
||||
btHeightfieldTerrainShape* terrainShape = (btHeightfieldTerrainShape*)handle->m_collisionShape;
|
||||
btScalar* heightfieldDest = (btScalar*)terrainShape->getHeightfieldRawData();
|
||||
//replace the data
|
||||
|
||||
btScalar* datafl = (btScalar*)heightfieldData;
|
||||
|
||||
for (int i = 0; i < width*height; i++)
|
||||
{
|
||||
heightfieldDest[i] = datafl[i];
|
||||
}
|
||||
//update graphics
|
||||
|
||||
btAlignedObjectArray<GLInstanceVertex> gfxVertices;
|
||||
btAlignedObjectArray<int> indices;
|
||||
int strideInBytes = 9 * sizeof(float);
|
||||
|
||||
|
||||
MyTriangleCollector4 col;
|
||||
col.m_pVerticesOut = &gfxVertices;
|
||||
col.m_pIndicesOut = &indices;
|
||||
btVector3 aabbMin, aabbMax;
|
||||
for (int k = 0; k < 3; k++)
|
||||
{
|
||||
aabbMin[k] = -BT_LARGE_FLOAT;
|
||||
aabbMax[k] = BT_LARGE_FLOAT;
|
||||
}
|
||||
terrainShape->processAllTriangles(&col, aabbMin, aabbMax);
|
||||
if (gfxVertices.size() && indices.size())
|
||||
{
|
||||
m_data->m_guiHelper->updateShape(terrainShape->getUserIndex(), &gfxVertices[0].xyzw[0]);
|
||||
}
|
||||
|
||||
terrainShape->clearAccelerator();
|
||||
terrainShape->buildAccelerator();
|
||||
|
||||
|
||||
btTriangleInfoMap* oldTriangleInfoMap = terrainShape->getTriangleInfoMap();
|
||||
delete (oldTriangleInfoMap);
|
||||
terrainShape->setTriangleInfoMap(0);
|
||||
|
||||
if (clientCmd.m_createUserShapeArgs.m_shapes[i].m_collisionFlags & GEOM_CONCAVE_INTERNAL_EDGE)
|
||||
{
|
||||
btTriangleInfoMap* triangleInfoMap = new btTriangleInfoMap();
|
||||
btGenerateInternalEdgeInfo(terrainShape, triangleInfoMap);
|
||||
}
|
||||
serverStatusOut.m_createUserShapeResultArgs.m_userShapeUniqueId = collisionShapeUid;
|
||||
delete worldImporter;
|
||||
serverStatusOut.m_type = CMD_CREATE_COLLISION_SHAPE_COMPLETED;
|
||||
}
|
||||
|
||||
delete heightfieldData;
|
||||
return hasStatus;
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
btScalar gridSpacing = 0.5;
|
||||
btScalar gridHeightScale = 1. / 256.;
|
||||
|
||||
bool flipQuadEdges = false;
|
||||
int upAxis = 2;
|
||||
/*btHeightfieldTerrainShape* heightfieldShape = worldImporter->createHeightfieldShape( width, height,
|
||||
heightfieldData,
|
||||
gridHeightScale,
|
||||
minHeight, maxHeight,
|
||||
upAxis, int(scalarType), flipQuadEdges);
|
||||
*/
|
||||
btHeightfieldTerrainShape* heightfieldShape = new btHeightfieldTerrainShape(width, height,
|
||||
heightfieldData,
|
||||
gridHeightScale,
|
||||
minHeight, maxHeight,
|
||||
upAxis, int(scalarType), flipQuadEdges);
|
||||
*/
|
||||
btHeightfieldTerrainShape* heightfieldShape = new btHeightfieldTerrainShape( width, height,
|
||||
heightfieldData,
|
||||
gridHeightScale,
|
||||
minHeight, maxHeight,
|
||||
upAxis, scalarType, flipQuadEdges);
|
||||
m_data->m_collisionShapes.push_back(heightfieldShape);
|
||||
upAxis, scalarType, flipQuadEdges);
|
||||
m_data->m_collisionShapes.push_back(heightfieldShape);
|
||||
|
||||
heightfieldShape->setUserValue3(clientCmd.m_createUserShapeArgs.m_shapes[i].m_heightfieldTextureScaling);
|
||||
shape = heightfieldShape;
|
||||
if (upAxis == 2)
|
||||
heightfieldShape->setFlipTriangleWinding(true);
|
||||
//buildAccelerator is optional, it may not support all features.
|
||||
heightfieldShape->buildAccelerator();
|
||||
|
||||
// scale the shape
|
||||
btVector3 localScaling(clientCmd.m_createUserShapeArgs.m_shapes[i].m_meshScale[0],
|
||||
clientCmd.m_createUserShapeArgs.m_shapes[i].m_meshScale[1],
|
||||
clientCmd.m_createUserShapeArgs.m_shapes[i].m_meshScale[2]);
|
||||
|
||||
heightfieldShape->setLocalScaling(localScaling);
|
||||
|
||||
btTriangleInfoMap* triangleInfoMap = new btTriangleInfoMap();
|
||||
btGenerateInternalEdgeInfo(heightfieldShape, triangleInfoMap);
|
||||
|
||||
this->m_data->m_heightfieldDatas.push_back(heightfieldData);
|
||||
heightfieldShape->setUserValue3(clientCmd.m_createUserShapeArgs.m_shapes[i].m_heightfieldTextureScaling);
|
||||
shape = heightfieldShape;
|
||||
if (upAxis == 2)
|
||||
heightfieldShape->setFlipTriangleWinding(true);
|
||||
|
||||
// scale the shape
|
||||
btVector3 localScaling(clientCmd.m_createUserShapeArgs.m_shapes[i].m_meshScale[0],
|
||||
clientCmd.m_createUserShapeArgs.m_shapes[i].m_meshScale[1],
|
||||
clientCmd.m_createUserShapeArgs.m_shapes[i].m_meshScale[2]);
|
||||
|
||||
heightfieldShape->setLocalScaling(localScaling);
|
||||
//buildAccelerator is optional, it may not support all features.
|
||||
heightfieldShape->buildAccelerator();
|
||||
|
||||
if (clientCmd.m_createUserShapeArgs.m_shapes[i].m_collisionFlags & GEOM_CONCAVE_INTERNAL_EDGE)
|
||||
{
|
||||
btTriangleInfoMap* triangleInfoMap = new btTriangleInfoMap();
|
||||
btGenerateInternalEdgeInfo(heightfieldShape, triangleInfoMap);
|
||||
}
|
||||
this->m_data->m_heightfieldDatas.push_back(heightfieldData);
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
@@ -127,6 +127,7 @@ enum MultiThreadedGUIHelperCommunicationEnums
|
||||
eGUIHelperChangeTexture,
|
||||
eGUIHelperRemoveTexture,
|
||||
eGUIHelperSetVisualizerFlagCheckRenderedFrame,
|
||||
eGUIHelperUpdateShape,
|
||||
};
|
||||
|
||||
#include <stdio.h>
|
||||
@@ -865,6 +866,18 @@ public:
|
||||
workerThreadWait();
|
||||
}
|
||||
|
||||
int m_updateShapeIndex;
|
||||
float* m_updateShapeVertices;
|
||||
|
||||
virtual void updateShape(int shapeIndex, float* vertices)
|
||||
{
|
||||
m_updateShapeIndex = shapeIndex;
|
||||
m_updateShapeVertices = vertices;
|
||||
|
||||
m_cs->lock();
|
||||
m_cs->setSharedParam(1, eGUIHelperUpdateShape);
|
||||
workerThreadWait();
|
||||
}
|
||||
virtual int registerTexture(const unsigned char* texels, int width, int height)
|
||||
{
|
||||
int* cachedTexture = m_cachedTextureIds[texels];
|
||||
@@ -1916,6 +1929,15 @@ void PhysicsServerExample::updateGraphics()
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
break;
|
||||
}
|
||||
|
||||
case eGUIHelperUpdateShape:
|
||||
{
|
||||
B3_PROFILE("eGUIHelperUpdateShape");
|
||||
m_multiThreadedHelper->m_childGuiHelper->updateShape(m_multiThreadedHelper->m_updateShapeIndex, m_multiThreadedHelper->m_updateShapeVertices);
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
break;
|
||||
}
|
||||
|
||||
case eGUIHelperRegisterGraphicsShape:
|
||||
{
|
||||
B3_PROFILE("eGUIHelperRegisterGraphicsShape");
|
||||
@@ -2039,6 +2061,7 @@ void PhysicsServerExample::updateGraphics()
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
case eGUIHelperSetVisualizerFlagCheckRenderedFrame:
|
||||
{
|
||||
if (m_renderedFrames != m_multiThreadedHelper->m_renderedFrames)
|
||||
|
||||
@@ -965,6 +965,7 @@ struct b3CreateUserShapeData
|
||||
int m_numHeightfieldColumns;
|
||||
double m_rgbaColor[4];
|
||||
double m_specularColor[3];
|
||||
int m_replaceHeightfieldIndex;
|
||||
};
|
||||
|
||||
#define MAX_COMPOUND_COLLISION_SHAPES 16
|
||||
|
||||
Reference in New Issue
Block a user