SimBenchmark

SimBenchmark provides benchmark results of contact simulation on the state-of-the-art physics engines for various robotic tasks.

Table of Contents

  1. Introduction
  2. Contact and Multibody Dynamics of Physics Engines
  3. List of Physics Engines
  4. Evaluation Metrics
  5. Test and Results

Introduction

As the robots interact with environments by the contact force, accurate and fast simulation of contact dynamics is crucial for model-based control of robots. Notably, the motion of legged robots is highly dependent on the contact force generated by a feet-terrain interaction that drives the entire body. It is natural to pursue the realistic and efficient contact simulation for legged robotics research, which enables the successful control of robot locomotion strategy or end-to-end training.

Many rigid body simulation tools that simulate contact dynamics has been introduced to the robotics society, yet the field is fragmented without strong dominance. For robotics researchers, it is challenging to find and select the best simulator suits to their robotics tasks among numerous options.

anymal-walking-raisim
Fig. 1. ANYmal walking in a simulation.
Image courtesy of Joonho Lee.

In this project, we seek to provide an comprehensive evaluation of the accuracy and the speed of contact simulation on the most widely-used physics engines for various situation scenes from single-bodies with a limited number of contacts to complex articulated robotic systems with PD control input. Our primary goal is to aid robotics researchers to select the best physics engine for their applications.


Contact and Multibody Dynamics of Physics Engines

Solving contact dynamics is NP-hard problem[1] due to its non-convexity and discontinuity. To make the problem tractable, physics engines approximate the contact problem as a relaxed problem that enables using efficient solving methods. Each method has different characteristics, but some of them significantly sacrifice the accuracy of the contact solution that leads to the poor reality of the simulation.

Moreover, physics engine requires efficient multibody dynamics implementation to be used for complex robot systems. For robotic articulated systems that have multiple joints and links, solving the multibody dynamics is considerably expensive as $n$ links have $O(n^3)$ complexity. Most state-of-the-art physics engines, therefore, adopt linear complex algorithms that solve the problem in an efficient manner.

In the benchmark tests, we investigated different characteristics of the contact model and multibody dynamics algorithms that each physics engine applies.

Please read this page for more backgrounds.


List of Physics Engines

We evaluated the most widely-used physics engines for robotics and machine learning applications.[2] The list of the engines is as follows:

You can find more details about each engine and how they were used in our benchmark software here.

RaiSim Bullet ODE MuJoCo DART
Initial
release
Unreleased 2006 2001 2015 2012
Author J. Hwangbo
D. Kang
E. Coumans R. Smith E. Todorov J. Lee et al
License Proprietary Zlib
(open-source)
GPL / BSD
(open-source)
Proprietary BSD
Main
purpose
Robotics Game, Graphics Game, Graphics Robotics Robotics
Language C++ C / C++ C++ C C++
API C++ C++ / Python C C C++
Contacts Hard Hard/Soft Hard/Soft Soft Hard
Solver Bisection MLCP LCP Newton / PGS / CG LCP
Integrator Semi-implicit Euler Semi-implicit Euler Semi-implicit Euler Semi-implicit Euler / RK4 Semi-implicit Euler
Coordinates Minimal Minimal Maximal Minimal Minimal

Evaluation Metrics

The error of the contact simulation is caused by

  1. inaccurate impulse/force solution from a contact solver
  2. inherited discretized error from numerical integration.
For iterative contact solvers, 1) can be reduced by increasing the number of iteration, and 2) can be reduced by decreasing timestep $dt$. In both cases, there is a speed-accuracy trade-off: accurate simulation requires more CPU time.

To evaluate the performance in a fair manner, we have to take into account the whole speed-accuracy curve as proposed in [3]. In the following example of speed-accuracy curve plot, the ideal engine is on the top-right corner, while most of the engines are represented as the curves sloping downwards from left to right. The better engine's curve locates upper-right than others; thus the engine 1 represented by curve 1 is better than the engine 2 represented by curve 2.

plot-format
Fig. 2. Speed-accuracy curve format.

Although our lack of knowledge on real physics, we use analytical solution of object trajectory as a reference obtained from Newton's rigid body dynamics and Coulomb's friction cone model when it is applicable: for systems with single rigid body with small number of contacts, we find analytical solution of the object trajectory and investigate numerical errors from simulation.

Besides, it may not be possible to find analytical trajectory for complex systems. In these cases, we investigate generic physical quantities such as total kinetic energy or linear momentum.

Finally, we also observe position level drift by measuring penetration error that is caused by discretization or inaccurate contact model. Apparently it should be zero for rigid body simulation with hard contacts.

More details of benchmark methodology are here.


Test and Results

Tests

Summary of Results

The following table describes the benchmark results assessed by the speed-accuracy curves.

RaiSim Bullet ODE MuJoCo DART
Rolling ++ +++ - + -
Bouncing ++++ ++ +++ - +
666 +++ + ++ + +
Elastic 666 ++++ ++ +++ - +
ANYmal PD +++++ +++ + ++++ ++
ANYmal
Momentum
+++ ++ +++++ ++++ (RK4) +
++ (Euler)
ANYmal
Energy
++++ +++ ++ +++++ (RK4) +
+++ (Euler)

ODE generally performs well with single-body primitive shaped objects while MuJoCo and DART have benefits on multibody simulations. The multibody system simulation on ODE is very expensive but notably, it outperformed in ANYmal momentum test: although it is significantly inefficient, the maximal coordinate representation has good momentum preservability. Bullet can simulates slip of the object with frictional contacts very accurately and also efficiently.

But, these engines also reveled their limitations:

RaiSim generally has good performance for both single-body and multibody tasks by the virtue of its distinctive contact solving method and efficient multibody dynamics algorithm implementation. We expect RaiSim to be an good alternative of the current state-of-the-art engines for contact simulation of robotics applications.


Commentary

Acknowledgment

Special thanks to Erwin Coumans who is the inventor of Bullet Physics.

References

  1. D. Kaufman et al., “Staggered projections for frictional contact in multibody systems,” 2008.
  2. S. Ivaldi et al., "Tools for dynamics simulation of robots: a survey based on user feedback," 2014
  3. Tom Erez et al., "Simulation Tools for Model-Based Robotics: Comparison of Bullet, Havok, MuJoCo, ODE and PhysX," 2015