Bullet Collision Detection & Physics Library
btDeformableMultiBodyDynamicsWorld.cpp
Go to the documentation of this file.
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/*
19A single step of the deformable body simulation contains the following main components:
20Call internalStepSimulation multiple times, to achieve 240Hz (4 steps of 60Hz).
211. 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.
222. Detect discrete collisions between rigid and deformable bodies at position x_{n+1}^* = x_n + dt * v_{n+1}^*.
23
243a. Solve all constraints, including LCP. Contact, position correction due to numerical drift, friction, and anchors for deformable.
25
263b. 5 Newton steps (multiple step). Conjugent Gradient solves linear system. Deformable Damping: Then velocities of deformable bodies v_{n+1} are solved in
27 M(v_{n+1} - v_{n+1}^*) = damping_force * dt / mass,
28 by a conjugate gradient solver, where the damping force is implicit and depends on v_{n+1}.
29 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.
304. Position is updated via x_{n+1} = x_n + dt * v_{n+1}.
31
32
33The algorithm also closely resembles the one in http://physbam.stanford.edu/~fedkiw/papers/stanford2008-03.pdf
34 */
35
36#include <stdio.h>
41#include "btSoftBodyInternals.h"
44 m_deformableBodySolver(deformableBodySolver),
45 m_solverCallback(0)
46{
48 m_drawNodeTree = true;
49 m_drawFaceTree = false;
50 m_drawClusterTree = false;
56
60 m_sbi.water_normal = btVector3(0, 0, 0);
61 m_sbi.m_gravity.setValue(0, -9.8, 0);
62 m_internalTime = 0.0;
63 m_implicit = false;
64 m_lineSearch = false;
65 m_useProjection = false;
68}
69
71{
73}
74
76{
77 BT_PROFILE("internalSingleStepSimulation");
79 {
80 (*m_internalPreTickCallback)(this, timeStep);
81 }
82 reinitialize(timeStep);
83
84 // add gravity to velocity of rigid and multi bodys
85 applyRigidBodyGravity(timeStep);
86
89
92
94
95 beforeSolverCallbacks(timeStep);
96
97 // ///solve contact constraints and then deformable bodies momemtum equation
98 solveConstraints(timeStep);
99
100 afterSolverCallbacks(timeStep);
101
103
104 applyRepulsionForce(timeStep);
105
107
108 integrateTransforms(timeStep);
109
112
113 updateActivationState(timeStep);
114 // End solver-wise simulation step
115 // ///////////////////////////////
116}
117
119{
120 for (int i = 0; i < m_softBodies.size(); ++i)
121 {
122 m_softBodies[i]->m_softSoftCollision = true;
123 }
124
125 for (int i = 0; i < m_softBodies.size(); ++i)
126 {
127 for (int j = i; j < m_softBodies.size(); ++j)
128 {
129 m_softBodies[i]->defaultCollisionHandler(m_softBodies[j]);
130 }
131 }
132
133 for (int i = 0; i < m_softBodies.size(); ++i)
134 {
135 m_softBodies[i]->m_softSoftCollision = false;
136 }
137}
138
140{
141 for (int i = 0; i < m_softBodies.size(); i++)
142 {
143 btSoftBody* psb = m_softBodies[i];
144 psb->updateDeactivation(timeStep);
145 if (psb->wantsSleeping())
146 {
147 if (psb->getActivationState() == ACTIVE_TAG)
150 {
151 psb->setZeroVelocity();
152 }
153 }
154 else
155 {
158 }
159 }
161}
162
164{
165 BT_PROFILE("btDeformableMultiBodyDynamicsWorld::applyRepulsionForce");
166 for (int i = 0; i < m_softBodies.size(); i++)
167 {
168 btSoftBody* psb = m_softBodies[i];
169 if (psb->isActive())
170 {
171 psb->applyRepulsionForce(timeStep, true);
172 }
173 }
174}
175
177{
178 BT_PROFILE("btDeformableMultiBodyDynamicsWorld::performGeometricCollisions");
179 // refit the BVH tree for CCD
180 for (int i = 0; i < m_softBodies.size(); ++i)
181 {
182 btSoftBody* psb = m_softBodies[i];
183 if (psb->isActive())
184 {
185 m_softBodies[i]->updateFaceTree(true, false);
186 m_softBodies[i]->updateNodeTree(true, false);
187 for (int j = 0; j < m_softBodies[i]->m_faces.size(); ++j)
188 {
189 btSoftBody::Face& f = m_softBodies[i]->m_faces[j];
190 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);
191 }
192 }
193 }
194
195 // clear contact points & update DBVT
196 for (int r = 0; r < m_ccdIterations; ++r)
197 {
198 for (int i = 0; i < m_softBodies.size(); ++i)
199 {
200 btSoftBody* psb = m_softBodies[i];
201 if (psb->isActive())
202 {
203 // clear contact points in the previous iteration
204 psb->m_faceNodeContactsCCD.clear();
205
206 // update m_q and normals for CCD calculation
207 for (int j = 0; j < psb->m_nodes.size(); ++j)
208 {
209 psb->m_nodes[j].m_q = psb->m_nodes[j].m_x + timeStep * psb->m_nodes[j].m_v;
210 }
211 for (int j = 0; j < psb->m_faces.size(); ++j)
212 {
213 btSoftBody::Face& f = psb->m_faces[j];
214 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);
215 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;
216 }
217 }
218 }
219
220 // apply CCD to register new contact points
221 for (int i = 0; i < m_softBodies.size(); ++i)
222 {
223 for (int j = i; j < m_softBodies.size(); ++j)
224 {
227 if (psb1->isActive() && psb2->isActive())
228 {
229 m_softBodies[i]->geometricCollisionHandler(m_softBodies[j]);
230 }
231 }
232 }
233
234 int penetration_count = 0;
235 for (int i = 0; i < m_softBodies.size(); ++i)
236 {
237 btSoftBody* psb = m_softBodies[i];
238 if (psb->isActive())
239 {
241 ;
242 }
243 }
244 if (penetration_count == 0)
245 {
246 break;
247 }
248
249 // apply inelastic impulse
250 for (int i = 0; i < m_softBodies.size(); ++i)
251 {
252 btSoftBody* psb = m_softBodies[i];
253 if (psb->isActive())
254 {
255 psb->applyRepulsionForce(timeStep, false);
256 }
257 }
258 }
259}
260
262{
263 BT_PROFILE("btDeformableMultiBodyDynamicsWorld::softBodySelfCollision");
264 for (int i = 0; i < m_softBodies.size(); i++)
265 {
266 btSoftBody* psb = m_softBodies[i];
267 if (psb->isActive())
268 {
269 psb->defaultCollisionHandler(psb);
270 }
271 }
272}
273
275{
276 // correct the position of rigid bodies with temporary velocity generated from split impulse
278 btVector3 zero(0, 0, 0);
279 for (int i = 0; i < m_nonStaticRigidBodies.size(); ++i)
280 {
282 //correct the position/orientation based on push/turn recovery
284 btVector3 pushVelocity = rb->getPushVelocity();
285 btVector3 turnVelocity = rb->getTurnVelocity();
286 if (pushVelocity[0] != 0.f || pushVelocity[1] != 0 || pushVelocity[2] != 0 || turnVelocity[0] != 0.f || turnVelocity[1] != 0 || turnVelocity[2] != 0)
287 {
288 btTransformUtil::integrateTransform(rb->getWorldTransform(), pushVelocity, turnVelocity * infoGlobal.m_splitImpulseTurnErp, timeStep, newTransform);
289 rb->setWorldTransform(newTransform);
290 rb->setPushVelocity(zero);
291 rb->setTurnVelocity(zero);
292 }
293 }
294}
295
297{
298 BT_PROFILE("integrateTransforms");
299 positionCorrection(timeStep);
302}
303
305{
306 BT_PROFILE("btDeformableMultiBodyDynamicsWorld::solveConstraints");
307 // save v_{n+1}^* velocity after explicit forces
309
310 // set up constraints among multibodies and between multibodies and deformable bodies
312
313 // solve contact constraints
315
316 // set up the directions in which the velocity does not change in the momentum solve
317 if (m_useProjection)
319 else
321
322 // for explicit scheme, m_backupVelocity = v_{n+1}^*
323 // for implicit scheme, m_backupVelocity = v_n
324 // Here, set dv = v_{n+1} - v_n for nodes in contact
326
327 // At this point, dv should be golden for nodes in contact
328 // proceed to solve deformable momentum equation
330}
331
333{
334 // set up constraints between multibody and deformable bodies
336
337 // set up constraints among multibodies
338 {
340 // setup the solver callback
344
345 // build islands
347 }
348}
349
351{
353 int i;
354 for (i = 0; i < getNumConstraints(); i++)
355 {
357 }
359
361 for (i = 0; i < m_multiBodyConstraints.size(); i++)
362 {
364 }
366}
367
369{
370 // process constraints on each island
372
373 // process deferred
376
377 // write joint feedback
378 {
379 for (int i = 0; i < this->m_multiBodies.size(); i++)
380 {
382
383 bool isSleeping = false;
384
385 if (bod->getBaseCollider() && bod->getBaseCollider()->getActivationState() == ISLAND_SLEEPING)
386 {
387 isSleeping = true;
388 }
389 for (int b = 0; b < bod->getNumLinks(); b++)
390 {
391 if (bod->getLink(b).m_collider && bod->getLink(b).m_collider->getActivationState() == ISLAND_SLEEPING)
392 isSleeping = true;
393 }
394
395 if (!isSleeping)
396 {
397 //useless? they get resized in stepVelocities once again (AND DIFFERENTLY)
398 m_scratch_r.resize(bod->getNumLinks() + 1); //multidof? ("Y"s use it and it is used to store qdd)
399 m_scratch_v.resize(bod->getNumLinks() + 1);
400 m_scratch_m.resize(bod->getNumLinks() + 1);
401
402 if (bod->internalNeedsJointFeedback())
403 {
404 if (!bod->isUsingRK4Integration())
405 {
406 if (bod->internalNeedsJointFeedback())
407 {
408 bool isConstraintPass = true;
409 bod->computeAccelerationsArticulatedBodyAlgorithmMultiDof(m_solverInfo.m_timeStep, m_scratch_r, m_scratch_v, m_scratch_m, isConstraintPass,
410 getSolverInfo().m_jointFeedbackInWorldSpace,
411 getSolverInfo().m_jointFeedbackInJointFrame);
412 }
413 }
414 }
415 }
416 }
417 }
418
419 for (int i = 0; i < this->m_multiBodies.size(); i++)
420 {
422 bod->processDeltaVeeMultiDof2();
423 }
424}
425
427{
429
430 // Set the soft body solver that will deal with this body
431 // to be the world's solver
433
437}
438
440{
441 BT_PROFILE("predictUnconstraintMotion");
444}
445
447{
450}
451
453{
454 m_internalTime += timeStep;
459 dispatchInfo.m_timeStep = timeStep;
460 dispatchInfo.m_stepCount = 0;
463 if (m_useProjection)
464 {
468 }
469 else
470 {
474 }
475}
476
478{
480
481 for (int i = 0; i < getSoftBodyArray().size(); i++)
482 {
484 {
487 }
488 }
489}
490
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
497 // integrate rigid body gravity
498 for (int i = 0; i < m_nonStaticRigidBodies.size(); ++i)
499 {
501 rb->integrateVelocities(timeStep);
502 }
503
504 // integrate multibody gravity
505 {
508 {
509 for (int i = 0; i < this->m_multiBodies.size(); i++)
510 {
512
513 bool isSleeping = false;
514
515 if (bod->getBaseCollider() && bod->getBaseCollider()->getActivationState() == ISLAND_SLEEPING)
516 {
517 isSleeping = true;
518 }
519 for (int b = 0; b < bod->getNumLinks(); b++)
520 {
521 if (bod->getLink(b).m_collider && bod->getLink(b).m_collider->getActivationState() == ISLAND_SLEEPING)
522 isSleeping = true;
523 }
524
525 if (!isSleeping)
526 {
527 m_scratch_r.resize(bod->getNumLinks() + 1);
528 m_scratch_v.resize(bod->getNumLinks() + 1);
529 m_scratch_m.resize(bod->getNumLinks() + 1);
530 bool isConstraintPass = false;
531 {
532 if (!bod->isUsingRK4Integration())
533 {
534 bod->computeAccelerationsArticulatedBodyAlgorithmMultiDof(m_solverInfo.m_timeStep,
536 getSolverInfo().m_jointFeedbackInWorldSpace,
537 getSolverInfo().m_jointFeedbackInJointFrame);
538 }
539 else
540 {
541 btAssert(" RK4Integration is not supported");
542 }
543 }
544 }
545 }
546 }
547 }
548 clearGravity();
549}
550
552{
553 BT_PROFILE("btMultiBody clearGravity");
554 // clear rigid body gravity
555 for (int i = 0; i < m_nonStaticRigidBodies.size(); i++)
556 {
558 if (body->isActive())
559 {
560 body->clearGravity();
561 }
562 }
563 // clear multibody gravity
564 for (int i = 0; i < this->m_multiBodies.size(); i++)
565 {
567
568 bool isSleeping = false;
569
570 if (bod->getBaseCollider() && bod->getBaseCollider()->getActivationState() == ISLAND_SLEEPING)
571 {
572 isSleeping = true;
573 }
574 for (int b = 0; b < bod->getNumLinks(); b++)
575 {
576 if (bod->getLink(b).m_collider && bod->getLink(b).m_collider->getActivationState() == ISLAND_SLEEPING)
577 isSleeping = true;
578 }
579
580 if (!isSleeping)
581 {
582 bod->addBaseForce(-m_gravity * bod->getBaseMass());
583
584 for (int j = 0; j < bod->getNumLinks(); ++j)
585 {
586 bod->addLinkForce(j, -m_gravity * bod->getLinkMass(j));
587 }
588 }
589 }
590}
591
593{
594 if (0 != m_internalTickCallback)
595 {
596 (*m_internalTickCallback)(this, timeStep);
597 }
598
599 if (0 != m_solverCallback)
600 {
601 (*m_solverCallback)(m_internalTime, this);
602 }
603}
604
606{
607 if (0 != m_solverCallback)
608 {
609 (*m_solverCallback)(m_internalTime, this);
610 }
611}
612
614{
616 bool added = false;
617 for (int i = 0; i < forces.size(); ++i)
618 {
619 if (forces[i]->getForceType() == force->getForceType())
620 {
621 forces[i]->addSoftBody(psb);
622 added = true;
623 break;
624 }
625 }
626 if (!added)
627 {
628 force->addSoftBody(psb);
631 }
632}
633
635{
637 int removed_index = -1;
638 for (int i = 0; i < forces.size(); ++i)
639 {
640 if (forces[i]->getForceType() == force->getForceType())
641 {
642 forces[i]->removeSoftBody(psb);
643 if (forces[i]->m_softBodies.size() == 0)
644 removed_index = i;
645 break;
646 }
647 }
648 if (removed_index >= 0)
650}
651
653{
655 for (int i = 0; i < forces.size(); ++i)
656 {
657 forces[i]->removeSoftBody(psb);
658 }
659}
660
662{
664 m_softBodies.remove(body);
666 // force a reinitialize so that node indices get updated.
668}
669
671{
673 if (body)
674 removeSoftBody(body);
675 else
677}
678
680{
681 startProfiling(timeStep);
682
683 int numSimulationSubSteps = 0;
684
685 if (maxSubSteps)
686 {
687 //fixed timestep with interpolation
689 m_localTime += timeStep;
691 {
694 }
695 }
696 else
697 {
698 //variable timestep
699 fixedTimeStep = timeStep;
701 m_fixedTimeStep = 0;
702 if (btFuzzyZero(timeStep))
703 {
705 maxSubSteps = 0;
706 }
707 else
708 {
710 maxSubSteps = 1;
711 }
712 }
713
714 //process some debugging flags
715 if (getDebugDrawer())
716 {
719 }
721 {
722 //clamp the number of substeps, to prevent simulation grinding spiralling down to a halt
724
726
727 for (int i = 0; i < clampedSimulationSteps; i++)
728 {
731 }
732 }
733 else
734 {
736 }
737
738 clearForces();
739
740#ifndef BT_NO_PROFILE
741 CProfileManager::Increment_Frame_Counter();
742#endif //BT_NO_PROFILE
743
745}
#define ACTIVE_TAG
#define DISABLE_DEACTIVATION
#define WANTS_DEACTIVATION
#define ISLAND_SLEEPING
const T & btMax(const T &a, const T &b)
Definition btMinMax.h:27
#define BT_PROFILE(name)
bool gDisableDeactivation
float btScalar
The btScalar type abstracts floating point numbers, to easily switch between double and single floati...
Definition btScalar.h:314
bool btFuzzyZero(btScalar x)
Definition btScalar.h:572
#define btAssert(x)
Definition btScalar.h:153
The btAlignedObjectArray template class uses a subset of the stl::vector interface for its methods It...
int size() const
return the number of elements in the array
void resize(int newsize, const T &fillData=T())
void remove(const T &key)
void quickSort(const L &CompareFunc)
void push_back(const T &_Val)
The btBroadphaseInterface class provides an interface to detect aabb-overlapping object pairs.
btCollisionConfiguration allows to configure Bullet collision detection stack allocator size,...
btCollisionObject can be used to manage collision detection objects.
void setActivationState(int newState) const
int getActivationState() const
btDispatcher * getDispatcher()
btDispatcherInfo & getDispatchInfo()
virtual btIDebugDraw * getDebugDrawer()
virtual void removeCollisionObject(btCollisionObject *collisionObject)
virtual void addCollisionObject(btCollisionObject *collisionObject, int collisionFilterGroup=btBroadphaseProxy::DefaultFilter, int collisionFilterMask=btBroadphaseProxy::AllFilter)
virtual void performDiscreteCollisionDetection()
btIDebugDraw * m_debugDrawer
virtual void allSolved(const btContactSolverInfo &, class btIDebugDraw *)
virtual void solveDeformableConstraints(btScalar solverdt)
virtual void setConstraints(const btContactSolverInfo &infoGlobal)
virtual void applyTransforms(btScalar timeStep)
virtual void setStrainLimiting(bool opt)
virtual void setPreconditioner(int opt)
virtual btAlignedObjectArray< btDeformableLagrangianForce * > * getLagrangianForceArray()
virtual void reinitialize(const btAlignedObjectArray< btSoftBody * > &softBodies, btScalar dt)
virtual void setupDeformableSolve(bool implicit)
void setLineSearch(bool lineSearch)
virtual const btAlignedObjectArray< btSoftBody::Node * > * getIndices()
virtual void predictMotion(btScalar solverdt)
Predict motion of soft bodies into next timestep.
virtual void setGravity(const btVector3 &gravity)
btDeformableMultiBodyDynamicsWorld(btDispatcher *dispatcher, btBroadphaseInterface *pairCache, btDeformableMultiBodyConstraintSolver *constraintSolver, btCollisionConfiguration *collisionConfiguration, btDeformableBodySolver *deformableBodySolver=0)
void removeCollisionObject(btCollisionObject *collisionObject)
removeCollisionObject will first check if it is a rigid body, if so call removeRigidBody otherwise ca...
virtual void addSoftBody(btSoftBody *body, int collisionFilterGroup=btBroadphaseProxy::DefaultFilter, int collisionFilterMask=btBroadphaseProxy::AllFilter)
void addForce(btSoftBody *psb, btDeformableLagrangianForce *force)
void removeForce(btSoftBody *psb, btDeformableLagrangianForce *force)
virtual void internalSingleStepSimulation(btScalar timeStep)
virtual int stepSimulation(btScalar timeStep, int maxSubSteps=1, btScalar fixedTimeStep=btScalar(1.)/btScalar(60.))
if maxSubSteps > 0, it will interpolate motion between fixedTimeStep's
DeformableBodyInplaceSolverIslandCallback * m_solverDeformableBodyIslandCallback
virtual void setGravity(const btVector3 &gravity)
btDeformableBodySolver * m_deformableBodySolver
Solver classes that encapsulate multiple deformable bodies for solving.
void updateActions(btScalar timeStep)
virtual void setGravity(const btVector3 &gravity)
btAlignedObjectArray< btTypedConstraint * > m_sortedConstraints
btSimulationIslandManager * m_islandManager
btAlignedObjectArray< btTypedConstraint * > m_constraints
btAlignedObjectArray< btRigidBody * > m_nonStaticRigidBodies
virtual void removeCollisionObject(btCollisionObject *collisionObject)
removeCollisionObject will first check if it is a rigid body, if so call removeRigidBody otherwise ca...
btConstraintSolver * m_constraintSolver
btCollisionWorld * getCollisionWorld()
void startProfiling(btScalar timeStep)
The btDispatcher interface class can be used in combination with broadphase to dispatch calculations ...
btContactSolverInfo m_solverInfo
btContactSolverInfo & getSolverInfo()
btInternalTickCallback m_internalTickCallback
btInternalTickCallback m_internalPreTickCallback
The btIDebugDraw interface class allows hooking up a debug renderer to visually debug simulations.
The btMultiBodyDynamicsWorld adds Featherstone multi body dynamics to Bullet This implementation is s...
btAlignedObjectArray< btMultiBodyConstraint * > m_multiBodyConstraints
virtual void clearForces()
the forces on each rigidbody is accumulating together with gravity. clear this after each timestep.
virtual void updateActivationState(btScalar timeStep)
btAlignedObjectArray< btMatrix3x3 > m_scratch_m
btAlignedObjectArray< btVector3 > m_scratch_v
virtual void predictUnconstraintMotion(btScalar timeStep)
virtual void integrateTransforms(btScalar timeStep)
btAlignedObjectArray< btMultiBody * > m_multiBodies
btAlignedObjectArray< btScalar > m_scratch_r
btAlignedObjectArray< btMultiBodyConstraint * > m_sortedMultiBodyConstraints
virtual void saveKinematicState(btScalar timeStep)
virtual void applyGravity()
apply gravity, call this once per timestep
The btRigidBody is the main class for rigid body objects.
Definition btRigidBody.h:60
void clearGravity()
void processIslands(btDispatcher *dispatcher, btCollisionWorld *collisionWorld, IslandCallback *callback)
void buildIslands(btDispatcher *dispatcher, btCollisionWorld *colWorld)
The btSoftBody is an class to simulate cloth and volumetric soft bodies.
Definition btSoftBody.h:75
void defaultCollisionHandler(const btCollisionObjectWrapper *pcoWrap)
void setZeroVelocity()
btAlignedObjectArray< DeformableFaceNodeContact > m_faceNodeContactsCCD
Definition btSoftBody.h:828
void setSoftBodySolver(btSoftBodySolver *softBodySolver)
bool wantsSleeping()
void updateDeactivation(btScalar timeStep)
tFaceArray m_faces
Definition btSoftBody.h:817
void applyRepulsionForce(btScalar timeStep, bool applySpringForce)
tNodeArray m_nodes
Definition btSoftBody.h:814
static const btSoftBody * upcast(const btCollisionObject *colObj)
static void integrateTransform(const btTransform &curTrans, const btVector3 &linvel, const btVector3 &angvel, btScalar timeStep, btTransform &predictedTransform)
The btTransform class supports rigid transforms with only translation and rotation and no scaling/she...
Definition btTransform.h:30
TypedConstraint is the baseclass for Bullet constraints and vehicles.
btVector3 can be used to represent 3D points and vectors.
Definition btVector3.h:82
void setValue(const btScalar &_x, const btScalar &_y, const btScalar &_z)
Definition btVector3.h:640
virtual void setup(btContactSolverInfo *solverInfo, btTypedConstraint **sortedConstraints, int numConstraints, btMultiBodyConstraint **sortedMultiBodyConstraints, int numMultiBodyConstraints, btIDebugDraw *debugDrawer)
static void Draw(btSoftBody *psb, btIDebugDraw *idraw, int drawflags=fDrawFlags::Std)
static void DrawFrame(btSoftBody *psb, btIDebugDraw *idraw)
btDispatcher * m_dispatcher
Definition btSoftBody.h:55
btScalar water_density
Definition btSoftBody.h:50
btSparseSdf< 3 > m_sparsesdf
Definition btSoftBody.h:57
btVector3 m_gravity
Definition btSoftBody.h:56
btVector3 water_normal
Definition btSoftBody.h:53
btScalar water_offset
Definition btSoftBody.h:51
btBroadphaseInterface * m_broadphase
Definition btSoftBody.h:54
void setDefaultVoxelsz(btScalar sz)
void Initialize(int hashsize=2383, int clampCells=256 *1024)