1 /*
2  Written by Xuchen Han <xuchenhan2015@u.northwestern.edu>
3 
4  Bullet Continuous Collision Detection and Physics Library
5  Copyright (c) 2019 Google Inc. http://bulletphysics.org
6  This software is provided 'as-is', without any express or implied warranty.
7  In no event will the authors be held liable for any damages arising from the use of this software.
8  Permission is granted to anyone to use this software for any purpose,
9  including commercial applications, and to alter it and redistribute it freely,
10  subject to the following restrictions:
11  1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
12  2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
13  3. This notice may not be removed or altered from any source distribution.
14  */
15 
16 /* ====== Overview of the Deformable Algorithm ====== */
17 
18 /*
19 A single step of the deformable body simulation contains the following main components:
20 Call internalStepSimulation multiple times, to achieve 240Hz (4 steps of 60Hz).
21 1. Deformable maintaintenance of rest lengths and volume preservation. Forces only depend on position: Update velocity to a temporary state v_{n+1}^* = v_n + explicit_force * dt / mass, where explicit forces include gravity and elastic forces.
22 2. Detect discrete collisions between rigid and deformable bodies at position x_{n+1}^* = x_n + dt * v_{n+1}^*.
23 
24 3a. Solve all constraints, including LCP. Contact, position correction due to numerical drift, friction, and anchors for deformable.
25     TODO: add option for positional drift correction (using vel_target += erp * pos_error/dt
26 
27 3b. 5 Newton steps (multiple step). Conjugent Gradient solves linear system. Deformable Damping: Then velocities of deformable bodies v_{n+1} are solved in
28         M(v_{n+1} - v_{n+1}^*) = damping_force * dt / mass,
29    by a conjugate gradient solver, where the damping force is implicit and depends on v_{n+1}.
30    Make sure contact constraints are not violated in step b by performing velocity projections as in the paper by Baraff and Witkin https://www.cs.cmu.edu/~baraff/papers/sig98.pdf. Dynamic frictions are treated as a force and added to the rhs of the CG solve, whereas static frictions are treated as constraints similar to contact.
31 4. Position is updated via x_{n+1} = x_n + dt * v_{n+1}.
32 
33 
34 The algorithm also closely resembles the one in http://physbam.stanford.edu/~fedkiw/papers/stanford2008-03.pdf
35  */
36 
37 #include <stdio.h>
38 #include "btDeformableMultiBodyDynamicsWorld.h"
39 #include "DeformableBodyInplaceSolverIslandCallback.h"
40 #include "btDeformableBodySolver.h"
41 #include "LinearMath/btQuickprof.h"
42 #include "btSoftBodyInternals.h"
btDeformableMultiBodyDynamicsWorld(btDispatcher * dispatcher,btBroadphaseInterface * pairCache,btDeformableMultiBodyConstraintSolver * constraintSolver,btCollisionConfiguration * collisionConfiguration,btDeformableBodySolver * deformableBodySolver)43 btDeformableMultiBodyDynamicsWorld::btDeformableMultiBodyDynamicsWorld(btDispatcher* dispatcher, btBroadphaseInterface* pairCache, btDeformableMultiBodyConstraintSolver* constraintSolver, btCollisionConfiguration* collisionConfiguration, btDeformableBodySolver* deformableBodySolver)
44 : btMultiBodyDynamicsWorld(dispatcher, pairCache, (btMultiBodyConstraintSolver*)constraintSolver, collisionConfiguration),
45 m_deformableBodySolver(deformableBodySolver), m_solverCallback(0)
46 {
47 	m_drawFlags = fDrawFlags::Std;
48 	m_drawNodeTree = true;
49 	m_drawFaceTree = false;
50 	m_drawClusterTree = false;
51 	m_sbi.m_broadphase = pairCache;
52 	m_sbi.m_dispatcher = dispatcher;
53 	m_sbi.m_sparsesdf.Initialize();
54 	m_sbi.m_sparsesdf.setDefaultVoxelsz(0.005);
55 	m_sbi.m_sparsesdf.Reset();
56 
57 	m_sbi.air_density = (btScalar)1.2;
58 	m_sbi.water_density = 0;
59 	m_sbi.water_offset = 0;
60 	m_sbi.water_normal = btVector3(0, 0, 0);
61 	m_sbi.m_gravity.setValue(0, -10, 0);
62 	m_internalTime = 0.0;
63 	m_implicit = false;
64 	m_lineSearch = false;
65 	m_selfCollision = true;
66 	m_solverDeformableBodyIslandCallback = new DeformableBodyInplaceSolverIslandCallback(constraintSolver, dispatcher);
67 }
68 
internalSingleStepSimulation(btScalar timeStep)69 void btDeformableMultiBodyDynamicsWorld::internalSingleStepSimulation(btScalar timeStep)
70 {
71     BT_PROFILE("internalSingleStepSimulation");
72     if (0 != m_internalPreTickCallback)
73     {
74         (*m_internalPreTickCallback)(this, timeStep);
75     }
76     reinitialize(timeStep);
77     // add gravity to velocity of rigid and multi bodys
78     applyRigidBodyGravity(timeStep);
79 
80     ///apply gravity and explicit force to velocity, predict motion
81     predictUnconstraintMotion(timeStep);
82 
83     ///perform collision detection
84     btMultiBodyDynamicsWorld::performDiscreteCollisionDetection();
85 
86     if (m_selfCollision)
87     {
88         softBodySelfCollision();
89     }
90 
91     btMultiBodyDynamicsWorld::calculateSimulationIslands();
92 
93     beforeSolverCallbacks(timeStep);
94 
95     ///solve contact constraints and then deformable bodies momemtum equation
96     solveConstraints(timeStep);
97 
98     afterSolverCallbacks(timeStep);
99 
100     integrateTransforms(timeStep);
101 
102     ///update vehicle simulation
103     btMultiBodyDynamicsWorld::updateActions(timeStep);
104 
105     updateActivationState(timeStep);
106     // End solver-wise simulation step
107     // ///////////////////////////////
108 }
109 
updateActivationState(btScalar timeStep)110 void btDeformableMultiBodyDynamicsWorld::updateActivationState(btScalar timeStep)
111 {
112     for (int i = 0; i < m_softBodies.size(); i++)
113     {
114         btSoftBody* psb = m_softBodies[i];
115         psb->updateDeactivation(timeStep);
116         if (psb->wantsSleeping())
117         {
118             if (psb->getActivationState() == ACTIVE_TAG)
119                 psb->setActivationState(WANTS_DEACTIVATION);
120             if (psb->getActivationState() == ISLAND_SLEEPING)
121             {
122                 psb->setZeroVelocity();
123             }
124         }
125         else
126         {
127             if (psb->getActivationState() != DISABLE_DEACTIVATION)
128                 psb->setActivationState(ACTIVE_TAG);
129         }
130     }
131     btMultiBodyDynamicsWorld::updateActivationState(timeStep);
132 }
133 
134 
softBodySelfCollision()135 void btDeformableMultiBodyDynamicsWorld::softBodySelfCollision()
136 {
137     m_deformableBodySolver->updateSoftBodies();
138     for (int i = 0; i < m_softBodies.size(); i++)
139     {
140         btSoftBody* psb = m_softBodies[i];
141         if (psb->isActive())
142         {
143             psb->defaultCollisionHandler(psb);
144         }
145     }
146 }
147 
positionCorrection(btScalar timeStep)148 void btDeformableMultiBodyDynamicsWorld::positionCorrection(btScalar timeStep)
149 {
150     // correct the position of rigid bodies with temporary velocity generated from split impulse
151     btContactSolverInfo infoGlobal;
152     btVector3 zero(0,0,0);
153     for (int i = 0; i < m_nonStaticRigidBodies.size(); ++i)
154     {
155         btRigidBody* rb = m_nonStaticRigidBodies[i];
156         //correct the position/orientation based on push/turn recovery
157         btTransform newTransform;
158         btVector3 pushVelocity = rb->getPushVelocity();
159         btVector3 turnVelocity = rb->getTurnVelocity();
160         if (pushVelocity[0] != 0.f || pushVelocity[1] != 0 || pushVelocity[2] != 0 || turnVelocity[0] != 0.f || turnVelocity[1] != 0 || turnVelocity[2] != 0)
161         {
162             btTransformUtil::integrateTransform(rb->getWorldTransform(), pushVelocity, turnVelocity * infoGlobal.m_splitImpulseTurnErp, timeStep, newTransform);
163             rb->setWorldTransform(newTransform);
164             rb->setPushVelocity(zero);
165             rb->setTurnVelocity(zero);
166         }
167     }
168 }
169 
integrateTransforms(btScalar timeStep)170 void btDeformableMultiBodyDynamicsWorld::integrateTransforms(btScalar timeStep)
171 {
172     BT_PROFILE("integrateTransforms");
173     positionCorrection(timeStep);
174     btMultiBodyDynamicsWorld::integrateTransforms(timeStep);
175     for (int i = 0; i < m_softBodies.size(); ++i)
176     {
177         btSoftBody* psb = m_softBodies[i];
178         for (int j = 0; j < psb->m_nodes.size(); ++j)
179         {
180             btSoftBody::Node& node = psb->m_nodes[j];
181             btScalar maxDisplacement = psb->getWorldInfo()->m_maxDisplacement;
182             btScalar clampDeltaV = maxDisplacement / timeStep;
183             for (int c = 0; c < 3; c++)
184             {
185                 if (node.m_v[c] > clampDeltaV)
186                 {
187                     node.m_v[c] = clampDeltaV;
188                 }
189                 if (node.m_v[c] < -clampDeltaV)
190                 {
191                     node.m_v[c] = -clampDeltaV;
192                 }
193             }
194             node.m_x  =  node.m_x + timeStep * node.m_v;
195             node.m_v -= node.m_vsplit;
196             node.m_vsplit.setZero();
197             node.m_q = node.m_x;
198             node.m_vn = node.m_v;
199         }
200         // enforce anchor constraints
201         for (int j = 0; j < psb->m_deformableAnchors.size();++j)
202         {
203             btSoftBody::DeformableNodeRigidAnchor& a = psb->m_deformableAnchors[j];
204             btSoftBody::Node* n = a.m_node;
205             n->m_x = a.m_cti.m_colObj->getWorldTransform() * a.m_local;
206 
207             // update multibody anchor info
208             if (a.m_cti.m_colObj->getInternalType() == btCollisionObject::CO_FEATHERSTONE_LINK)
209             {
210                 btMultiBodyLinkCollider* multibodyLinkCol = (btMultiBodyLinkCollider*)btMultiBodyLinkCollider::upcast(a.m_cti.m_colObj);
211                 if (multibodyLinkCol)
212                 {
213                     btVector3 nrm;
214                     const btCollisionShape* shp = multibodyLinkCol->getCollisionShape();
215                     const btTransform& wtr = multibodyLinkCol->getWorldTransform();
216                     psb->m_worldInfo->m_sparsesdf.Evaluate(
217                                                       wtr.invXform(n->m_x),
218                                                       shp,
219                                                       nrm,
220                                                       0);
221                     a.m_cti.m_normal = wtr.getBasis() * nrm;
222                     btVector3 normal = a.m_cti.m_normal;
223                     btVector3 t1 = generateUnitOrthogonalVector(normal);
224                     btVector3 t2 = btCross(normal, t1);
225                     btMultiBodyJacobianData jacobianData_normal, jacobianData_t1, jacobianData_t2;
226                     findJacobian(multibodyLinkCol, jacobianData_normal, a.m_node->m_x, normal);
227                     findJacobian(multibodyLinkCol, jacobianData_t1, a.m_node->m_x, t1);
228                     findJacobian(multibodyLinkCol, jacobianData_t2, a.m_node->m_x, t2);
229 
230                     btScalar* J_n = &jacobianData_normal.m_jacobians[0];
231                     btScalar* J_t1 = &jacobianData_t1.m_jacobians[0];
232                     btScalar* J_t2 = &jacobianData_t2.m_jacobians[0];
233 
234                     btScalar* u_n = &jacobianData_normal.m_deltaVelocitiesUnitImpulse[0];
235                     btScalar* u_t1 = &jacobianData_t1.m_deltaVelocitiesUnitImpulse[0];
236                     btScalar* u_t2 = &jacobianData_t2.m_deltaVelocitiesUnitImpulse[0];
237 
238                     btMatrix3x3 rot(normal.getX(), normal.getY(), normal.getZ(),
239                                     t1.getX(), t1.getY(), t1.getZ(),
240                                     t2.getX(), t2.getY(), t2.getZ()); // world frame to local frame
241                     const int ndof = multibodyLinkCol->m_multiBody->getNumDofs() + 6;
242                     btMatrix3x3 local_impulse_matrix = (Diagonal(n->m_im) + OuterProduct(J_n, J_t1, J_t2, u_n, u_t1, u_t2, ndof)).inverse();
243                     a.m_c0 =  rot.transpose() * local_impulse_matrix * rot;
244                     a.jacobianData_normal = jacobianData_normal;
245                     a.jacobianData_t1 = jacobianData_t1;
246                     a.jacobianData_t2 = jacobianData_t2;
247                     a.t1 = t1;
248                     a.t2 = t2;
249                 }
250             }
251         }
252         psb->interpolateRenderMesh();
253     }
254 }
255 
solveConstraints(btScalar timeStep)256 void btDeformableMultiBodyDynamicsWorld::solveConstraints(btScalar timeStep)
257 {
258     // save v_{n+1}^* velocity after explicit forces
259     m_deformableBodySolver->backupVelocity();
260 
261     // set up constraints among multibodies and between multibodies and deformable bodies
262     setupConstraints();
263 
264     // solve contact constraints
265     solveContactConstraints();
266 
267     // set up the directions in which the velocity does not change in the momentum solve
268     m_deformableBodySolver->m_objective->m_projection.setProjection();
269 
270     // for explicit scheme, m_backupVelocity = v_{n+1}^*
271     // for implicit scheme, m_backupVelocity = v_n
272     // Here, set dv = v_{n+1} - v_n for nodes in contact
273     m_deformableBodySolver->setupDeformableSolve(m_implicit);
274 
275     // At this point, dv should be golden for nodes in contact
276     // proceed to solve deformable momentum equation
277     m_deformableBodySolver->solveDeformableConstraints(timeStep);
278 }
279 
setupConstraints()280 void btDeformableMultiBodyDynamicsWorld::setupConstraints()
281 {
282     // set up constraints between multibody and deformable bodies
283     m_deformableBodySolver->setConstraints();
284 
285     // set up constraints among multibodies
286     {
287         sortConstraints();
288         // setup the solver callback
289         btMultiBodyConstraint** sortedMultiBodyConstraints = m_sortedMultiBodyConstraints.size() ? &m_sortedMultiBodyConstraints[0] : 0;
290         btTypedConstraint** constraintsPtr = getNumConstraints() ? &m_sortedConstraints[0] : 0;
291         m_solverDeformableBodyIslandCallback->setup(&m_solverInfo, constraintsPtr, m_sortedConstraints.size(), sortedMultiBodyConstraints, m_sortedMultiBodyConstraints.size(), getDebugDrawer());
292 
293         // build islands
294         m_islandManager->buildIslands(getCollisionWorld()->getDispatcher(), getCollisionWorld());
295     }
296 }
297 
sortConstraints()298 void btDeformableMultiBodyDynamicsWorld::sortConstraints()
299 {
300     m_sortedConstraints.resize(m_constraints.size());
301     int i;
302     for (i = 0; i < getNumConstraints(); i++)
303     {
304         m_sortedConstraints[i] = m_constraints[i];
305     }
306     m_sortedConstraints.quickSort(btSortConstraintOnIslandPredicate2());
307 
308     m_sortedMultiBodyConstraints.resize(m_multiBodyConstraints.size());
309     for (i = 0; i < m_multiBodyConstraints.size(); i++)
310     {
311         m_sortedMultiBodyConstraints[i] = m_multiBodyConstraints[i];
312     }
313     m_sortedMultiBodyConstraints.quickSort(btSortMultiBodyConstraintOnIslandPredicate());
314 }
315 
316 
solveContactConstraints()317 void btDeformableMultiBodyDynamicsWorld::solveContactConstraints()
318 {
319     // process constraints on each island
320     m_islandManager->processIslands(getCollisionWorld()->getDispatcher(), getCollisionWorld(), m_solverDeformableBodyIslandCallback);
321 
322     // process deferred
323     m_solverDeformableBodyIslandCallback->processConstraints();
324     m_constraintSolver->allSolved(m_solverInfo, m_debugDrawer);
325 
326     // write joint feedback
327     {
328         for (int i = 0; i < this->m_multiBodies.size(); i++)
329         {
330             btMultiBody* bod = m_multiBodies[i];
331 
332             bool isSleeping = false;
333 
334             if (bod->getBaseCollider() && bod->getBaseCollider()->getActivationState() == ISLAND_SLEEPING)
335             {
336                 isSleeping = true;
337             }
338             for (int b = 0; b < bod->getNumLinks(); b++)
339             {
340                 if (bod->getLink(b).m_collider && bod->getLink(b).m_collider->getActivationState() == ISLAND_SLEEPING)
341                     isSleeping = true;
342             }
343 
344             if (!isSleeping)
345             {
346                 //useless? they get resized in stepVelocities once again (AND DIFFERENTLY)
347                 m_scratch_r.resize(bod->getNumLinks() + 1);  //multidof? ("Y"s use it and it is used to store qdd)
348                 m_scratch_v.resize(bod->getNumLinks() + 1);
349                 m_scratch_m.resize(bod->getNumLinks() + 1);
350 
351                 if (bod->internalNeedsJointFeedback())
352                 {
353                     if (!bod->isUsingRK4Integration())
354                     {
355                         if (bod->internalNeedsJointFeedback())
356                         {
357                             bool isConstraintPass = true;
358                             bod->computeAccelerationsArticulatedBodyAlgorithmMultiDof(m_solverInfo.m_timeStep, m_scratch_r, m_scratch_v, m_scratch_m, isConstraintPass,
359                                                                                       getSolverInfo().m_jointFeedbackInWorldSpace,
360                                                                                       getSolverInfo().m_jointFeedbackInJointFrame);
361                         }
362                     }
363                 }
364             }
365         }
366     }
367 
368     for (int i = 0; i < this->m_multiBodies.size(); i++)
369     {
370         btMultiBody* bod = m_multiBodies[i];
371         bod->processDeltaVeeMultiDof2();
372     }
373 }
374 
addSoftBody(btSoftBody * body,int collisionFilterGroup,int collisionFilterMask)375 void btDeformableMultiBodyDynamicsWorld::addSoftBody(btSoftBody* body, int collisionFilterGroup, int collisionFilterMask)
376 {
377     m_softBodies.push_back(body);
378 
379     // Set the soft body solver that will deal with this body
380     // to be the world's solver
381     body->setSoftBodySolver(m_deformableBodySolver);
382 
383     btCollisionWorld::addCollisionObject(body,
384                                          collisionFilterGroup,
385                                          collisionFilterMask);
386 }
387 
predictUnconstraintMotion(btScalar timeStep)388 void btDeformableMultiBodyDynamicsWorld::predictUnconstraintMotion(btScalar timeStep)
389 {
390     BT_PROFILE("predictUnconstraintMotion");
391     btMultiBodyDynamicsWorld::predictUnconstraintMotion(timeStep);
392     m_deformableBodySolver->predictMotion(timeStep);
393 }
394 
reinitialize(btScalar timeStep)395 void btDeformableMultiBodyDynamicsWorld::reinitialize(btScalar timeStep)
396 {
397     m_internalTime += timeStep;
398     m_deformableBodySolver->setImplicit(m_implicit);
399     m_deformableBodySolver->setLineSearch(m_lineSearch);
400     m_deformableBodySolver->reinitialize(m_softBodies, timeStep);
401     btDispatcherInfo& dispatchInfo = btMultiBodyDynamicsWorld::getDispatchInfo();
402     dispatchInfo.m_timeStep = timeStep;
403     dispatchInfo.m_stepCount = 0;
404     dispatchInfo.m_debugDraw = btMultiBodyDynamicsWorld::getDebugDrawer();
405     btMultiBodyDynamicsWorld::getSolverInfo().m_timeStep = timeStep;
406 }
407 
408 
debugDrawWorld()409 void btDeformableMultiBodyDynamicsWorld::debugDrawWorld()
410 {
411 
412 	btMultiBodyDynamicsWorld::debugDrawWorld();
413 
414 	for (int i = 0; i < getSoftBodyArray().size(); i++)
415 	{
416 		btSoftBody* psb = (btSoftBody*)getSoftBodyArray()[i];
417 		{
418 			btSoftBodyHelpers::DrawFrame(psb, getDebugDrawer());
419 			btSoftBodyHelpers::Draw(psb, getDebugDrawer(), getDrawFlags());
420 		}
421 	}
422 
423 
424 }
425 
applyRigidBodyGravity(btScalar timeStep)426 void btDeformableMultiBodyDynamicsWorld::applyRigidBodyGravity(btScalar timeStep)
427 {
428     // Gravity is applied in stepSimulation and then cleared here and then applied here and then cleared here again
429     // so that 1) gravity is applied to velocity before constraint solve and 2) gravity is applied in each substep
430     // when there are multiple substeps
431     btMultiBodyDynamicsWorld::applyGravity();
432     // integrate rigid body gravity
433     for (int i = 0; i < m_nonStaticRigidBodies.size(); ++i)
434     {
435         btRigidBody* rb = m_nonStaticRigidBodies[i];
436         rb->integrateVelocities(timeStep);
437     }
438 
439     // integrate multibody gravity
440     {
441         forwardKinematics();
442         clearMultiBodyConstraintForces();
443         {
444             for (int i = 0; i < this->m_multiBodies.size(); i++)
445             {
446                 btMultiBody* bod = m_multiBodies[i];
447 
448                 bool isSleeping = false;
449 
450                 if (bod->getBaseCollider() && bod->getBaseCollider()->getActivationState() == ISLAND_SLEEPING)
451                 {
452                     isSleeping = true;
453                 }
454                 for (int b = 0; b < bod->getNumLinks(); b++)
455                 {
456                     if (bod->getLink(b).m_collider && bod->getLink(b).m_collider->getActivationState() == ISLAND_SLEEPING)
457                         isSleeping = true;
458                 }
459 
460                 if (!isSleeping)
461                 {
462                     m_scratch_r.resize(bod->getNumLinks() + 1);
463                     m_scratch_v.resize(bod->getNumLinks() + 1);
464                     m_scratch_m.resize(bod->getNumLinks() + 1);
465                     bool isConstraintPass = false;
466                     {
467                         if (!bod->isUsingRK4Integration())
468                         {
469                             bod->computeAccelerationsArticulatedBodyAlgorithmMultiDof(m_solverInfo.m_timeStep,
470                                                                                       m_scratch_r, m_scratch_v, m_scratch_m,isConstraintPass,
471                                                                                       getSolverInfo().m_jointFeedbackInWorldSpace,
472                                                                                       getSolverInfo().m_jointFeedbackInJointFrame);
473                         }
474                         else
475                         {
476                             btAssert(" RK4Integration is not supported" );
477                         }
478                     }
479                 }
480             }
481         }
482     }
483     clearGravity();
484 }
485 
clearGravity()486 void btDeformableMultiBodyDynamicsWorld::clearGravity()
487 {
488     BT_PROFILE("btMultiBody clearGravity");
489     // clear rigid body gravity
490     for (int i = 0; i < m_nonStaticRigidBodies.size(); i++)
491     {
492         btRigidBody* body = m_nonStaticRigidBodies[i];
493         if (body->isActive())
494         {
495             body->clearGravity();
496         }
497     }
498     // clear multibody gravity
499     for (int i = 0; i < this->m_multiBodies.size(); i++)
500     {
501         btMultiBody* bod = m_multiBodies[i];
502 
503         bool isSleeping = false;
504 
505         if (bod->getBaseCollider() && bod->getBaseCollider()->getActivationState() == ISLAND_SLEEPING)
506         {
507             isSleeping = true;
508         }
509         for (int b = 0; b < bod->getNumLinks(); b++)
510         {
511             if (bod->getLink(b).m_collider && bod->getLink(b).m_collider->getActivationState() == ISLAND_SLEEPING)
512                 isSleeping = true;
513         }
514 
515         if (!isSleeping)
516         {
517             bod->addBaseForce(-m_gravity * bod->getBaseMass());
518 
519             for (int j = 0; j < bod->getNumLinks(); ++j)
520             {
521                 bod->addLinkForce(j, -m_gravity * bod->getLinkMass(j));
522             }
523         }
524     }
525 }
526 
beforeSolverCallbacks(btScalar timeStep)527 void btDeformableMultiBodyDynamicsWorld::beforeSolverCallbacks(btScalar timeStep)
528 {
529     if (0 != m_internalTickCallback)
530     {
531         (*m_internalTickCallback)(this, timeStep);
532     }
533 
534     if (0 != m_solverCallback)
535     {
536         (*m_solverCallback)(m_internalTime, this);
537     }
538 }
539 
afterSolverCallbacks(btScalar timeStep)540 void btDeformableMultiBodyDynamicsWorld::afterSolverCallbacks(btScalar timeStep)
541 {
542     if (0 != m_solverCallback)
543     {
544         (*m_solverCallback)(m_internalTime, this);
545     }
546 }
547 
addForce(btSoftBody * psb,btDeformableLagrangianForce * force)548 void btDeformableMultiBodyDynamicsWorld::addForce(btSoftBody* psb, btDeformableLagrangianForce* force)
549 {
550     btAlignedObjectArray<btDeformableLagrangianForce*>& forces = m_deformableBodySolver->m_objective->m_lf;
551     bool added = false;
552     for (int i = 0; i < forces.size(); ++i)
553     {
554         if (forces[i]->getForceType() == force->getForceType())
555         {
556             forces[i]->addSoftBody(psb);
557             added = true;
558             break;
559         }
560     }
561     if (!added)
562     {
563         force->addSoftBody(psb);
564         force->setIndices(m_deformableBodySolver->m_objective->getIndices());
565         forces.push_back(force);
566     }
567 }
568 
removeSoftBody(btSoftBody * body)569 void btDeformableMultiBodyDynamicsWorld::removeSoftBody(btSoftBody* body)
570 {
571     m_softBodies.remove(body);
572     btCollisionWorld::removeCollisionObject(body);
573     // force a reinitialize so that node indices get updated.
574     m_deformableBodySolver->reinitialize(m_softBodies, btScalar(-1));
575 }
576 
removeCollisionObject(btCollisionObject * collisionObject)577 void btDeformableMultiBodyDynamicsWorld::removeCollisionObject(btCollisionObject* collisionObject)
578 {
579     btSoftBody* body = btSoftBody::upcast(collisionObject);
580     if (body)
581         removeSoftBody(body);
582     else
583         btDiscreteDynamicsWorld::removeCollisionObject(collisionObject);
584 }
585 
586 
stepSimulation(btScalar timeStep,int maxSubSteps,btScalar fixedTimeStep)587 int btDeformableMultiBodyDynamicsWorld::stepSimulation(btScalar timeStep, int maxSubSteps, btScalar fixedTimeStep)
588 {
589     startProfiling(timeStep);
590 
591     int numSimulationSubSteps = 0;
592 
593     if (maxSubSteps)
594     {
595         //fixed timestep with interpolation
596         m_fixedTimeStep = fixedTimeStep;
597         m_localTime += timeStep;
598         if (m_localTime >= fixedTimeStep)
599         {
600             numSimulationSubSteps = int(m_localTime / fixedTimeStep);
601             m_localTime -= numSimulationSubSteps * fixedTimeStep;
602         }
603     }
604     else
605     {
606         //variable timestep
607         fixedTimeStep = timeStep;
608         m_localTime = m_latencyMotionStateInterpolation ? 0 : timeStep;
609         m_fixedTimeStep = 0;
610         if (btFuzzyZero(timeStep))
611         {
612             numSimulationSubSteps = 0;
613             maxSubSteps = 0;
614         }
615         else
616         {
617             numSimulationSubSteps = 1;
618             maxSubSteps = 1;
619         }
620     }
621 
622     //process some debugging flags
623     if (getDebugDrawer())
624     {
625         btIDebugDraw* debugDrawer = getDebugDrawer();
626         gDisableDeactivation = (debugDrawer->getDebugMode() & btIDebugDraw::DBG_NoDeactivation) != 0;
627     }
628     if (numSimulationSubSteps)
629     {
630         //clamp the number of substeps, to prevent simulation grinding spiralling down to a halt
631         int clampedSimulationSteps = (numSimulationSubSteps > maxSubSteps) ? maxSubSteps : numSimulationSubSteps;
632 
633         saveKinematicState(fixedTimeStep * clampedSimulationSteps);
634 
635         for (int i = 0; i < clampedSimulationSteps; i++)
636         {
637             internalSingleStepSimulation(fixedTimeStep);
638             synchronizeMotionStates();
639         }
640     }
641     else
642     {
643         synchronizeMotionStates();
644     }
645 
646     clearForces();
647 
648 #ifndef BT_NO_PROFILE
649     CProfileManager::Increment_Frame_Counter();
650 #endif  //BT_NO_PROFILE
651 
652     return numSimulationSubSteps;
653 }
654