Skip to content
/ jaxsim Public

A differentiable physics engine and multibody dynamics library for control and robot learning.

License

Notifications You must be signed in to change notification settings

ami-iit/jaxsim

Repository files navigation

JaxSim

JaxSim is a differentiable physics engine and multibody dynamics library built with JAX, tailored for control and robotic learning applications.



Features

  • Reduced-coordinate physics engine for fixed-base and floating-base robots.
  • Multibody dynamics library for model-based control algorithms.
  • Fully Python-based, leveraging jax following a functional programming paradigm.
  • Seamless execution on CPUs, GPUs, and TPUs.
  • Supports JIT compilation and automatic vectorization for high performance.
  • Compatible with SDF models and URDF (via sdformat conversion).

Usage

Using JaxSim as simulator

import jax.numpy as jnp
import jaxsim.api as js
import icub_models
import pathlib

# Load the iCub model
model_path = icub_models.get_model_file("iCubGazeboV2_5")
joints = ('torso_pitch', 'torso_roll', 'torso_yaw', 'l_shoulder_pitch',
          'l_shoulder_roll', 'l_shoulder_yaw', 'l_elbow', 'r_shoulder_pitch',
          'r_shoulder_roll', 'r_shoulder_yaw', 'r_elbow', 'l_hip_pitch',
          'l_hip_roll', 'l_hip_yaw', 'l_knee', 'l_ankle_pitch', 'l_ankle_roll',
          'r_hip_pitch', 'r_hip_roll', 'r_hip_yaw', 'r_knee', 'r_ankle_pitch',
          'r_ankle_roll')

# Build and reduce the model
model_description = pathlib.Path(model_path)
full_model = js.model.JaxSimModel.build_from_model_description(
    model_description=model_description, time_step=0.0001, is_urdf=True
)
model = js.model.reduce(model=full_model, considered_joints=joints)

ndof = model.dofs()
# Initialize data and simulation
data = js.data.JaxSimModelData.zero(model=model).reset_base_position(
    base_position=jnp.array([0.0, 0.0, 1.0])
)
T = jnp.arange(start=0, stop=1.0, step=model.time_step)
tau = jnp.zeros(ndof)

# Simulate
for t in T:
    data, _ = js.model.step(model=model, data=data, link_forces=None, joint_force_references=tau)

Using JaxSim as a multibody dynamics library

import jax.numpy as jnp
import jaxsim.api as js
import icub_models
import pathlib

# Load the iCub model
model_path = icub_models.get_model_file("iCubGazeboV2_5")
joints = ('torso_pitch', 'torso_roll', 'torso_yaw', 'l_shoulder_pitch',
          'l_shoulder_roll', 'l_shoulder_yaw', 'l_elbow', 'r_shoulder_pitch',
          'r_shoulder_roll', 'r_shoulder_yaw', 'r_elbow', 'l_hip_pitch',
          'l_hip_roll', 'l_hip_yaw', 'l_knee', 'l_ankle_pitch', 'l_ankle_roll',
          'r_hip_pitch', 'r_hip_roll', 'r_hip_yaw', 'r_knee', 'r_ankle_pitch',
          'r_ankle_roll')

# Build and reduce the model
model_description = pathlib.Path(model_path)
full_model = js.model.JaxSimModel.build_from_model_description(
    model_description=model_description, time_step=0.0001, is_urdf=True
)
model = js.model.reduce(model=full_model, considered_joints=joints)

# Initialize model data
data = js.data.JaxSimModelData.build(
    model=model,
    base_position=jnp.array([0.0, 0.0, 1.0],
)

# Frame and dynamics computations
frame_index = js.frame.name_to_idx(model=model, frame_name="l_foot")
W_H_F = js.frame.transform(model=model, data=data, frame_index=frame_index)  # Frame transformation
W_J_F = js.frame.jacobian(model=model, data=data, frame_index=frame_index)  # Frame Jacobian

# Dynamics properties
M = js.model.free_floating_mass_matrix(model=model, data=data)  # Mass matrix
h = js.model.free_floating_bias_forces(model=model, data=data)  # Bias forces
g = js.model.free_floating_gravity_forces(model=model, data=data)  # Gravity forces
C = js.model.free_floating_coriolis_matrix(model=model, data=data)  # Coriolis matrix

# Print dynamics results
print(f"M: shape={M.shape}, h: shape={h.shape}, g: shape={g.shape}, C: shape={C.shape}")

Additional features

  • Full support for automatic differentiation of RBDAs (forward and reverse modes) with JAX.
  • Support for automatically differentiating against kinematics and dynamics parameters.
  • All fixed-step integrators are forward and reverse differentiable.
  • All variable-step integrators are forward differentiable.
  • Check the example folder for additional usecase !

Warning

This project is still experimental, APIs could change between releases without notice.

Note

JaxSim currently focuses on locomotion applications. Only contacts between bodies and smooth ground surfaces are supported.

Installation

With conda

You can install the project using conda as follows:

conda install jaxsim -c conda-forge

You can enforce GPU support, if needed, by also specifying "jaxlib = * = *cuda*".

With pixi

Note

The minimum version of pixi required is 0.39.0.

You can add the jaxsim dependency in pixi project as follows:

pixi add jaxsim

If you are on Linux and you want to use a cuda-powered version of jax, remember to add the appropriate line in the system-requirements table, i.e. adding

[system-requirements]
cuda = "12"

if you are using a pixi.toml file or

[tool.pixi.system-requirements]
cuda = "12"

if you are using a pyproject.toml file.

With pip

You can install the project using pypa/pip, preferably in a virtual environment, as follows:

pip install jaxsim

Check pyproject.toml for the complete list of optional dependencies. You can obtain a full installation using jaxsim[all].

If you need GPU support, follow the official installation instructions of JAX.

Contributors installation (with conda)

If you want to contribute to the project, we recommend creating the following jaxsim conda environment first:

conda env create -f environment.yml

Then, activate the environment and install the project in editable mode:

conda activate jaxsim
pip install --no-deps -e .
Contributors installation (with pixi)

Note

The minimum version of pixi required is 0.39.0.

You can install the default dependencies of the project using pixi as follows:

pixi install

See pixi task list for a list of available tasks.

Documentation

The JaxSim API documentation is available at jaxsim.readthedocs.io.

Overview

Structure of the Python package
# tree -L 2 -I "__pycache__" -I "__init__*" -I "__main__*" src/jaxsim

src/jaxsim
|-- api..........................# Package containing the main functional APIs.
|   |-- com.py...................# |-- APIs for computing quantities related to the center of mass.
|   |-- common.py................# |-- Common utilities used in the current package.
|   |-- contact.py...............# |-- APIs for computing quantities related to the collidable points.
|   |-- data.py..................# |-- Class storing the data of a simulated model.
|   |-- frame.py.................# |-- APIs for computing quantities related to additional frames.
|   |-- joint.py.................# |-- APIs for computing quantities related to the joints.
|   |-- kin_dyn_parameters.py....# |-- Class storing kinematic and dynamic parameters of a model.
|   |-- link.py..................# |-- APIs for computing quantities related to the links.
|   |-- model.py.................# |-- Class defining a simulated model and APIs for computing related quantities.
|   |-- ode.py...................# |-- APIs for computing quantities related to the system dynamics.
|   |-- ode_data.py..............# |-- Set of classes to store the data of the system dynamics.
|   `-- references.py............# `-- Helper class to create references (link forces and joint torques).
|-- exceptions.py................# Module containing functions to raise exceptions from JIT-compiled functions.
|-- integrators..................# Package containing the integrators used to simulate the system dynamics.
|   |-- common.py................# |-- Common utilities used in the current package.
|   |-- fixed_step.py............# |-- Fixed-step integrators (explicit Runge-Kutta schemes).
|   `-- variable_step.py.........# `-- Variable-step integrators (embedded Runge-Kutta schemes).
|-- logging.py...................# Module containing logging utilities.
|-- math.........................# Package containing mathematical utilities.
|   |-- adjoint.py...............# |-- APIs for creating and manipulating 6D transformations.
|   |-- cross.py.................# |-- APIs for computing cross products of 6D quantities.
|   |-- inertia.py...............# |-- APIs for creating and manipulating 6D inertia matrices.
|   |-- joint_model.py...........# |-- APIs defining the supported joint model and the corresponding transformations.
|   |-- quaternion.py............# |-- APIs for creating and manipulating quaternions.
|   |-- rotation.py..............# |-- APIs for creating and manipulating rotation matrices.
|   |-- skew.py..................# |-- APIs for creating and manipulating skew-symmetric matrices.
|   `-- transform.py.............# `-- APIs for creating and manipulating homogeneous transformations.
|-- mujoco.......................# Package containing utilities to interact with the Mujoco passive viewer.
|   |-- loaders.py...............# |-- Utilities for converting JaxSim models to Mujoco models.
|   |-- model.py.................# |-- Class providing high-level methods to compute quantities using Mujoco.
|   `-- visualizer.py............# `-- Class that simplifies opening the passive viewer and recording videos.
|-- parsers......................# Package containing utilities to parse model descriptions (SDF and URDF models).
|   |-- descriptions/............# |-- Package containing the intermediate representation of a model description.
|   |-- kinematic_graph.py.......# |-- Definition of the kinematic graph associated with a parsed model description.
|   `-- rod/.....................# `-- Package to create the intermediate representation from model descriptions using ROD.
|-- rbda.........................# Package containing the low-level rigid body dynamics algorithms.
|   |-- aba.py...................# |-- The Articulated Body Algorithm.
|   |-- collidable_points.py.....# |-- Kinematics of collidable points.
|   |-- contacts/................# |-- Package containing the supported contact models.
|   |-- crba.py..................# |-- The Composite Rigid Body Algorithm.
|   |-- forward_kinematics.py....# |-- Forward kinematics of the model.
|   |-- jacobian.py..............# |-- Full Jacobian and full Jacobian derivative.
|   |-- rnea.py..................# |-- The Recursive Newton-Euler Algorithm.
|   `-- utils.py.................# `-- Common utilities used in the current package.
|-- terrain......................# Package containing resources to specify the terrain.
|   `-- terrain.py...............# `-- Classes defining the supported terrains.
|-- typing.py....................# Module containing type hints.
`-- utils........................# Package of common utilities.
    |-- jaxsim_dataclass.py......# |-- Utilities to operate on pytree dataclasses.
    |-- tracing.py...............# |-- Utilities to use when JAX is tracing functions.
    `-- wrappers.py..............# `-- Utilities to wrap objects for specific use cases on pytree dataclass attributes.

Credits

The RBDAs are based on the theory of the Rigid Body Dynamics Algorithms book by Roy Featherstone. The algorithms and some simulation features were inspired by its accompanying code.

The development of JaxSim started in late 2021, inspired by early versions of google/brax. At that time, Brax was implemented in maximal coordinates, and we wanted a physics engine in reduced coordinates. We are grateful to the Brax team for their work and showing the potential of JAX in this field.

Brax v2 was later implemented reduced coordinates, following an approach comparable to JaxSim. The development then shifted to MJX, which today provides a JAX-based implementation of the Mujoco APIs.

The main differences between MJX/Brax and JaxSim are as follows:

  • JaxSim supports out-of-the-box all SDF models with Pose Frame Semantics.
  • JaxSim only supports collisions between points rigidly attached to bodies and a compliant ground surface. Our contact model requires careful tuning of its spring-damper parameters, but being an instantaneous function of the state $(\mathbf{q}, \boldsymbol{\nu})$, it doesn't require running any optimization algorithm when stepping the simulation forward.
  • JaxSim mitigates the stiffness of the contact-aware system dynamics by providing variable-step integrators.

Contributing

We welcome contributions from the community. Please read the contributing guide to get started.

Citing

@software{ferigo_jaxsim_2022,
  author = {Diego Ferigo and Filippo Luca Ferretti and Silvio Traversaro and Daniele Pucci},
  title = {{JaxSim}: A Differentiable Physics Engine and Multibody Dynamics Library for Control and Robot Learning},
  url = {http://github.com/ami-iit/jaxsim},
  year = {2022},
}

Theoretical aspects of JaxSim are based on Chapters 7 and 8 of the following Ph.D. thesis:

@phdthesis{ferigo_phd_thesis_2022,
  title = {Simulation Architectures for Reinforcement Learning applied to Robotics},
  author = {Diego Ferigo},
  school = {University of Manchester},
  type = {PhD Thesis},
  month = {July},
  year = {2022},
}

People

Authors Maintainers

License

BSD3