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:
@@ -1,6 +1,6 @@
|
||||
import pybullet as p
|
||||
import pybullet_data as pd
|
||||
|
||||
import math
|
||||
import time
|
||||
|
||||
p.connect(p.GUI)
|
||||
@@ -11,6 +11,7 @@ textureId = -1
|
||||
useProgrammatic = 0
|
||||
useTerrainFromPNG = 1
|
||||
useDeepLocoCSV = 2
|
||||
updateHeightfield = False
|
||||
|
||||
heightfieldSource = useProgrammatic
|
||||
import random
|
||||
@@ -30,7 +31,7 @@ if heightfieldSource==useProgrammatic:
|
||||
heightfieldData[2*i+1+(2*j+1)*numHeightfieldRows]=height
|
||||
|
||||
|
||||
terrainShape = p.createCollisionShape(shapeType = p.GEOM_HEIGHTFIELD, meshScale=[.05,.05,1], heightfieldTextureScaling=(numHeightfieldRows-1)/2, heightfieldData=heightfieldData, numHeightfieldRows=numHeightfieldRows, numHeightfieldColumns=numHeightfieldColumns, )
|
||||
terrainShape = p.createCollisionShape(shapeType = p.GEOM_HEIGHTFIELD, meshScale=[.05,.05,1], heightfieldTextureScaling=(numHeightfieldRows-1)/2, heightfieldData=heightfieldData, numHeightfieldRows=numHeightfieldRows, numHeightfieldColumns=numHeightfieldColumns)
|
||||
terrain = p.createMultiBody(0, terrainShape)
|
||||
p.resetBasePositionAndOrientation(terrain,[0,0,0], [0,0,0,1])
|
||||
|
||||
@@ -114,7 +115,23 @@ for i in range(p.getNumJoints(sphereUid)):
|
||||
|
||||
|
||||
while (p.isConnected()):
|
||||
#keys = p.getKeyboardEvents()
|
||||
keys = p.getKeyboardEvents()
|
||||
|
||||
if updateHeightfield and heightfieldSource==useProgrammatic:
|
||||
for j in range (int(numHeightfieldColumns/2)):
|
||||
for i in range (int(numHeightfieldRows/2) ):
|
||||
height = random.uniform(0,heightPerturbationRange)#+math.sin(time.time())
|
||||
heightfieldData[2*i+2*j*numHeightfieldRows]=height
|
||||
heightfieldData[2*i+1+2*j*numHeightfieldRows]=height
|
||||
heightfieldData[2*i+(2*j+1)*numHeightfieldRows]=height
|
||||
heightfieldData[2*i+1+(2*j+1)*numHeightfieldRows]=height
|
||||
#GEOM_CONCAVE_INTERNAL_EDGE may help avoid getting stuck at an internal (shared) edge of the triangle/heightfield.
|
||||
#GEOM_CONCAVE_INTERNAL_EDGE is a bit slower to build though.
|
||||
#flags = p.GEOM_CONCAVE_INTERNAL_EDGE
|
||||
flags = 0
|
||||
terrainShape2 = p.createCollisionShape(shapeType = p.GEOM_HEIGHTFIELD, flags = flags, meshScale=[.05,.05,1], heightfieldTextureScaling=(numHeightfieldRows-1)/2, heightfieldData=heightfieldData, numHeightfieldRows=numHeightfieldRows, numHeightfieldColumns=numHeightfieldColumns, replaceHeightfieldIndex = terrainShape)
|
||||
|
||||
|
||||
#print(keys)
|
||||
#getCameraImage note: software/TinyRenderer doesn't render/support heightfields!
|
||||
#p.getCameraImage(320,200, renderer=p.ER_BULLET_HARDWARE_OPENGL)
|
||||
|
||||
@@ -1,4 +1,4 @@
|
||||
|
||||
//#include "D:/develop/visual_leak_detector/include/vld.h"
|
||||
#include "../SharedMemory/PhysicsClientC_API.h"
|
||||
#include "../SharedMemory/PhysicsDirectC_API.h"
|
||||
#include "../SharedMemory/SharedMemoryInProcessPhysicsC_API.h"
|
||||
@@ -7987,7 +7987,7 @@ static PyObject* pybullet_createCollisionShape(PyObject* self, PyObject* args, P
|
||||
PyObject* heightfieldDataObj = 0;
|
||||
int numHeightfieldRows = -1;
|
||||
int numHeightfieldColumns = -1;
|
||||
|
||||
int replaceHeightfieldIndex = -1;
|
||||
static char* kwlist[] = {"shapeType",
|
||||
"radius",
|
||||
"halfExtents",
|
||||
@@ -8004,9 +8004,10 @@ static PyObject* pybullet_createCollisionShape(PyObject* self, PyObject* args, P
|
||||
"heightfieldData",
|
||||
"numHeightfieldRows",
|
||||
"numHeightfieldColumns",
|
||||
"replaceHeightfieldIndex",
|
||||
"physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|dOdsOOiOOOOdOiii", kwlist,
|
||||
&shapeType, &radius, &halfExtentsObj, &height, &fileName, &meshScaleObj, &planeNormalObj, &flags, &collisionFramePositionObj, &collisionFrameOrientationObj, &verticesObj, &indicesObj, &heightfieldTextureScaling, &heightfieldDataObj, &numHeightfieldRows, &numHeightfieldColumns, &physicsClientId))
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|dOdsOOiOOOOdOiiii", kwlist,
|
||||
&shapeType, &radius, &halfExtentsObj, &height, &fileName, &meshScaleObj, &planeNormalObj, &flags, &collisionFramePositionObj, &collisionFrameOrientationObj, &verticesObj, &indicesObj, &heightfieldTextureScaling, &heightfieldDataObj, &numHeightfieldRows, &numHeightfieldColumns, &replaceHeightfieldIndex, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -8083,7 +8084,8 @@ static PyObject* pybullet_createCollisionShape(PyObject* self, PyObject* args, P
|
||||
pointBuffer[i] = (float)PyFloat_AsDouble(item);
|
||||
}
|
||||
}
|
||||
shapeIndex = b3CreateCollisionShapeAddHeightfield2(sm, commandHandle, meshScale, heightfieldTextureScaling, pointBuffer, numHeightfieldRows, numHeightfieldColumns);
|
||||
shapeIndex = b3CreateCollisionShapeAddHeightfield2(sm, commandHandle, meshScale, heightfieldTextureScaling, pointBuffer, numHeightfieldRows, numHeightfieldColumns, replaceHeightfieldIndex);
|
||||
|
||||
free(pointBuffer);
|
||||
if (seqPoints)
|
||||
Py_DECREF(seqPoints);
|
||||
@@ -8141,7 +8143,10 @@ static PyObject* pybullet_createCollisionShape(PyObject* self, PyObject* args, P
|
||||
{
|
||||
pybullet_internalSetVector4d(collisionFrameOrientationObj, collisionFrameOrientation);
|
||||
}
|
||||
b3CreateCollisionShapeSetChildTransform(commandHandle, shapeIndex, collisionFramePosition, collisionFrameOrientation);
|
||||
if (collisionFramePositionObj || collisionFrameOrientationObj)
|
||||
{
|
||||
b3CreateCollisionShapeSetChildTransform(commandHandle, shapeIndex, collisionFramePosition, collisionFrameOrientation);
|
||||
}
|
||||
}
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
|
||||
Reference in New Issue
Block a user