fix memory issues in btSparseSDF.h
(hash function on structure with uninitialized padding, and Reset not called in destructor) expose sparseSdfVoxelSize in PyBullet.setPhysicsEngineParameter don't call deformable wireframe drawing in the wrong thread/place (it can cause crashes)
This commit is contained in:
committed by
Xuchen Han
parent
4ee788e2af
commit
e5ed15c3b2
27
examples/pybullet/examples/deformable_ball.py
Normal file
27
examples/pybullet/examples/deformable_ball.py
Normal file
@@ -0,0 +1,27 @@
|
||||
import pybullet as p
|
||||
from time import sleep
|
||||
|
||||
physicsClient = p.connect(p.GUI)
|
||||
|
||||
p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD)
|
||||
|
||||
p.setGravity(0, 0, -10)
|
||||
|
||||
planeOrn = [0,0,0,1]#p.getQuaternionFromEuler([0.3,0,0])
|
||||
planeId = p.loadURDF("plane.urdf", [0,0,-2],planeOrn)
|
||||
|
||||
boxId = p.loadURDF("cube.urdf", [0,3,2],useMaximalCoordinates = True)
|
||||
|
||||
ballId = p.loadSoftBody("ball.vtk", basePosition = [0,0,-1], scale = 0.5, mass = 0.1, useNeoHookean = 1, NeoHookeanMu = 20, NeoHookeanLambda = 20, NeoHookeanDamping = 0.001, useSelfCollision = 1, frictionCoeff = .5)
|
||||
p.setPhysicsEngineParameter(sparseSdfVoxelSize=0.25)
|
||||
p.setRealTimeSimulation(1)
|
||||
|
||||
#logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "perf.json")
|
||||
|
||||
while p.isConnected():
|
||||
|
||||
p.setGravity(0,0,-10)
|
||||
sleep(1./240.)
|
||||
|
||||
#p.resetSimulation()
|
||||
#p.stopStateLogging(logId)
|
||||
@@ -12,6 +12,7 @@ planeId = p.loadURDF("plane.urdf", [0,0,-2])
|
||||
boxId = p.loadURDF("cube.urdf", [0,3,2],useMaximalCoordinates = True)
|
||||
|
||||
bunnyId = p.loadSoftBody("torus.vtk", useNeoHookean = 1, NeoHookeanMu = 60, NeoHookeanLambda = 200, NeoHookeanDamping = 0.01, useSelfCollision = 1, frictionCoeff = 0.5)
|
||||
p.setPhysicsEngineParameter(sparseSdfVoxelSize=0.25)
|
||||
p.setRealTimeSimulation(1)
|
||||
|
||||
while p.isConnected():
|
||||
|
||||
@@ -1583,6 +1583,7 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
|
||||
int reportSolverAnalytics = -1;
|
||||
|
||||
double warmStartingFactor = -1;
|
||||
double sparseSdfVoxelSize = -1;
|
||||
|
||||
int physicsClientId = 0;
|
||||
|
||||
@@ -1611,11 +1612,12 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
|
||||
"minimumSolverIslandSize",
|
||||
"reportSolverAnalytics",
|
||||
"warmStartingFactor",
|
||||
"sparseSdfVoxelSize",
|
||||
"physicsClientId", NULL};
|
||||
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiidiiddddiididdiidiidi", kwlist, &fixedTimeStep, &numSolverIterations, &useSplitImpulse, &splitImpulsePenetrationThreshold, &numSubSteps,
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiidiiddddiididdiidiiddi", kwlist, &fixedTimeStep, &numSolverIterations, &useSplitImpulse, &splitImpulsePenetrationThreshold, &numSubSteps,
|
||||
&collisionFilterMode, &contactBreakingThreshold, &maxNumCmdPer1ms, &enableFileCaching, &restitutionVelocityThreshold, &erp, &contactERP, &frictionERP, &enableConeFriction, &deterministicOverlappingPairs, &allowedCcdPenetration, &jointFeedbackMode, &solverResidualThreshold, &contactSlop, &enableSAT, &constraintSolverType, &globalCFM, &minimumSolverIslandSize,
|
||||
&reportSolverAnalytics, &warmStartingFactor, &physicsClientId))
|
||||
&reportSolverAnalytics, &warmStartingFactor, &sparseSdfVoxelSize, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -1740,6 +1742,10 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
|
||||
{
|
||||
b3PhysicsParamSetWarmStartingFactor(command, warmStartingFactor);
|
||||
}
|
||||
if (sparseSdfVoxelSize >= 0)
|
||||
{
|
||||
b3PhysicsParameterSetSparseSdfVoxelSize(command, sparseSdfVoxelSize);
|
||||
}
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user