Getting started with the Jolt Physics Engine

Motivation

In the past I have experimented with sequential impulses to implement constraints (see part 1, part 2, part 3, part 4, part 5, part 6 of my rigid body physics series). I tried to integrate Runge-Kutta integration with sequential impulses. However it was difficult to prevent interpenetration of objects. Also implementing a vehicle with wheels and suspension, where the weight ratio between the vehicle and the wheels was high, required a high number of iterations to stabilise. Finally stacking of boxes turned out to be unstable.

In a GDC 2014 talk, Erin Catto showed sequential impulses and stable box stacking in the Box2D engine. Stacking of 2D boxes was made stable by solving for multiple impulses at the same time.

In 2022 Jorrit Rouwe released JoltPhysics which is a physics engine for 3D rigid objects also using sequential impulses. His GDC 2022 talk Architecting Jolt Physics for Horizon Forbidden West refers to Erin Catto’s talk and discusses various performance optimisations developed in Jolt Physics.

In the following I have tested a few base cases of rigid body physics with the Jolt Physics library.

Installing Jolt

Jolt Physics is a C++ library built using CMake. To compile with double precision, I changed the cmake call in JoltPhysics/Build/cmake_linux_clang_gcc.sh as follows:

cmake -S . -B $BUILD_DIR -G "Unix Makefiles" -DDOUBLE_PRECISION=ON -DCMAKE_BUILD_TYPE=$BUILD_TYPE -DCMAKE_CXX_COMPILER=$COMPILER "${@}"

A release build with g++ and installation is done as follows:

./cmake_linux_clang_gcc.sh Release g++
cd Linux_Release
make
sudo make install

Next you can have a look at JoltPhysics/HelloWorld/HelloWorld.cpp which is a simple example of a sphere bouncing on a floor. The example shows how to implement the required layers and collision filters (e.g. stationary objects cannot collide with each other). Make sure to define the Trace variable so you get useful warnings if something goes wrong.

Tumbling object in space

In this section we test the tumbling motion of a cuboid in space.

To compile a C++ program using Jolt, you need to use the same preprocessor definitions which were used to compile Jolt. If you have set up the Trace function, you will get a warning if the preprocessor definitions do not match.

Here is an example Makefile to compile and link a program with the release build of the Jolt library, GLFW, and GLEW.

CCFLAGS = -g -fPIC -Wall -Werror -DNDEBUG -DJPH_PROFILE_ENABLED -DJPH_DEBUG_RENDERER -DJPH_OBJECT_STREAM -DJPH_DOUBLE_PRECISION $(shell pkg-config --cflags glfw3 glew)
LDFLAGS = -flto=auto $(shell pkg-config --libs glfw3 glew) -lJolt

all: tumble

tumble: tumble.o
	g++ -o $@ $^ $(LDFLAGS)

clean:
	rm -f tumble *.o

.cc.o:
	g++ -c $(CCFLAGS) -o $@ $<

See Makefile for complete build code.

The core of the example creates a shape of dimension a×b×c and sets the density to 1000.0. Furthermore the convex radius used for approximating collision shapes needs to be much smaller than the object dimensions. The limit for the linear velocity is lifted and most importantly the solution for gyroscopic forces is enabled. Furthermore linear and angular damping are set to zero. Finally the body is created, added to the physics system, and the angular velocity is set to an interesting value. The code snippet is shown below:

float a = 1.0;
float b = 0.1;
float c = 0.5;
// ...
BoxShapeSettings body_shape_settings(Vec3(a, b, c));
body_shape_settings.mConvexRadius = 0.01;
body_shape_settings.SetDensity(1000.0);
body_shape_settings.SetEmbedded();
ShapeSettings::ShapeResult body_shape_result = body_shape_settings.Create();
ShapeRefC body_shape = body_shape_result.Get();
BodyCreationSettings body_settings(body_shape, RVec3(0.0, 0.0, 0.0), Quat::sIdentity(), EMotionType::Dynamic, Layers::MOVING);
body_settings.mMaxLinearVelocity = 10000.0;
body_settings.mApplyGyroscopicForce = true;
body_settings.mLinearDamping = 0.0;
body_settings.mAngularDamping = 0.0;
Body *body = body_interface.CreateBody(body_settings);
body_interface.AddBody(body->GetID(), EActivation::Activate);
body_interface.SetLinearVelocity(body->GetID(), Vec3(0.0, 0.0, 0.0));
body_interface.SetAngularVelocity(body->GetID(), Vec3(0.3, 0.0, 5.0));

Here is a video showing the result of the simulation. As one can see, Jolt is able to simulate a tumbling motion without deterioation.

See tumble.cc for full source code.

Stack of cuboids

In this section we test the falling motion of a stack of cuboids. Three cuboids are created and the initial positions are staggered in the x direction to get a more interesting result. Using i = 0, 1, 2 the cuboids are created in the following way:

BoxShapeSettings body_shape_settings(Vec3(0.5 * a, 0.5 * b, 0.5 * c));
body_shape_settings.mConvexRadius = 0.01;
body_shape_settings.SetDensity(1000.0);
body_shape_settings.SetEmbedded();
ShapeSettings::ShapeResult body_shape_result = body_shape_settings.Create();
ShapeRefC body_shape = body_shape_result.Get();
BodyCreationSettings body_settings(body_shape, RVec3(i * 0.4, 0.2 + i * 0.2, -i * 0.3), Quat::sIdentity(), EMotionType::Dynamic, Layers::MOVING);
body_settings.mMaxLinearVelocity = 10000.0;
body_settings.mApplyGyroscopicForce = true;
body_settings.mLinearDamping = 0.0;
body_settings.mAngularDamping = 0.0;
Body *body = body_interface.CreateBody(body_settings);
body->SetFriction(0.5);
body->SetRestitution(0.3f);
body_interface.AddBody(body->GetID(), EActivation::Activate);

Furthermore a ground shape is created. Note that for simplicity I only created one layer. If the ground was composed of multiple convex objects, a static layer should be created and used.

BoxShapeSettings ground_shape_settings(Vec3(3.0, 0.1, 3.0));
ground_shape_settings.mConvexRadius = 0.01;
ground_shape_settings.SetEmbedded();
ShapeSettings::ShapeResult ground_shape_result = ground_shape_settings.Create();
ShapeRefC ground_shape = ground_shape_result.Get();
BodyCreationSettings ground_settings(ground_shape, RVec3(0.0, -0.5, 0.0), Quat::sIdentity(), EMotionType::Static, Layers::MOVING);
Body *ground = body_interface.CreateBody(ground_settings);
ground->SetFriction(0.5);
body_interface.AddBody(ground->GetID(), EActivation::DontActivate);

Note that the bodies need to be activated for the simulation to take place.

body_interface.ActivateBody(body->GetID());

The simulation is run by repeatedly calling the Update method on the physics system.

const int cCollisionSteps = 1;
physics_system.Update(dt, cCollisionSteps, &temp_allocator, &job_system);

The following video shows the result of the simulation.

See stack.cc for full source code.

For a more challenging demo of this type, see the Stable Box Stacking demo video by Jorrit Rouwe.

Double pendulum

The double pendulum is created using the HingeConstraintSettings class. There are two hinges. One between the base and the upper arm of the pendulum and one between the upper arm and the lower arm. The physics library also requires initialisation of a vector normal to the hinge axis.

HingeConstraintSettings hinge1;
hinge1.mPoint1 = hinge1.mPoint2 = RVec3(0.0, 0.5, 0);
hinge1.mHingeAxis1 = hinge1.mHingeAxis2 = Vec3::sAxisZ();
hinge1.mNormalAxis1 = hinge1.mNormalAxis2 = Vec3::sAxisY();
physics_system.AddConstraint(hinge1.Create(*base, *upper));

HingeConstraintSettings hinge2;
hinge2.mPoint1 = hinge2.mPoint2 = RVec3(a, 0.5, 0);
hinge2.mHingeAxis1 = hinge2.mHingeAxis2 = Vec3::sAxisZ();
hinge2.mNormalAxis1 = hinge2.mNormalAxis2 = Vec3::sAxisY();
physics_system.AddConstraint(hinge2.Create(*upper, *lower));

The following video shows the result.

See pendulum.cc for full source code.

Suspension

Another test case is a prismatic joint with a suspension constraint. The prismatic joint is created using the SliderConstraintSettings class. The suspension is created using a soft distance constraint. The code snippet is shown below:

SliderConstraintSettings slider_settings;
slider_settings.mAutoDetectPoint = true;
slider_settings.SetSliderAxis(Vec3::sAxisY());
physics_system.AddConstraint(slider_settings.Create(*boxes[0], *boxes[1]));

DistanceConstraintSettings distance_settings;
distance_settings.mPoint1 = RVec3(0.0, 0.0, 0.0);
distance_settings.mPoint2 = RVec3(0.0, 0.4, 0.0);
distance_settings.mLimitsSpringSettings.mDamping = 0.1f;
distance_settings.mLimitsSpringSettings.mStiffness = 1.0f;
physics_system.AddConstraint(distance_settings.Create(*boxes[0], *boxes[1]));

The video shows the result of running this sumulation.

See suspension.cc for full source code.

Wheeled vehicle

Jolt comes with a specialised implementation for simulating wheeled vehicles (there is also even one for tracked vehicles). The vehicle API allows placing the wheels and adjusting the suspension minimum and maximum length. One can set the angular damping of the wheels to zero. Furthermore there are longitudinal and lateral friction curves of the wheels which I haven’t modified. Finally there is a vehicle controller object for setting motor, steering angle, brakes, and hand brake.

RefConst<Shape> car_shape = new BoxShape(Vec3(half_vehicle_width, half_vehicle_height, half_vehicle_length));
BodyCreationSettings car_body_settings(car_shape, RVec3::sZero(), Quat::sIdentity(), EMotionType::Dynamic, Layers::MOVING);
car_body_settings.mOverrideMassProperties = EOverrideMassProperties::CalculateInertia;
car_body_settings.mMassPropertiesOverride.mMass = 1500.0f;
car_body_settings.mLinearDamping = 0.0;
car_body_settings.mAngularDamping = 0.0;

VehicleConstraintSettings vehicle;

WheelSettingsWV *w1 = new WheelSettingsWV;
w1->mPosition = Vec3(0.0f, -0.9f * half_vehicle_height, half_vehicle_length - 1.0f * wheel_radius);
w1->mSuspensionMinLength = wheel_radius;
w1->mSuspensionMaxLength = 2 * wheel_radius;
w1->mAngularDamping = 0.0f;
w1->mMaxSteerAngle = 0.0f; // max_steering_angle;
w1->mMaxHandBrakeTorque = 0.0f;
w1->mRadius = wheel_radius;
w1->mWidth = wheel_width;

WheelSettingsWV *w2 = new WheelSettingsWV;
w2->mPosition = Vec3(half_vehicle_width, -0.9f * half_vehicle_height, -half_vehicle_length + 1.0f * wheel_radius);
// ...

WheelSettingsWV *w3 = new WheelSettingsWV;
w3->mPosition = Vec3(-half_vehicle_width, -0.9f * half_vehicle_height, -half_vehicle_length + 1.0f * wheel_radius);
// ...

vehicle.mWheels = {w1, w2, w3};

WheeledVehicleControllerSettings *controller = new WheeledVehicleControllerSettings;
vehicle.mController = controller;

Body *car_body = body_interface.CreateBody(car_body_settings);
body_interface.AddBody(car_body->GetID(), EActivation::Activate);
VehicleConstraint *constraint = new VehicleConstraint(*car_body, vehicle);
VehicleCollisionTester *tester = new VehicleCollisionTesterRay(Layers::MOVING);
constraint->SetVehicleCollisionTester(tester);
physics_system.AddConstraint(constraint);
physics_system.AddStepListener(constraint);

vehicle_controller->SetDriverInput(0.0f, 0.0f, 0.0f, 0.0f);

A vehicle dropping on the ground with horizontal speed is shown in the following video.

Note that the inertia of the wheels was high in this video. One can correct this by reducing the inertia of the wheels as follows.

w1->mInertia = 0.01;
w2->mInertia = 0.01;
w3->mInertia = 0.01;

See vehicle.cc for full source code.

Enjoy!