btDeformableMultiBodyDynamicsWorld.cpp 26 KB

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