pybullet: allow programmatic creation of heightfield. See https://github.com/erwincoumans/bullet3/tree/master/examples/pybullet/examples/heightfield.py
premake4: allow to build example browser without C++11, re-enable stable PD control plugin using --enable_stable_pd=True
This commit is contained in:
@@ -7,13 +7,39 @@ p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pd.getDataPath())
|
||||
|
||||
textureId = -1
|
||||
useDeepLocoCSV = False
|
||||
|
||||
if useDeepLocoCSV:
|
||||
terrainShape = p.createCollisionShape(shapeType = p.GEOM_HEIGHTFIELD, meshScale=[.5,.5,2.5],fileName = "heightmaps/ground0.txt", heightfieldTextureScaling=128)#Image8x4.png")#wm_height_out.png")
|
||||
useProgrammatic = 0
|
||||
useTerrainFromPNG = 1
|
||||
useDeepLocoCSV = 2
|
||||
|
||||
heightfieldSource = useProgrammatic
|
||||
import random
|
||||
random.seed(10)
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||
heightPerturbationRange = 0.05
|
||||
if heightfieldSource==useProgrammatic:
|
||||
numHeightfieldRows = 256
|
||||
numHeightfieldColumns = 256
|
||||
heightfieldData = [0]*numHeightfieldRows*numHeightfieldColumns
|
||||
for j in range (int(numHeightfieldColumns/2)):
|
||||
for i in range (int(numHeightfieldRows/2) ):
|
||||
height = random.uniform(0,heightPerturbationRange)
|
||||
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
|
||||
|
||||
|
||||
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,[-8,0,-2], [0,0,0,1])
|
||||
else:
|
||||
p.resetBasePositionAndOrientation(terrain,[0,0,0], [0,0,0,1])
|
||||
|
||||
if heightfieldSource==useDeepLocoCSV:
|
||||
terrainShape = p.createCollisionShape(shapeType = p.GEOM_HEIGHTFIELD, meshScale=[.5,.5,2.5],fileName = "heightmaps/ground0.txt", heightfieldTextureScaling=128)
|
||||
terrain = p.createMultiBody(0, terrainShape)
|
||||
p.resetBasePositionAndOrientation(terrain,[0,0,0], [0,0,0,1])
|
||||
|
||||
if heightfieldSource==useTerrainFromPNG:
|
||||
terrainShape = p.createCollisionShape(shapeType = p.GEOM_HEIGHTFIELD, meshScale=[.1,.1,24],fileName = "heightmaps/wm_height_out.png")
|
||||
textureId = p.loadTexture("heightmaps/gimp_overlay_out.png")
|
||||
terrain = p.createMultiBody(0, terrainShape)
|
||||
@@ -78,6 +104,7 @@ for i in range(3):
|
||||
for joint in range(p.getNumJoints(sphereUid)):
|
||||
p.setJointMotorControl2(sphereUid, joint, p.VELOCITY_CONTROL, targetVelocity=1, force=10)
|
||||
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||
p.setGravity(0, 0, -10)
|
||||
p.setRealTimeSimulation(1)
|
||||
|
||||
@@ -85,9 +112,10 @@ p.getNumJoints(sphereUid)
|
||||
for i in range(p.getNumJoints(sphereUid)):
|
||||
p.getJointInfo(sphereUid, i)
|
||||
|
||||
while (1):
|
||||
keys = p.getKeyboardEvents()
|
||||
print(keys)
|
||||
|
||||
while (p.isConnected()):
|
||||
#keys = p.getKeyboardEvents()
|
||||
#print(keys)
|
||||
#getCameraImage note: software/TinyRenderer doesn't render/support heightfields!
|
||||
#p.getCameraImage(320,200, renderer=p.ER_BULLET_HARDWARE_OPENGL)
|
||||
time.sleep(0.01)
|
||||
|
||||
@@ -1,3 +1,4 @@
|
||||
|
||||
#include "../SharedMemory/PhysicsClientC_API.h"
|
||||
#include "../SharedMemory/PhysicsDirectC_API.h"
|
||||
#include "../SharedMemory/SharedMemoryInProcessPhysicsC_API.h"
|
||||
@@ -336,18 +337,19 @@ static PyObject* pybullet_stepSimulation(PyObject* self, PyObject* args, PyObjec
|
||||
struct b3ForwardDynamicsAnalyticsArgs analyticsData;
|
||||
int numIslands = 0;
|
||||
int i;
|
||||
PyObject* val = 0;
|
||||
PyObject* val = 0;
|
||||
PyObject* pyAnalyticsData;
|
||||
|
||||
numIslands = b3GetStatusForwardDynamicsAnalyticsData(statusHandle, &analyticsData);
|
||||
PyObject* pyAnalyticsData = PyTuple_New(numIslands);
|
||||
pyAnalyticsData = PyTuple_New(numIslands);
|
||||
|
||||
for (i=0;i<numIslands;i++)
|
||||
{
|
||||
val = Py_BuildValue("{s:i, s:i, s:i, s:d}",
|
||||
"islandId", analyticsData.m_islandData[i].m_islandId,
|
||||
"numBodies", analyticsData.m_islandData[i].m_numBodies,
|
||||
"numIterationsUsed", analyticsData.m_islandData[i].m_numIterationsUsed,
|
||||
"remainingResidual", analyticsData.m_islandData[i].m_remainingLeastSquaresResidual);
|
||||
val = Py_BuildValue("{s:i, s:i, s:i, s:d}",
|
||||
"islandId", analyticsData.m_islandData[i].m_islandId,
|
||||
"numBodies", analyticsData.m_islandData[i].m_numBodies,
|
||||
"numIterationsUsed", analyticsData.m_islandData[i].m_numIterationsUsed,
|
||||
"remainingResidual", analyticsData.m_islandData[i].m_remainingLeastSquaresResidual);
|
||||
PyTuple_SetItem(pyAnalyticsData, i, val);
|
||||
}
|
||||
|
||||
@@ -7960,6 +7962,7 @@ static int extractIndices(PyObject* indicesObj, int* indices, int maxNumIndices)
|
||||
return numIndicesOut;
|
||||
}
|
||||
|
||||
|
||||
static PyObject* pybullet_createCollisionShape(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
int physicsClientId = 0;
|
||||
@@ -7981,10 +7984,29 @@ static PyObject* pybullet_createCollisionShape(PyObject* self, PyObject* args, P
|
||||
PyObject* halfExtentsObj = 0;
|
||||
PyObject* verticesObj = 0;
|
||||
PyObject* indicesObj = 0;
|
||||
PyObject* heightfieldDataObj = 0;
|
||||
int numHeightfieldRows = -1;
|
||||
int numHeightfieldColumns = -1;
|
||||
|
||||
static char* kwlist[] = {"shapeType", "radius", "halfExtents", "height", "fileName", "meshScale", "planeNormal", "flags", "collisionFramePosition", "collisionFrameOrientation", "vertices", "indices", "heightfieldTextureScaling", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|dOdsOOiOOOOdi", kwlist,
|
||||
&shapeType, &radius, &halfExtentsObj, &height, &fileName, &meshScaleObj, &planeNormalObj, &flags, &collisionFramePositionObj, &collisionFrameOrientationObj, &verticesObj, &indicesObj, &heightfieldTextureScaling, &physicsClientId))
|
||||
static char* kwlist[] = {"shapeType",
|
||||
"radius",
|
||||
"halfExtents",
|
||||
"height",
|
||||
"fileName",
|
||||
"meshScale",
|
||||
"planeNormal",
|
||||
"flags",
|
||||
"collisionFramePosition",
|
||||
"collisionFrameOrientation",
|
||||
"vertices",
|
||||
"indices",
|
||||
"heightfieldTextureScaling",
|
||||
"heightfieldData",
|
||||
"numHeightfieldRows",
|
||||
"numHeightfieldColumns",
|
||||
"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))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -8029,6 +8051,43 @@ static PyObject* pybullet_createCollisionShape(PyObject* self, PyObject* args, P
|
||||
shapeIndex = b3CreateCollisionShapeAddHeightfield(commandHandle, fileName, meshScale, heightfieldTextureScaling);
|
||||
|
||||
}
|
||||
if (shapeType == GEOM_HEIGHTFIELD && fileName==0 && heightfieldDataObj && numHeightfieldColumns>0 && numHeightfieldRows > 0)
|
||||
{
|
||||
if (meshScaleObj)
|
||||
{
|
||||
pybullet_internalSetVectord(meshScaleObj, meshScale);
|
||||
}
|
||||
PyObject* seqPoints = PySequence_Fast(heightfieldDataObj, "expected a sequence");
|
||||
int numHeightfieldPoints = PySequence_Size(heightfieldDataObj);
|
||||
if (numHeightfieldPoints != numHeightfieldColumns*numHeightfieldRows)
|
||||
{
|
||||
PyErr_SetString(SpamError, "Size of heightfieldData doesn't match numHeightfieldColumns*numHeightfieldRows");
|
||||
return NULL;
|
||||
}
|
||||
PyObject* item;
|
||||
int i;
|
||||
float* pointBuffer = (float*)malloc(numHeightfieldPoints*sizeof(float));
|
||||
if (PyList_Check(seqPoints))
|
||||
{
|
||||
for (i = 0; i < numHeightfieldPoints; i++)
|
||||
{
|
||||
item = PyList_GET_ITEM(seqPoints, i);
|
||||
pointBuffer[i] = (float)PyFloat_AsDouble(item);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
for (i = 0; i < numHeightfieldPoints; i++)
|
||||
{
|
||||
item = PyTuple_GET_ITEM(seqPoints, i);
|
||||
pointBuffer[i] = (float)PyFloat_AsDouble(item);
|
||||
}
|
||||
}
|
||||
shapeIndex = b3CreateCollisionShapeAddHeightfield2(sm, commandHandle, meshScale, heightfieldTextureScaling, pointBuffer, numHeightfieldRows, numHeightfieldColumns);
|
||||
free(pointBuffer);
|
||||
if (seqPoints)
|
||||
Py_DECREF(seqPoints);
|
||||
}
|
||||
if (shapeType == GEOM_MESH && fileName)
|
||||
{
|
||||
pybullet_internalSetVectord(meshScaleObj, meshScale);
|
||||
|
||||
Reference in New Issue
Block a user