This page is currently maintained by Ying Lu.

In the following brief reviews, it is our intent to be as accurate as possible in my descriptions of the capabilities of the packages with respect to rigid body dynamics with intermittent unilateral contact. If you find errors, disagree with our assessment, know of any packages that we've missed, or know that some of the packages listed are no longer available, please let us know. Send email to Ying Lu.

This survey is limited to simulation packages that can handle systems with intermittent unilateral contacts

Open Source Packages

  • Bullet
    The recent release of Bullet incorporates pybullet for robotics, deep learning, VR and haptics, in collaboration with Google brain team. As for the PGS LCP constraint solver, it has a new option to terminate as soon as the residual (error) is below a specified tolerance (instead of fixed number of iterations). There is also support to load some MuJoCo MJCF xml files. Bullet 2.87 added reinforcement learning environment to allow the user of pybullet inside Unity 3D for robotics and reinforcement learning.
    05/07/2018.
    Bullet Physics is a professional open source collision detection, rigid body and soft body dynamics library. Bullet relaxes the friction model to make solution by projected Gauss-Seidel possible. Bullet's strength is in its recent developments for parallel computation. Collision detection and physics solutions can run entirely on a GPU without needing to communicate with a CPU. The recently released Bullet 2.80 includes a preview of the GPU OpenCL rigid body pipeline. Collision detection and physics have been optimized to run on multiple parallel processors. By using a special collision dispatcher, the code can activate parallel optimizations.
    03/06/2012.

  • Chrono
    Chrono is a physics-based modelling and simulation infrastructure based on a platform-independent, open-source design. The core of Chrono is the Chrono::Engine middleware, an object-oriented library whose C++ API can be used to develop simulation software. Among the other components of the Chrono ecosystems are: Chrono::Parallel, a library for enabling parallel computation in Chrono; Chrono::Vehicle, which provides support for vehicle dynamics simulation; Chrono::FEA, which provides support for linear and nonlinear Finite Element Analysis; Chrono::FSI, which provides support for Fluid-Solid Interaction problems; Chrono::PyEngine, which enables one to use Chrono::Engine in Python; Chrono::SolidWorks, an add-in for SolidWorks, which can be used to export 3D models and geometries from a CAD file into Chrono. Chrono is released under a permissive BSD3 license.
    05/07/2018.
    ProjectChrono is a set of open-source tools for mechanical simulations. The core of ProjectChrono is the Chrono::Engine C++ middleware, a powerful object-oriented set of libraries and their application program interface (API) can be freely used to develop simulation software. There are impressive simulation videos of many-body dynamics and they take advantage of the GPU and CPU parallelization. The physical contact model in Chrono::Engine is based a cone complementarity problem (CCP) with relaxation and stablization terms in the formulation.
    02/25/2014.
    This engine is based on the work of Anitescu and Tasora. See Tasora's mechanical system simulation page for pictures and technical papers on the methods. The basic model is the complementarity problem similar to the engines described on this page, but it is modified to take the form of a second-order cone constrained optimization problem (SOCCOP). It is solved with a matrix-free method. They have simulated up to about 1,000,000 bodies coupled through contact on Tesla GPUs. To form the SOCCOP, the friction model is regularized with the undesirable side effect being the physical formation of gaps at all sliding contacts.
    03/07/2012.

  • DART
    DART is accurate and stable for especially humanoid robot simulation, due to its use of generalized coordinates to represent articulated rigid body systems and Featherstone’s Articulated Body Algorithm to compute the dynamics of motion. DART has been fully integrated with Gazebo, together with ODE and Simbody. DART supports dynamics systems with closed-loop structure. DART handles contacts and collisions using an implicit LCP to guarantee non-penetration, directional friction, and approximated Coulomb friction cone condition.
    05/07/2018.
    Dynamic Animation and Robotics Toolkits (DART) is an open source library for developing kinematic and dynamic applications in robotics and computer animation. DART uses generalized coordinates to represent articulated rigid body systems and computes Lagrange's equations derived from D'Alembert's principle to describe the dynamics of motion. The contact and collision are handled using an implicit time-stepping, velocity-based linear complementarity problem (LCP) to guarantee non-penetration, directional friction and approximated Coulomb's friction cone conditions. The LCP problem is solved by Lemke's algorithm.
    02/25/2014.

  • Gazebo
    Gazebo is moving towards ignition libraries, with ignition-cmake, ignition-math, ignition-msgs, ignition-transport, etc. An updated documentation platform has been created for ignition robotics . Gazebo also incorporates vehicle simulation using Prius model. The underlying physics of Gazebo relies on ODE, Bullet and Simbody.
    05/07/2018.
    Gazebo is a multi-robot simulator for outdoor environment. It has been used in the Darpa Robotics Challenge (DRC). It is capable of simulating a population of robots, sensors and objects, but does so in a three-dimensional world. It generates both realistic sensor feedback and physically plausible interactions between objects. Moreover, Gazebo is in the process to support other physics engines; right now, Gazebo supports 4 physics engines: ODE, Bullet , DART and Simbody
    02/25/2014.

  • Position-Based Dynamics
    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. Position-Based Dynamics is now open-source on github.
    05/07/2018.
    These comments are based on my reading of the 2006 paper, "Constraint-based collision and contact handling using impulses". In one time-step, this simulator identifies all imminent collisions and existing contacts. Then it executes two main steps. First, it iterates through all collisions to find impulses consistent with Newton's restitution model. Second it processes the sustained contacts, iteratively until it finds impulses that prevent penetration. The first part is done in a way very similar to what Mirtich implemented in Impulse. The second is similar to the Euler approximation of the dynamic equations used in velocity-level complementarity methods. The two iterative phases are essentially fixed-point iteration schemes applied in a Gauss-Seidel fashion. A benefit is that implementation as an any-time method is possible. The videos are impressive.
    04/22/2010.

  • MBSim
    MBSim represents a universal simulation tool for multibody systems. The main focus of this software is the efficient treatment of unilateral and bilateral rigid contacts to calculate nonsmooth dynamics. As integration method amongst others modern time stepping methods are available in MBSim. The created models can be visualized by an interface to OpenMBV. The kernel of MBSim was developed at the Institute within a dissertation and is provided under the GNU General Public License on the hosting platform Github.
    05/07/2018.
    This project is being developed by the Center for Applied Mechanics at Technical University of Munich. It uses prox function formulations of the time-stepping subproblems to properly handle unilateral contacts with quadratic Coulomb friction. One drawback is that collision detection is not general. Pairs of geometric primitives are manually chosen for contact monitoring.
    03/07/2012.

  • Open Dynamics Engine
    ODE is not actively releasing new features, and the source code is maintained on Github by ODE Devs.
    05/07/2018.
    ODE use the maximal coordinate solver: Projected Gauss Seidel (PGS), and the default maximum number of iterations in PGS solver is 40. Once it runs out of the maximum, the loop terminates with the solution from the last iteration. To my knowledge, there is no tracking of the best solution in the loop. Now Gazebo calls the PGS solver in ODE when solving the subproblems during each time step.
    02/25/2014.
    The friction models are not Coulomb friction. The user can choose one of two approximations that make the time-stepping subproblem (an LCP) much easier to solve, but at the expense of some accuracy. There are several LCP solvers available in ODE. I like the documentation.
    01/09/2010.
    Free software still under development from Russell Smith who worked at Math Engine. The method of integration is based on complementarity formulations of Stewart/Trinkle and Anitescu/Potra. The solver is based on Baraff's pivoting method. Collisions are handled following Mirtich's method.
    01/29/2002.

  • RPISim
    RPI-MATLAB-Simulator (RPISim) is not actively releasing features, but the source code is maintained on Github due to the disfunction of Google code.
    05/07/2018.
    RPI-MATLAB-Simulator (RPISim) is a physics engine and simulator in MATLAB. RPISim is aimed at building a modular simulator for both teaching and research. RPISim contains multiple joint constraints such as revolute, prismatic, spherical and so on. Collision detection, modeling, dynamics formulation, solution algorithms are independent modules, so RPISim provide users a flexible platform to simulate multibody dynamics. Besides, the linear complementarity problem, nonlinear complementarity problem and mixed complementarity problem are all supported in RPISim. Furthermore, there are pivoting and iterative algorithms to solve these problems. In order to fairly compare the performance of different algorithms, there is a Benchmark Problems for Multibody Dynamics (BPMD) framework. BPMD framework is open source and use the Hierarchical Data Format 5 (HDF5) BPMD database to compare the solution algorithms.
    02/25/2014.

  • RBDL
    RBDL supports new constraint type CustomConstraint, which is a versatile interface to define more general types of constraints. It also adds support to specify external forces on bodies on constrained forward dynamics. RBDL added support for closed-loop models by replacing Contacts API by a new Constraint AP, in a most recent release in 2018, with the second latest update in 2016.
    05/07/2018.
    Rigid Body Dynamics Library(RBDL) performs the dynamics computation in a very efficient manner for models using generalized coordinates. It uses Featherstone's Spatial Algebra and allows for efficient evaluation of forward and inverse dynamics using the Articulated Body Algorithm and the Recursive Newton Euler Algorithm. RBDL also has implementation of methods to compute collisions and bilateral contact forces.
    01/01/2013.

  • Simbody
    Simbody uses an advanced Featherstone-style formulation of rigid body mechanics to provide results in Order(n) time for any set of n generalized coordinates. This can be used for internal coordinate modeling of molecules, or for coarse-grained models based on larger chunks. It is also useful for large-scale mechanical models, such as neuromuscular models of human gait, robotics, avatars, and animation. Simbody can also be used in real time interactive applications for biosimulation as well as for virtual worlds and games.
    05/07/2018.
    Simbody provides general multibody dynamics capability to solve Newton's second law in any set of generalized coordinates subject to any arbitrary constraint. Simbody uses an advanced featherstone-style formulation of rigid body mechanics to solve in O(n) time for any set of n genearlized coordinates.
    02/25/2014.

  • Siconos Platform
    Siconos is an open-source scientific software primarily targeted at modeling and simulating nonsmooth dynamical systems. Siconos is one of the simulators that supports the nonsmooth multibody dynamics system with unilateral contact and Coulomb friction. Siconos supports various formulations (LCP, NCP, QP, ...) with dedicated solvers for each of the formulation. They have a nonsmooth Gauss-Seidel solver and some LCP solvers can be found here: http://siconos.gforge.inria.fr/users_guide/lcp_solvers.html
    05/07/2018.
    SICONOS is an open source scientific software primarily targeted at modeling and simulating nonsmooth dynamical system. There are some videos updated in granular terrain simulation on the web page. The directory hierarchy is well linked on the web page. Most of the algorithms are used to solve the linear complementarity problems.
    02/25/2014.
    This project is still being actively developed. It would be nice if some videos were easily accessible.
    01/09/2010.
    This software was developed for general non-smooth dynamical systems, including multi-rigid-body systems with unilateral contacts. Time-stepping is based on subproblems formulated as complementarity problems.
    12/11/2007.

  • SOFA
    The SOFA engine provides many algorithms and physiological models. SOFA includes different integration schemes and linear system solvers. As for the physical models for rigid bodies, SOFA supports articulated bodies based on penalties or reduced coordinates.
    05/07/2018.
    Simulation Open Framework Architecture (SOFA) is an open source (LGPL) software package, primarily intended for real-time dynamic simulation in the medical field. It's been around since 2006-2007, and is developed by a large team. SOFA includes cluster and GPU support, including using CUDA, and they are working on support for haptic devices. The software is very well organized. There are several collision checkers and dynamic models (flexible and rigid). It appears to have good support for finite element methods also.
    03/06/2012.

Closed Source Packages
  • Adams
    Utilizing multibody dynamics solution technology, Adams runs nonlinear dynamics in a fraction of the time required by FEA solutions. Loads and forces computed by Adams simulations improve the accuracy of FEA by providing better assessment of how they vary throughout a full range of motion and operating environments.
    05/07/2018.
    Simulation of unilateral contact is still via a penalty method.
    01/09/2010.
    "Adams Solver" solves rigid body contact problems with a penalty method. It exhibited problems typical of penalty methods. For example, I tried rolling a faceted approximation of a uniform sphere on a plane and had to try many parameter settings before Solver returned a solution approximating the known exact solution.
    11/10/2001.

  • Animats
    Falling Bodies is a spring/damper simulator using a reduced degree of freedom model to create a set of ordinary differential equations, which are then integrated forward using both explicit and implicit integrators. Joints are handled by the reduced degree of freedom model using generalized coordinates. Collisions are modeled as exponential springs. Some new techniques, covered by a pending U.S. patent, allow Falling Bodies to deal effectively and reliably with the very stiff numerical systems that result from this formulation. Collision detection is based on convex polyhedra, with a distance measure using the GJK algorithm front-ended by an axis-oriented bounding box system. Most other simulators for animation and games use an impulse/constraint approach. It's inherent in the impulse/constraint approach that collisions result in instantaneous changes in direction and velocity. That looks subtly wrong; light and heavy objects bounce the same way, and the viewer doesn't get the impression of weight when a heavy object hits. We call this the "boink problem". Our approach, using nonlinear springs to simulate collisions, provides a more accurate simulation; heavy and light objects bounce differently. This, incidentally, is why Falling Bodies is slower than some of the competitive products. Now that 1GHz PCs are shipping, this is much less of a problem than it used to be.
    05/07/2018.
    According to John Nagel of Animats, Falling Bodies, mentioned below, has been licensed to Havok for the past five years.
    04/01/2010.
    The Animats web page is still under active development. Of interest is that they have patented at least two algorithms: (Patent 1) "Robots which can run up hills without slipping are usually covered by this patent." This patent appears to be based on a control method that reduces the magnitudes of the friction forces needed to prevent foot slip. (Patent 2) "This broad patent covers most spring/damper character simulation systems. If it falls, it has joints, it looks right, and it works right, it's usually covered by our patent." My interpretation of the patent is that they use a penalty method that begins responding in before the bodies are in contact and grows quickly to ensure that penetration never occurs.
    01/09/2010.
    The Falling Bodies software takes a spring/damper approach with a Featherstone-type approach to articulated characters, but with very careful handling of the details (SDFast is used to generate C-code from Featherstone's algorithm). It slows down on difficult collisions, but eventually grinds its way through them.
    11/10/2002.

  • Cinema 4D Dynamics
    I didn't get much meaningful information about physics simulation on their website.
    05/07/2018.
    Animations are done by key-framing, which would imply that there are no built-in rigid body dynamics algorithms. I was unable to find impressive videos that I saw 8 years ago here.
    01/09/2010.
    This software simulates rigid body systems and other flexible systems like cloth. Only $500. This package seems to be an equal (on paper) to "Total Havok." Excellent videos. There is no information about the method used for rigid body dynamics.
    02/02/2002.

  • DynaWiz
    It looks like the software has changed its name to Concurrent Dynamics, and the website has not been updated recently.
    05/07/2018.
    DynaWiz has been updated to allow unilateral contacts to occur during run-time. Here is a quote from the web page about solution the complexity of their time-stepping method: "Order(N + sum(n_i^3)), where N = number of bodies, and n_i^3 = number of flexible modes for the i-th body." The implication here is that unilateral contacts are treated as permanently connected. If an LCP (or NCP) formulation were employed, then there should be another term in the complexity expression; something like O(n_c^3), where n_c is the number of unilateral contacts.
    01/09/2010.
    DynaWiz formulates multibody dynamics in Lagrangian form, and provisions are made for event detection. However, in the introductory web pages, there is no description of how rigid-rigid contacts are handled. A direct communication with CDI indicated that DynaWiz does not support unilateral rigid contacts. The user would have to insert his own solvers.
    01/28/2002.

  • Havok Physics
    Havok Physics supports a wide variety of useful game-ready constraint types. It has continuous collision detection for environments, characters and vehicles. The Havok physics focuses more on simulation for games, with enhanced run-time performance, reduced memory footprint, etc.
    05/07/2018.
    This system is still actively being developed. There are many interesting videos with flexible objects and fluid flow. Havok is free for non-commercial use.
    01/09/2010.
    A dynamics engine geared toward rigid body dynamics for real-time virtual environments. The package "Total Havok" adds flexible bodies and fluid dynamics. The demos are as impressive as any I've seen, but there is no indication of the simulation method used.
    02/03/2002.

  • LMS Dads
    Siemens embedded the LMS Dads into LMS virtual.Lab and now with the LMS Virtual.Lab Motion, you can quickly start with the sketcher, the automatic assembly capabilities and the library of mechanism elements in LMS Virtual.Lab Motion. Users can parameterize models, analyze more design variants and move from single point analysis to design space exploration.
    05/07/2018.
    From an engineer at LMS, I learned that the user can specify a linear stiffness and damping model Kelvin-Voigt) to generate the contact force or use a Hertzian contact model. The API will return depth of penetration, velocity, normal, etc. for advanced users who want to create their own penalty-based contact force model.
    01/09/2010.
    A full-blown commercial package similar to MDI Adams. Intermittent contacts are handled, but I don't yet know the method used. However, there is mention of using DAE methods for integration, which implies that they manage contact state transitions by monitoring contact forces (as Haug did in the original DADS package).
    01/30/2002.

  • Maya
    The Bullet plug-in provides seamless mapping of Bullet objects to Maya objects. The controls to the Bullet objects are exposed in Maya Objects, and the interaction follows the typical Maya dynamics paradigm. Maya also provides deep adaptive fluid simulation and ocean simulation system with waves, ripples, and wakes.
    05/07/2018.
    Maya is a comprehensive 3D animation software, which offers a comprehensive creative feature set for 3D computer animation, modeling, simulation, rendering, and compositing on a highly extensible production platform. I got to know Jos Stam at the Banff center in Canada for a workshop on computational contact mechanics. The unified dynamics framework Nucleus in Jos' presentation is based on particles with constraints. There are impressive videos with simulation on cloth, rigid bodies and liquids; All of the dynamics are unified in a single solver.
    02/27/2010.

  • PhysX
    Not sure whether PhysX is still solving the complementarity problem for the frictional contacts. But after a quick search around, I found the NVIDIA GPUGems has a demo to solve the complementarity problem using Lemke's algorithm here: https://developer.nvidia.com/gpugems/GPUGems3/gpugems3_ch33.html
    05/07/2018.
    You can easily find lots of info on PhysX online. What you won't find is that when Ageia originally developed the engine, it was based on the impulse-velocity time-stepping formulations of Stewart-Trinkle and Anitescu-Potra. So friction and intermittency of contact was handled with the framework of complementarity problems. I don't know how much of this has been retained in the Nvidia product.
    04/01/2010.

  • SIMPACK
    I didn't find anything new related to the contact models on the website.
    05/07/2018.
    This package implements a penalty method using a polygonal contact model developed by Gerhard Hippman. Contact forces can be specified as functions of penetration volumes, depths, elastic moduli, material deformation damping constants, Poisson's ratio, etc.
    06/03/2010.

  • Sonar Simulation
    Sonar software consists of Sonar_LAB an Sonar_SIM. Sonar_LAB is a tool to create 3-dimensional multibody dynamic models using C#; Sonar_SIM is used to execute the simulation of the models created by means of sonar-3D-LAB. Sonar-SIM supports the multiprocessing standard 'openMP', and it comes with different licenses. The frictional contact between two rigid bodies is solved using a spring-damping system, without formulation of the complementarity problems.
    04/12/2018.

  • Tokamak
    Tokamak features a unique iterative method for solving constraints. This is claimed to allow developers to make trade-offs between accuracy and speed and provides more predictable processor and memory usage. Tokamak's constraint solver does not involve solving large matrices, thereby avoiding memory bandwidth limitations on some game consoles. The SDK supports a variety of joint types and joint limits and a realistic friction model. Tokamak is optimized for stacking large numbers of objects - a frequently requested feature by game developers. Tokamak provides collision detection for primitives (box, sphere, capsule), combinations of primitives, and arbitrary static triangle meshes. Lightweight 'rigid particles' provide particle effects in games at minimal cost.
    05/07/2018.
    Tokamak Game Physics SDK is a high performance real-time physics library designed specially for games. Tokamak features a unique iterative method for solving constraint, which allows developers to make the trade-off between accuracy. Besides, Tokamak supports a variety of joint types and joint limits and provides a very realistic friction model.
    06/03/2010.

  • MSC Nastran
    I didn't find anything related to dynamics or contact models online about this simulator.
    05/07/2018.
    This product is available, but I found much less information about it than other MSC products.
    01/09/2010.
    Formerly Working Model. The integration method for rigid body dynamics is a penalty method. Even though it probably exhibits the usual problems that plague penalty methods, vN4D ran right "out of the box" on a problem in which three parts with about 1500 facets each were dropped onto a plane such that they would collide with each other. The API does not provide access to contact point locations and normals, but is schedule to in the next release - Q1 of 2002.
    09/25/2001.

  • Vortex
    Vortex now becomes "Vortex Simulation Studio Platform", which models the constraints and environment precisely. There are some really impressive videos on the website. Vortex studio can provide the tools to create engaging virtual training simulation for tactical vehicle or heavy equipment operators.
    05/07/2018.
    Vortex 5.1 with the new Vortex Editor puts the vehicles, robots, heavy equipment and more into high-fidelity synthetic environments for operator training, mission rehearsal, virtual prototyping and testing.
    01/01/2013.
    Version 3 of Vortex will include "scaled" box friction, which approximates a quadratic friction cone with a 4-sided friction pyramid (Chris Funk, CMLabs).
    04/01/2010.
    In the PackBot video, I noticed penetration between the PackBot and the ground (especially when the Bot moves up and over a curb. This can come from an offset in the geometry used for collision detection and that used for visual rendering, Or it can come from using a penalty approach for contact force resolution.
    01/09/2010.
    Specialized for rigid body dynamics with unilateral, frictional contacts. However, dry friction does not obey Coulomb's Law. There are three choices, zero friction, infinite friction, and "box" friction. Box friction is simple limits on the tangential force values in two directions - no dependency on the normal load. A first-order semi-implicit time-stepper is used. The contact constraints are likely to be formulated as a complementarity problem, since it is possible to get a warning about cycling during constraint solution. The solver is at least partially based on algorithms to solve complementarity problems. The demos are impressive.
    01/28/2002.
Defunct Packages
  • Abdula
    This was a link to Abdula on Francois' page at TU Wien (Technical University of Vienna), but it is broken now.
    01/09/2010.
    Francios Faure's Abdula can do some pretty amazing animations; up to 64,000 frictionless spheres dropped into a bowl. The simulation method is not published, but is related to the "optimization-based animation" of Schmidl and Milenkovic. Abdula is no longer being improved as Francios is developing a more general and flexible library.
    02/01/2002.

  • AERO
    No new information.
    01/09/2010.
    Refers to itself as a physically-based animation system. This software uses a penalty method to calculate the contact forces. It also uses a "fixed set of bodies instead of triangular meshes." Complementarity theory and Baraff's method are mentioned as worthy goals that are not implemented.
    01/31/2002.

  • Dance
    This has been updated since 2012.
    05/07/2018.
    Recently updated the binary version which is available for Windows with installer. The entire DANCE system is now open with all source code included. It supports the import/export of motion capture with easy plugin interface. Physical simulation of characters with dynamic control and pose-based dynamic control is available for DANCE. Besides, it has also been integrated with the Open Dynamics Engine(ODE).
    01/01/2013.
    This system is still actively being developed.
    01/09/2010.
    This is a multibody dynamics simulator based on SD/Fast and targeted at animation applications. It appears as though rigid-rigid contacts are supported through "actuator plug-ins," which can be implemented as a penalty method.
    01/31/2002.

  • dVC3d
    dVC3d has not been updated since 2014.
    05/07/2018.
    dVC3d is a physical simulation engine that focuses on accurate robotics application and testing of different cutting edge theories in physical simulation. Theoretically, it inherits the basic framework from dVC2Dd. Beside moving completely to 3D, dVC3d also integrates research works developed recently.
    03/06/2012.

  • DynaMechs
    I can't find anything about unilateral contacts on the web page, but I learned from David Orin that unilateral contacts for a walking machine were implement using a penalty method.
    01/09/2010.
    Free software being developed at Ohio State University. Dynamics of mechanisms with and without closed loops. Contact force models are being developed to support applications such as walking robots. There was no mention of rigid-rigid contacts - probably not yet included.
    01/29/2002.

  • Impulse
    Nothing new here.
    01/09/2010.
    Brian Mirtich's Impulse does rigid body simulation with nothing but collisions. A hybrid version was developed to combined impulse with joint constraints. While at MERL Mirtich added a "time-warp" feature to avoid the crippling bottleneck caused by synchronous processing for large numbers of bodies.
    01/31/2002.

  • Moby
    Moby has not been updated since 2012.
    05/07/2018.
    Moby contains multiple joint constraints such as revolute, prismatic, spherical and so on. Besides, two optional convex solving methods incorporated in Moby are fast(active set QP-based) solver and accurate(interior-point quadratically constrained quadratic program-based) solver. Multiple integrator types are supported and thanks to the plugin of ODEPACK, the time stepper in Moby can now be variable step. Articulated bodies are supported using both independent coordinate and absolute coordinate representations.
    01/01/2013.
    Moby uses the Anitescu/Potra time-stepping method augmented with Baumgarte stabilization for the bilateral constraints. No stabilization is used for the unilateral constraints, which means that unilateral constraints are added to the time-stepping subproblems as penetrations occur, and no attempt is made to correct these penetrations. This means that penetrations are controlled using an event-driven approach that adjusts the time steps to find the time when each contact occurs. Several LCP methods have been incorporated: Lemke, Lemke with Yamane's modification, and PATH.
    04/01/2010.

  • Simulation and Active Interfaces
    This project is no longer under development and the link is broken
    03/06/2012.
    A rigid body dynamics engine developed by Arachi.com that is based on the algorithms of Featherstone (dynamics with bilateral constraints), Mirtich (collision impulse response), and Baraff (contact transitions e.g., sticking to sliding). A haptic interface allows real-time interaction with a virtual environments as long as the number of degrees of freedom and number of steady contacts is not too large.
    03/16/2002.

  • Solfec
    It looks like Solfec has stopped updating since 2013, and the source code is still hosted on Google code, which was turned down in 2016.
    05/07/2018.

    Solfec is an implicit three-dimensional multibody frictional Contact Dynamics software. Both serial and parallel (MPI) versions are being actively developed. The non-smooth, velocity level frictional contact law (Signorini-Coulomb) is solved by means of a nonlinear Gauss-Seidel or a projected quasi-Newton method. Rigid, pseudo-rigid and finite element kinematics is included.
    05/19/2011.

  • Umbra
    This seems defunct now and has no update since 2012.
    05/07/2018.
    Umbra development has intensified. Michael Skroch, manager of the group developing Umbra, said, "I have been focusing on Umbra being useful for the nexus of physical-cyber-behavior concepts in a 3D embodied environment. We've started work on parallelizing Umbra and providing multi-thread enhancements. We also are working with GPUs to improve speed."
    05/01/2010.
    Umbra is a general simulation and visualization environment developed by Fred Oppel and Eric Gottlieb at Sandia National Laboratories. It contains a rigid body dynamics module developed by Eric Gottlieb with technical guidance from Florian Potra and Jeff Trinkle. The time-stepping algorithm is based on the Stewart-Trinkle LCP formulation (in terms of velocities and impulses). All the videos on this web page were produced with Umbra. Even though there is currently no impact law is implemented, bouncing behavior can be observed in the animations. This is simply a side effect of the constraint stabilization in the Stewart-Trinkle algorithm. Many enhancements are underway.
    12/23/2002.