diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 92a9746e5..94159893e 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -1642,7 +1642,6 @@ struct PhysicsServerCommandProcessorInternalData btAlignedObjectArray m_lf; #endif - btMultiBodyDynamicsWorld* m_dynamicsWorld; int m_constraintSolverType; @@ -1713,7 +1712,6 @@ struct PhysicsServerCommandProcessorInternalData m_deformablebodySolver(0), #endif m_dynamicsWorld(0), - m_deformablebodySolver(0), m_constraintSolverType(-1), m_remoteDebugDrawer(0), m_stateLoggersUniqueId(0), @@ -8104,7 +8102,7 @@ bool PhysicsServerCommandProcessor::processLoadSoftBodyCommand(const struct Shar { std::vector shapes; tinyobj::attrib_t attribute; - std::string err = tinyobj::LoadObj(attribute, shapes, out_found_filename.c_str(), "", fileIO); + std::string err = tinyobj::LoadObj(attribute, shapes, out_found_sim_filename.c_str(), "", fileIO); if (!shapes.empty()) { const tinyobj::shape_t& shape = shapes[0]; @@ -8153,7 +8151,7 @@ bool PhysicsServerCommandProcessor::processLoadSoftBodyCommand(const struct Shar } #endif } - else if (out_type == UrdfGeometry::FILE_VTK) + else if (out_sim_type == UrdfGeometry::FILE_VTK) { #ifndef SKIP_DEFORMABLE_BODY btDeformableMultiBodyDynamicsWorld* deformWorld = getDeformableWorld(); diff --git a/examples/pybullet/examples/deformable_ball.py b/examples/pybullet/examples/deformable_ball.py index 4ff81b613..279737fa4 100644 --- a/examples/pybullet/examples/deformable_ball.py +++ b/examples/pybullet/examples/deformable_ball.py @@ -13,6 +13,7 @@ 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.setTimeStep(0.001) p.setPhysicsEngineParameter(sparseSdfVoxelSize=0.25) p.setRealTimeSimulation(1) diff --git a/src/BulletSoftBody/btSoftBody.cpp b/src/BulletSoftBody/btSoftBody.cpp index a0d025480..2a458b1d8 100644 --- a/src/BulletSoftBody/btSoftBody.cpp +++ b/src/BulletSoftBody/btSoftBody.cpp @@ -2460,7 +2460,7 @@ bool btSoftBody::checkDeformableFaceContact(const btCollisionObjectWrapper* colO // const btTransform& wtr = colObjWrap->getWorldTransform(); btScalar dst; -#define USE_QUADRATURE 1 +//#define USE_QUADRATURE 1 //#define CACHE_PREV_COLLISION // use the contact position of the previous collision