mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-14 05:40:05 +00:00
Merge pull request #2968 from xhan0619/implicit-picking
Implicit picking
This commit is contained in:
commit
b09f9eda1d
@ -2,13 +2,13 @@
|
||||
<robot name="torus">
|
||||
<deformable name="torus">
|
||||
<inertial>
|
||||
<mass value="1" />
|
||||
<mass value="3" />
|
||||
<inertia ixx="0.0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" />
|
||||
</inertial>
|
||||
<collision_margin value="0.006"/>
|
||||
<repulsion_stiffness value="800.0"/>
|
||||
<friction value= "0.5"/>
|
||||
<neohookean mu= "60" lambda= "200" damping= "0.01" />
|
||||
<neohookean mu= "180" lambda= "600" damping= "0.01" />
|
||||
<visual filename="torus.vtk"/>
|
||||
</deformable>
|
||||
</robot>
|
||||
|
@ -14,7 +14,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, collisionMargin = 0.006)
|
||||
ballId = p.loadSoftBody("ball.vtk", basePosition = [0,0,-1], scale = 0.5, mass = 4, useNeoHookean = 1, NeoHookeanMu = 400, NeoHookeanLambda = 600, NeoHookeanDamping = 0.001, useSelfCollision = 1, frictionCoeff = .5, collisionMargin = 0.001)
|
||||
p.setTimeStep(0.001)
|
||||
p.setPhysicsEngineParameter(sparseSdfVoxelSize=0.25)
|
||||
p.setRealTimeSimulation(1)
|
||||
|
@ -14,7 +14,7 @@ planeId = p.loadURDF("plane.urdf", [0,0,-2])
|
||||
|
||||
boxId = p.loadURDF("cube.urdf", [0,3,2],useMaximalCoordinates = True)
|
||||
|
||||
bunnyId = p.loadSoftBody("torus.vtk", mass = 1, useNeoHookean = 1, NeoHookeanMu = 60, NeoHookeanLambda = 200, NeoHookeanDamping = 0.01, collisionMargin = 0.006, useSelfCollision = 1, frictionCoeff = 0.5, repulsionStiffness = 800)
|
||||
bunnyId = p.loadSoftBody("torus.vtk", mass = 3, useNeoHookean = 1, NeoHookeanMu = 180, NeoHookeanLambda = 600, NeoHookeanDamping = 0.01, collisionMargin = 0.006, useSelfCollision = 1, frictionCoeff = 0.5, repulsionStiffness = 800)
|
||||
|
||||
bunny2 = p.loadURDF("torus_deform.urdf", [0,1,0], flags=p.URDF_USE_SELF_COLLISION)
|
||||
|
||||
|
@ -86,7 +86,8 @@ void btDeformableBackwardEulerObjective::multiply(const TVStack& x, TVStack& b)
|
||||
{
|
||||
// add damping matrix
|
||||
m_lf[i]->addScaledDampingForceDifferential(-m_dt, x, b);
|
||||
if (m_implicit)
|
||||
// Always integrate picking force implicitly for stability.
|
||||
if (m_implicit || m_lf[i]->getForceType() == BT_MOUSE_PICKING_FORCE)
|
||||
{
|
||||
m_lf[i]->addScaledElasticForceDifferential(-m_dt * m_dt, x, b);
|
||||
}
|
||||
@ -176,7 +177,8 @@ void btDeformableBackwardEulerObjective::computeResidual(btScalar dt, TVStack& r
|
||||
// add implicit force
|
||||
for (int i = 0; i < m_lf.size(); ++i)
|
||||
{
|
||||
if (m_implicit)
|
||||
// Always integrate picking force implicitly for stability.
|
||||
if (m_implicit || m_lf[i]->getForceType() == BT_MOUSE_PICKING_FORCE)
|
||||
{
|
||||
m_lf[i]->addScaledForces(dt, residual);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user