Increase mesh allocation for vertices/indices in PyBullet.createCollisionShape

See createMesh.py for an example.

The data has to fit in shared memory, hence the limit on Mac is lower than Windows and Linux:

#ifdef __APPLE__
#define B3_MAX_NUM_VERTICES 8192
#define B3_MAX_NUM_INDICES 32768
#else
#define B3_MAX_NUM_VERTICES 131072
#define B3_MAX_NUM_INDICES 524288
#endif
This commit is contained in:
Erwin Coumans
2019-01-03 16:19:28 -08:00
parent 21d9465d94
commit bf9efffa4b
7 changed files with 199 additions and 44 deletions

View File

@@ -0,0 +1,121 @@
import pybullet as p
import time
import math
p.connect(p.GUI)
#don't create a ground plane, to allow for gaps etc
p.resetSimulation()
#p.createCollisionShape(p.GEOM_PLANE)
#p.createMultiBody(0,0)
#p.resetDebugVisualizerCamera(5,75,-26,[0,0,1]);
p.resetDebugVisualizerCamera(15,-346,-16,[-15,0,1]);
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
sphereRadius = 0.05
colSphereId = p.createCollisionShape(p.GEOM_SPHERE,radius=sphereRadius)
#a few different ways to create a mesh:
vertices=[ [-0.246350,-0.246483,-0.000624],
[-0.151407, -0.176325, 0.172867],
[ -0.246350, 0.249205, -0.000624],
[ -0.151407, 0.129477, 0.172867],
[ 0.249338, -0.246483, -0.000624],
[ 0.154395, -0.176325, 0.172867],
[ 0.249338, 0.249205, -0.000624],
[ 0.154395, 0.129477, 0.172867]
]
indices=[0,3,2,
3,6,2,
7,4,6,
5,0,4,
6,0,2,
3,5,7,
0,1,3,
3,7,6,
7,5,4,
5,1,0,
6,4,0,
3,1,5]
#convex mesh from obj
stoneId = p.createCollisionShape(p.GEOM_MESH,vertices=vertices,indices=indices)
boxHalfLength = 0.5
boxHalfWidth = 2.5
boxHalfHeight = 0.1
segmentLength = 5
colBoxId = p.createCollisionShape(p.GEOM_BOX,halfExtents=[boxHalfLength,boxHalfWidth,boxHalfHeight])
mass = 1
visualShapeId = -1
segmentStart = 0
for i in range (segmentLength):
p.createMultiBody(baseMass=0,baseCollisionShapeIndex = colBoxId,basePosition = [segmentStart,0,-0.1])
segmentStart=segmentStart-1
for i in range (segmentLength):
height = 0
if (i%2):
height=1
p.createMultiBody(baseMass=0,baseCollisionShapeIndex = colBoxId,basePosition = [segmentStart,0,-0.1+height])
segmentStart=segmentStart-1
baseOrientation = p.getQuaternionFromEuler([math.pi/2.,0,math.pi/2.])
for i in range (segmentLength):
p.createMultiBody(baseMass=0,baseCollisionShapeIndex = colBoxId,basePosition = [segmentStart,0,-0.1])
segmentStart=segmentStart-1
if (i%2):
p.createMultiBody(baseMass=0,baseCollisionShapeIndex = colBoxId,basePosition = [segmentStart,i%3,-0.1+height+boxHalfWidth],baseOrientation=baseOrientation)
for i in range (segmentLength):
p.createMultiBody(baseMass=0,baseCollisionShapeIndex = colBoxId,basePosition = [segmentStart,0,-0.1])
width=4
for j in range (width):
p.createMultiBody(baseMass=0,baseCollisionShapeIndex = stoneId,basePosition = [segmentStart,0.5*(i%2)+j-width/2.,0])
segmentStart=segmentStart-1
link_Masses=[1]
linkCollisionShapeIndices=[colBoxId]
linkVisualShapeIndices=[-1]
linkPositions=[[0,0,0]]
linkOrientations=[[0,0,0,1]]
linkInertialFramePositions=[[0,0,0]]
linkInertialFrameOrientations=[[0,0,0,1]]
indices=[0]
jointTypes=[p.JOINT_REVOLUTE]
axis=[[1,0,0]]
baseOrientation = [0,0,0,1]
for i in range (segmentLength):
boxId = p.createMultiBody(0,colSphereId,-1,[segmentStart,0,-0.1],baseOrientation,linkMasses=link_Masses,linkCollisionShapeIndices=linkCollisionShapeIndices,linkVisualShapeIndices=linkVisualShapeIndices,linkPositions=linkPositions,linkOrientations=linkOrientations,linkInertialFramePositions=linkInertialFramePositions, linkInertialFrameOrientations=linkInertialFrameOrientations,linkParentIndices=indices,linkJointTypes=jointTypes,linkJointAxis=axis)
p.changeDynamics(boxId,-1,spinningFriction=0.001, rollingFriction=0.001,linearDamping=0.0)
print(p.getNumJoints(boxId))
for joint in range (p.getNumJoints(boxId)):
targetVelocity = 10
if (i%2):
targetVelocity =-10
p.setJointMotorControl2(boxId,joint,p.VELOCITY_CONTROL,targetVelocity=targetVelocity,force=100)
segmentStart=segmentStart-1.1
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
while (1):
camData = p.getDebugVisualizerCamera()
viewMat = camData[2]
projMat = camData[3]
p.getCameraImage(256,256,viewMatrix=viewMat, projectionMatrix=projMat, renderer=p.ER_BULLET_HARDWARE_OPENGL)
keys = p.getKeyboardEvents()
p.stepSimulation()
#print(keys)
time.sleep(0.01)

View File

@@ -6696,9 +6696,12 @@ static int extractVertices(PyObject* verticesObj, double* vertices, int maxNumVe
double vertex[3];
if (pybullet_internalSetVectord(vertexObj, vertex))
{
vertices[numVerticesOut*3+0]=vertex[0];
vertices[numVerticesOut*3+1]=vertex[1];
vertices[numVerticesOut*3+2]=vertex[2];
if (vertices)
{
vertices[numVerticesOut * 3 + 0] = vertex[0];
vertices[numVerticesOut * 3 + 1] = vertex[1];
vertices[numVerticesOut * 3 + 2] = vertex[2];
}
numVerticesOut++;
}
}
@@ -6730,7 +6733,10 @@ static int extractIndices(PyObject* indicesObj, int* indices, int maxNumIndices)
for (i = 0; i < numIndicesSrc; i++)
{
int index = pybullet_internalGetIntFromSequence(seqIndicesObj,i);
indices[numIndicesOut]=index;
if (indices)
{
indices[numIndicesOut] = index;
}
numIndicesOut++;
}
}
@@ -6806,11 +6812,10 @@ static PyObject* pybullet_createCollisionShape(PyObject* self, PyObject* args, P
}
if (shapeType == GEOM_MESH && verticesObj)
{
int numVertices=0;
int numIndices=0;
double vertices[B3_MAX_NUM_VERTICES*3];
int indices[B3_MAX_NUM_INDICES];
int numVertices= extractVertices(verticesObj, 0, B3_MAX_NUM_VERTICES);
int numIndices= extractIndices(indicesObj, 0, B3_MAX_NUM_INDICES);
double* vertices = numVertices ? malloc(numVertices * 3 * sizeof(double)) : 0;
int* indices = numIndices ? malloc(numIndices * sizeof(int)) : 0;
numVertices = extractVertices(verticesObj, vertices, B3_MAX_NUM_VERTICES);
pybullet_internalSetVectord(meshScaleObj, meshScale);
@@ -6822,11 +6827,13 @@ static PyObject* pybullet_createCollisionShape(PyObject* self, PyObject* args, P
if (numIndices)
{
shapeIndex = b3CreateCollisionShapeAddConcaveMesh(commandHandle, meshScale, vertices, numVertices, indices, numIndices);
shapeIndex = b3CreateCollisionShapeAddConcaveMesh(sm, commandHandle, meshScale, vertices, numVertices, indices, numIndices);
} else
{
shapeIndex = b3CreateCollisionShapeAddConvexMesh(commandHandle, meshScale, vertices, numVertices);
shapeIndex = b3CreateCollisionShapeAddConvexMesh(sm, commandHandle, meshScale, vertices, numVertices);
}
free(vertices);
free(indices);
}
if (shapeType == GEOM_PLANE)