Convert Figma logo to code with AI

InteractiveComputerGraphics logoPositionBasedDynamics

PositionBasedDynamics is a library for the physically-based simulation of rigid bodies, deformable solids and fluids.

1,893
358
1,893
9

Top Related Projects

3,152

NVIDIA PhysX SDK

12,417

Bullet Physics SDK: real-time collision detection and multi-physics simulation for VR, games, visual effects, robotics, machine learning etc.

17,590

Filament is a real-time physically based rendering engine for Android, iOS, Windows, Linux, macOS, and WebGL2

Tiny Differentiable Simulator is a header-only C++ and CUDA physics library for reinforcement learning and robotics with zero dependencies.

2D physics engine for games

Quick Overview

PositionBasedDynamics is a C++ library for position-based simulation of rigid bodies, deformable solids, and fluids. It implements various position-based methods for real-time physics simulations, focusing on stability and efficiency. The library is designed to be modular and extensible, making it suitable for a wide range of applications in computer graphics and interactive systems.

Pros

  • Efficient and stable simulation of various physical phenomena
  • Modular design allowing easy integration and extension
  • Supports both CPU and GPU-based simulations
  • Well-documented with examples and demos

Cons

  • Steep learning curve for beginners in physics-based simulations
  • Limited built-in rendering capabilities
  • Requires external dependencies for some features
  • May not be suitable for extremely large-scale simulations

Code Examples

  1. Creating a rigid body simulation:
#include "Simulation/SimulationModel.h"
#include "Simulation/CubicSDFCollisionDetection.h"

SimulationModel model;
model.init();
Simulation::CubicSDFCollisionDetection cd;
cd.init(model.getParticles());

// Add rigid bodies and constraints
// ...

// Simulate
const Real h = 0.005;
TimeStepController timeStep;
timeStep.step(model, h);
  1. Adding a cloth simulation:
#include "Simulation/TriangleModel.h"

TriangleModel *cloth = new TriangleModel();
cloth->initMesh(50, 50, 1.0, 1.0);
cloth->updateMeshNormals();
model.addTriangleModel(cloth);

// Add distance constraints
for (unsigned int i = 0; i < cloth->getParticleMesh().numVertices(); i++)
{
    model.addDistanceConstraint(cloth->getParticleMesh().getVertex(i), 0.1);
}
  1. Implementing fluid simulation:
#include "Simulation/SPHKernels.h"

FluidModel *fluid = new FluidModel();
fluid->initModel(10000, Vector3r(0, 0, 0), Vector3r(1, 1, 1));
model.addFluidModel(fluid);

// Set up SPH parameters
fluid->setDensity0(1000);
fluid->setViscosity(0.01);
fluid->setSurfaceTension(0.2);

Getting Started

  1. Clone the repository:

    git clone https://github.com/InteractiveComputerGraphics/PositionBasedDynamics.git
    
  2. Install dependencies (Eigen3, CMake, OpenGL, GLFW)

  3. Build the project:

    mkdir build
    cd build
    cmake ..
    make
    
  4. Run an example:

    ./ClothDemo
    

For more detailed instructions and examples, refer to the documentation in the repository.

Competitor Comparisons

3,152

NVIDIA PhysX SDK

Pros of PhysX

  • More comprehensive and feature-rich physics engine
  • Optimized for GPU acceleration, potentially offering better performance
  • Widely adopted in the game industry with extensive documentation and support

Cons of PhysX

  • Larger codebase and steeper learning curve
  • Less flexibility for customization compared to PositionBasedDynamics
  • Closed-source components may limit certain use cases

Code Comparison

PhysX (C++):

PxRigidDynamic* createDynamic(const PxTransform& t, const PxGeometry& geometry, const PxVec3& velocity=PxVec3(0))
{
    PxRigidDynamic* dynamic = PxCreateDynamic(*gPhysics, t, geometry, *gMaterial, 10.0f);
    dynamic->setAngularDamping(0.5f);
    dynamic->setLinearVelocity(velocity);
    gScene->addActor(*dynamic);
    return dynamic;
}

PositionBasedDynamics (C++):

void initModel()
{
    SimulationModel *model = Simulation::getCurrent()->getModel();
    model->addRigidBody(rb);
    model->addTriangleModel(tm);
    model->setGravity(Eigen::Vector3f(0.0f, -9.81f, 0.0f));
}

Both repositories offer physics simulation capabilities, but PhysX provides a more comprehensive solution with GPU acceleration, while PositionBasedDynamics focuses on a specific simulation technique, offering more flexibility for customization.

12,417

Bullet Physics SDK: real-time collision detection and multi-physics simulation for VR, games, visual effects, robotics, machine learning etc.

Pros of Bullet3

  • More comprehensive physics simulation, including rigid body dynamics, soft body dynamics, and fluid simulation
  • Widely adopted in industry, with extensive documentation and community support
  • Optimized for performance, including GPU acceleration capabilities

Cons of Bullet3

  • Steeper learning curve due to its extensive feature set
  • Heavier resource usage, which may impact performance on lower-end systems
  • More complex integration process for simple projects

Code Comparison

PositionBasedDynamics example:

SimulationModel model;
TimeStepController timeStep;
model.addRigidBody(rb);
timeStep.setTimeStepSize(0.005);
timeStep.step(model);

Bullet3 example:

btDiscreteDynamicsWorld* dynamicsWorld;
btRigidBody* body = createRigidBody(mass, startTransform, shape);
dynamicsWorld->addRigidBody(body);
dynamicsWorld->stepSimulation(1.f/60.f, 10);

PositionBasedDynamics focuses on position-based simulation techniques, offering a simpler API for specific use cases. Bullet3 provides a more comprehensive physics engine with a wider range of features, but requires more setup and configuration. The choice between the two depends on project requirements, performance needs, and desired level of physics complexity.

17,590

Filament is a real-time physically based rendering engine for Android, iOS, Windows, Linux, macOS, and WebGL2

Pros of Filament

  • More comprehensive rendering engine with advanced features like PBR, IBL, and post-processing
  • Cross-platform support for mobile, desktop, and web applications
  • Actively maintained by Google with frequent updates and improvements

Cons of Filament

  • Steeper learning curve due to its complexity and extensive feature set
  • Larger codebase and potentially higher resource requirements
  • Less focused on specific physics simulations compared to PositionBasedDynamics

Code Comparison

PositionBasedDynamics (particle simulation):

Vector3r position = particle.getPosition();
Vector3r velocity = particle.getVelocity();
position += timestep * velocity;
velocity += timestep * acceleration;

Filament (rendering setup):

Engine* engine = Engine::create();
Renderer* renderer = engine->createRenderer();
Scene* scene = engine->createScene();
View* view = engine->createView();
view->setScene(scene);

While PositionBasedDynamics focuses on physics simulations, Filament provides a more comprehensive rendering solution. PositionBasedDynamics is better suited for specific physics-based applications, while Filament offers a broader range of graphics capabilities for various platforms and use cases.

Tiny Differentiable Simulator is a header-only C++ and CUDA physics library for reinforcement learning and robotics with zero dependencies.

Pros of tiny-differentiable-simulator

  • Focuses on differentiable physics simulation, enabling gradient-based optimization and machine learning applications
  • Lightweight and designed for easy integration into other projects
  • Supports a variety of rigid body dynamics and articulated systems

Cons of tiny-differentiable-simulator

  • Less comprehensive feature set compared to PositionBasedDynamics
  • May have a steeper learning curve for users not familiar with differentiable physics concepts
  • Limited documentation and examples compared to PositionBasedDynamics

Code Comparison

PositionBasedDynamics:

Vector3r position = particle.getPosition();
Vector3r velocity = particle.getVelocity();
position += timestep * velocity;
particle.setPosition(position);

tiny-differentiable-simulator:

TinyVector3f position = body.m_position;
TinyVector3f velocity = body.m_velocity;
position += dt * velocity;
body.m_position = position;

Both repositories use similar approaches for basic particle/body updates, but tiny-differentiable-simulator's implementation is geared towards differentiability. PositionBasedDynamics offers a more extensive set of physics-based simulations, while tiny-differentiable-simulator focuses on providing a lightweight, differentiable physics engine for machine learning applications.

2D physics engine for games

Pros of LiquidFun

  • Specialized for fluid and soft body simulations, offering more advanced features in this domain
  • Backed by Google, potentially leading to better long-term support and updates
  • Includes a comprehensive set of demos and examples for easier integration

Cons of LiquidFun

  • Less versatile for general-purpose physics simulations compared to PositionBasedDynamics
  • May have a steeper learning curve due to its focus on fluid dynamics
  • Limited to 2D simulations, while PositionBasedDynamics supports 3D

Code Comparison

PositionBasedDynamics (C++):

Vector3r position = particle.getPosition();
Vector3r velocity = particle.getVelocity();
position += timestep * velocity;
particle.setPosition(position);

LiquidFun (C++):

b2ParticleSystem* particleSystem = world->CreateParticleSystem(&particleSystemDef);
b2ParticleGroupDef pd;
pd.flags = b2_waterParticle;
pd.position.Set(0.0f, 0.0f);
b2ParticleGroup* group = particleSystem->CreateParticleGroup(pd);

Both libraries use C++ for their core implementations. PositionBasedDynamics focuses on general particle-based simulations, while LiquidFun specializes in fluid dynamics with a more complex particle system setup. PositionBasedDynamics offers a more straightforward approach for basic physics simulations, whereas LiquidFun provides more advanced features for fluid-specific scenarios.

Convert Figma logo designs to code with AI

Visual Copilot

Introducing Visual Copilot: A new AI model to turn Figma designs to high quality code using your components.

Try Visual Copilot

README

PositionBasedDynamics

      Documentation Status

This library supports the physically-based simulation of mechanical effects. In the last years position-based simulation methods have become popular in the graphics community. In contrast to classical simulation approaches these methods compute the position changes in each simulation step directly, based on the solution of a quasi-static problem. Therefore, position-based approaches are fast, stable and controllable which make them well-suited for use in interactive environments. However, these methods are generally not as accurate as force-based methods but still provide visual plausibility. Hence, the main application areas of position-based simulation are virtual reality, computer games and special effects in movies and commercials.

The PositionBasedDynamics library allows the position-based handling of many types of constraints in a physically-based simulation. The library uses CMake, Eigen, json, pybind, glfw, hapPLY and imgui (only for the demos). All external dependencies are included.

Furthermore we use our own library:

  • Discregrid to generate cubic signed distance fields for the collision detection

Author: Jan Bender, License: MIT

News

  • We added a Python interface: pyPBD
  • Our new paper about a Direct Position-Based Solver for Stiff Rods uses the PositionBasedDynamics library. You can watch the video here.
  • PBD now has a collision detection based on cubic signed distance fields
  • SPlisHSPlasH is our new open-source fluid simulator which uses the PositionBasedDynamics library to handle rigid-fluid coupling. It can be downloaded here: https://github.com/InteractiveComputerGraphics/SPlisHSPlasH
  • Our new paper about adaptive signed distance fields uses the PositionBasedDynamics library. You can watch the video here.

Documentation

The documentation can be found here:

Forum

On our GitHub discussions page you can ask questions, discuss about simulation topics, and share ideas.

Build Instructions

This project is based on CMake. Simply generate project, Makefiles, etc. using CMake and compile the project with the compiler of your choice. The code was tested with the following configurations:

  • Windows 10 64-bit, CMake 3.9.5, Visual Studio 2019
  • Debian 9 64-bit, CMake 3.12.3, GCC 6.3.0.

Note: Please use a 64-bit target on a 64-bit operating system. 32-bit builds on a 64-bit OS are not supported.

Python Installation Instruction

For Windows and Linux targets there exists prebuilt python wheel files which can be installed using

pip install pypbd

These are available for different Python Versions. See also here: pyPBD. If you do not meet these conditions please refer to the build instructions and to the python binding Getting started guide.

Latest Important Changes

  • GUI is now based on imgui
  • added support of PLY files
  • added Python binding
  • added some XPBD constraints
  • added OBJ export
  • added substepping
  • added DamperJoint
  • improved implementation of slider and hinge joints/motors
  • Crispin Deul added the implementation of his paper Deul, Kugelstadt, Weiler, Bender, "Direct Position-Based Solver for Stiff Rods", Computer Graphics Forum 2018 and a corresponding demo
  • added collision detection for arbitrary meshes based on cubic signed distance fields
  • added implementation of the paper Kugelstadt, Schoemer, "Position and Orientation Based Cosserat Rods", SCA 2016
  • removed Boost dependency
  • added SceneGenerator.py to generate new scenarios easily by simple Python scripting
  • added scene loader based on json
  • added collision detection based on distance functions
  • added collision handling for rigid and deformable bodies
  • high resolution visualization mesh can be attached to a deformable body
  • added support for Mac OS X
  • added automatic computation of inertia tensor for arbitrary triangle meshes
  • added OBJ file loader
  • parallelized unified solver using graph coloring
  • implemented unified solver for rigid bodies and deformable solids

Features

  • Physically-based simulation with (eXtended) position-based constraint handling.
  • Simple interface
  • Demos
  • Library is free even for commercial applications.
  • Collision detection based on cubic signed distance fields
  • Library supports many constraints:
    • Elastic rods:
      • bend-twist constraint
      • stretch-shear constraint
      • Cosserat constraint
    • Deformable solids:
      • point-point distance constraint (PBD & XPBD)
      • point-edge distance constraint
      • point-triangle distance constraint
      • edge-edge distance constraint
      • dihedral bending constraint
      • isometric bending constraint (PBD & XPBD)
      • volume constraint (PBD & XPBD)
      • shape matching
      • FEM-based PBD (2D & 3D)
      • strain-based dynamics (2D & 3D)
    • Fluids:
      • position-based fluids
    • Rigid bodies:
      • contact constraints
      • ball joint
      • ball-on-line-joint
      • hinge joint
      • target angle motor hinge joint
      • target velocity motor hinge joint
      • universal joint
      • slider joint
      • target position motor slider joint
      • target velocity motor slider joint
      • ball joint between rigid body and particle
      • distance joint
      • damper joint
      • implicit spring
    • Generic constraints

Videos

The following videos were generated using the PositionBasedDynamics library:

Hierarchical hp-Adaptive Signed Distance FieldsDirect Position-Based Solver for Stiff Rods
VideoVideo

Screenshots

References

  • J. Bender, M. Müller and M. Macklin, "Position-Based Simulation Methods in Computer Graphics", In Tutorial Proceedings of Eurographics, 2015
  • J. Bender, D. Koschier, P. Charrier and D. Weber, ""Position-based simulation of continuous materials", Computers & Graphics 44, 2014
  • J. Bender, M. Müller, M. A. Otaduy, M. Teschner and M. Macklin, "A Survey on Position-Based Simulation Methods in Computer Graphics", Computer Graphics Forum 33, 6, 2014
  • C. Deul, T. Kugelstadt, M. Weiler, J. Bender, "Direct Position-Based Solver for Stiff Rods", Computer Graphics Forum, 2018
  • C. Deul, P. Charrier and J. Bender, "Position-Based Rigid Body Dynamics", Computer Animation and Virtual Worlds, 2014
  • D. Koschier, C. Deul, M. Brand and J. Bender, "An hp-Adaptive Discretization Algorithm for Signed Distance Field Generation", IEEE Transactions on Visualization and Computer Graphics 23, 2017
  • M. Macklin, M. Müller, N. Chentanez and T.Y. Kim, "Unified particle physics for real-time applications", ACM Trans. Graph. 33, 4, 2014
  • M. Müller, N. Chentanez, T.Y. Kim, M. Macklin, "Strain based dynamics", In Proceedings of the 2014 ACM SIGGRAPH/Eurographics Symposium on Computer Animation, 2014
  • J. Bender, D. Weber and R. Diziol, "Fast and stable cloth simulation based on multi-resolution shape matching", Computers & Graphics 37, 8, 2013
  • R. Diziol, J. Bender and D. Bayer, "Robust Real-Time Deformation of Incompressible Surface Meshes", In Proceedings of ACM SIGGRAPH / EUROGRAPHICS Symposium on Computer Animation (SCA), 2011
  • M. Müller and N. Chentanez, "Solid simulation with oriented particles", ACM Trans. Graph. 30, 4, 2011
  • M. Müller, "Hierarchical Position Based Dynamics", In VRIPHYS 08: Fifth Workshop in Virtual Reality Interactions and Physical Simulations, 2008
  • M. Müller, B. Heidelberger, M. Hennix and J. Ratcliff, "Position based dynamics", Journal of Visual Communication and Image Representation 18, 2, 2007
  • M. Müller, B. Heidelberger, M. Teschner and M. Gross, "Meshless deformations based on shape matching", ACM Trans. Graph. 24, 3, 2005
  • M. Macklin and M. Müller, "Position based fluids", ACM Trans. Graph. 32, 4, 2013
  • Dan Koschier, Crispin Deul and Jan Bender, "Hierarchical hp-Adaptive Signed Distance Fields", In Proceedings of ACM SIGGRAPH / EUROGRAPHICS Symposium on Computer Animation (SCA), 2016
  • Tassilo Kugelstadt, Elmar Schoemer, "Position and Orientation Based Cosserat Rods", In Proceedings of ACM SIGGRAPH / EUROGRAPHICS Symposium on Computer Animation (SCA), 2016
  • M. Macklin, M. Müller and N. Chentanez, "XPBD: Position-based Simulation of Compliant Constrained Dynamics", Proceedings of the 9th International Conference on Motion in Games (MIG), 2016