change reduced deformable example set up in pybullet

This commit is contained in:
Jingyu Chen
2021-12-09 14:21:03 -05:00
parent 578523eab4
commit 1feb81463a
3 changed files with 14 additions and 5 deletions

View File

@@ -2791,7 +2791,14 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld(int flags)
m_data->m_dynamicsWorld->getSolverInfo().m_frictionERP = 0.2; //need to check if there are artifacts with frictionERP
m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.00001;
m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = 50;
m_data->m_dynamicsWorld->getSolverInfo().m_minimumSolverBatchSize = 0;
if (flags & RESET_USE_REDUCED_DEFORMABLE_WORLD)
{
m_data->m_dynamicsWorld->getSolverInfo().m_minimumSolverBatchSize = 128;
}
else
{
m_data->m_dynamicsWorld->getSolverInfo().m_minimumSolverBatchSize = 0;
}
m_data->m_dynamicsWorld->getSolverInfo().m_warmstartingFactor = 0.1;
gDbvtMargin = btScalar(0);
m_data->m_dynamicsWorld->getSolverInfo().m_leastSquaresResidualThreshold = 1e-7;

View File

@@ -14,9 +14,10 @@ p.setGravity(0, 0, -10)
tex = p.loadTexture("uvmap.png")
planeId = p.loadURDF("plane.urdf", [0,0,-2])
# p.startStateLogging(p.STATE_LOGGING_VIDEO_MP4, "reduced_cube.mp4")
boxId = p.loadURDF("cube.urdf", [1,1,10],useMaximalCoordinates = True)
p.startStateLogging(p.STATE_LOGGING_VIDEO_MP4, "reduced_cube.mp4")
cube = p.loadURDF("reduced_cube/reduced_cube.urdf", [1,1,1])
# cube = p.loadURDF("reduced_cube/deform_cube.urdf", [1,1,1])
p.changeVisualShape(cube, -1, rgbaColor=[1,1,1,1], textureUniqueId=tex, flags=0)
p.setPhysicsEngineParameter(sparseSdfVoxelSize=0.25)
p.setRealTimeSimulation(0)

View File

@@ -6,7 +6,6 @@ physicsClient = p.connect(p.GUI)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
# p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD)
p.resetSimulation(p.RESET_USE_REDUCED_DEFORMABLE_WORLD)
p.resetDebugVisualizerCamera(4,-40,-30,[0, 0, 0])
p.setGravity(0, 0, -10)
@@ -14,7 +13,9 @@ p.setGravity(0, 0, -10)
tex = p.loadTexture("uvmap.png")
planeId = p.loadURDF("plane.urdf", [0,0,-2])
# p.startStateLogging(p.STATE_LOGGING_VIDEO_MP4, "reduced_cube.mp4")
boxId = p.loadURDF("cube.urdf", [1,1,3],useMaximalCoordinates = True)
# p.startStateLogging(p.STATE_LOGGING_VIDEO_MP4, "reduced_torus.mp4")
cube = p.loadURDF("reduced_torus/reduced_torus.urdf", [1,1,1])
p.changeVisualShape(cube, -1, rgbaColor=[1,1,1,1], textureUniqueId=tex, flags=0)
p.setPhysicsEngineParameter(sparseSdfVoxelSize=0.25)