Menagerie is a collection of high-quality models for the MuJoCo physics engine, curated by Google DeepMind.
A physics simulator is only as good as the model it is simulating, and in a powerful simulator like MuJoCo with many modeling options, it is easy to create "bad" models which do not behave as expected. The goal of this collection is to provide the community with a curated library of well-designed models that work well right out of the gate.
The minimum required MuJoCo version for each model is specified in its
respective README. You can download prebuilt binaries for MuJoCo from the GitHub
releases page, or if you
are working with Python, you can install the native bindings from
PyPI via pip install mujoco
. For
alternative installation instructions, see
here.
The structure of Menagerie is illustrated below. For brevity, we have only included one model directory since all others follow the exact same pattern.
├── unitree_go2
│ ├── assets
│ │ ├── base_0.obj
│ │ ├── ...
│ ├── go2.png
│ ├── go2.xml
│ ├── LICENSE
│ ├── README.md
│ └── scene.xml
│ └── go2_mjx.xml
│ └── scene_mjx.xml
assets
: stores the 3D meshes (.stl or .obj) of the model used for visual and
collision purposesLICENSE
: describes the copyright and licensing terms of the modelREADME.md
: contains detailed steps describing how the model's MJCF XML file
was generated<model>.xml
: contains the MJCF definition of the modelscene.xml
: includes <model>.xml
with a plane, a light source and
potentially other objects<model>.png
: a PNG image of scene.xml
<model>_mjx.xml
: contains an MJX-compatible version of the model. Not all
models have an MJX variant (see Menagerie Models for more
information).scene_mjx.xml
: same as scene.xml
but loads the MJX variantNote that <model>.xml
solely describes the model, i.e., no other entity is
defined in the kinematic tree. We leave additional body definitions for the
scene.xml
file, as can be seen in the Shadow Hand
scene.xml
.
robot-descriptions
You can use the opensource
robot_descriptions
package to load any model in Menagerie. It is available on PyPI and can be
installed via pip install robot_descriptions
.
Once installed, you can load a model of your choice as follows:
import mujoco
# Loading a specific model description as an imported module.
from robot_descriptions import panda_mj_description
model = mujoco.MjModel.from_xml_path(panda_mj_description.MJCF_PATH)
# Directly loading an instance of MjModel.
from robot_descriptions.loaders.mujoco import load_robot_description
model = load_robot_description("panda_mj_description")
# Loading a variant of the model, e.g. panda without a gripper.
model = load_robot_description("panda_mj_description", variant="panda_nohand")
git clone
You can also directly clone this repository in the directory of your choice:
git clone https://github.com/google-deepmind/mujoco_menagerie.git
You can then interactively explore the model using the Python viewer:
python -m mujoco.viewer --mjcf mujoco_menagerie/unitree_go2/scene.xml
If you have further questions, please check out our FAQ.
Our goal is to eventually make all Menagerie models as faithful as possible to the real system they are being modeled after. Improving model quality is an ongoing effort, and the current state of many models is not necessarily as good as it could be.
However, by releasing Menagerie in its current state, we hope to consolidate and increase visibility for community contributions. To help Menagerie users set proper expectations around the quality of each model, we introduce the following grading system:
Grade | Description |
---|---|
A+ | Values are the product of proper system identification |
A | Values are realistic, but have not been properly identified |
B | Stable, but some values are unrealistic |
C | Conditionally stable, can be significantly improved |
The grading system will be applied to each model once a proper system identification toolbox is created. We are currently planning to release this toolbox later this year.
For more information regarding contributions, for example to add a new model to Menagerie, see CONTRIBUTING.
Arms.
Name | Maker | DoFs | License | MJX |
---|---|---|---|---|
FR3 | Franka Robotics | 7 | Apache-2.0 | ✖️ |
iiwa14 | KUKA | 7 | BSD-3-Clause | ✖️ |
Lite6 | UFACTORY | 6 | BSD-3-Clause | ✖️ |
Panda | Franka Robotics | 7 | BSD-3-Clause | ✔️ |
Sawyer | Rethink Robotics | 7 | Apache-2.0 | ✖️ |
Unitree Z1 | Unitree Robotics | 6 | BSD-3-Clause | ✖️ |
UR5e | Universal Robots | 6 | BSD-3-Clause | ✖️ |
UR10e | Universal Robots | 6 | BSD-3-Clause | ✖️ |
ViperX 300 | Trossen Robotics | 8 | BSD-3-Clause | ✖️ |
WidowX 250 | Trossen Robotics | 8 | BSD-3-Clause | ✖️ |
xarm7 | UFACTORY | 7 | BSD-3-Clause | ✖️ |
Gen3 | Kinova Robotics | 7 | BSD-3-Clause | ✖️ |
Bipeds.
Name | Maker | DoFs | License | MJX |
---|---|---|---|---|
Cassie | Agility Robotics | 28 | BSD-3-Clause | ✖️ |
Dual Arms.
Name | Maker | DoFs | License | MJX |
---|---|---|---|---|
ALOHA 2 | Trossen Robotics, Google DeepMind | 16 | BSD-3-Clause | ✔️ |
Drones.
Name | Maker | DoFs | License | MJX |
---|---|---|---|---|
Crazyflie 2 | Bitcraze | 0 | MIT | ✖️ |
Skydio X2 | Skydio | 0 | Apache-2.0 | ✖️ |
End-effectors.
Name | Maker | DoFs | License | MJX |
---|---|---|---|---|
Allegro Hand V3 | Wonik Robotics | 16 | BSD-2-Clause | ✖️ |
LEAP Hand | Carnegie Mellon University | 16 | MIT | ✖️ |
Robotiq 2F-85 | Robotiq | 8 | BSD-2-Clause | ✖️ |
Shadow Hand EM35 | Shadow Robot Company | 24 | Apache-2.0 | ✖️ |
Shadow DEX-EE Hand | Shadow Robot Company | 12 | Apache-2.0 | ✖️ |
Mobile Manipulators.
Name | Maker | DoFs | License | MJX |
---|---|---|---|---|
Google Robot | Google DeepMind | 9 | Apache-2.0 | ✖️ |
Stretch 2 | Hello Robot | 17 | Clear BSD | ✖️ |
Stretch 3 | Hello Robot | 17 | Apache-2.0 | ✖️ |
Humanoids.
Name | Maker | DoFs | License | MJX |
---|---|---|---|---|
Robotis OP3 | Robotis | 20 | Apache-2.0 | ✖️ |
Unitree G1 | Unitree Robotics | 37 | BSD-3-Clause | ✖️ |
Unitree H1 | Unitree Robotics | 19 | BSD-3-Clause | ✖️ |
TALOS | PAL Robotics | 32 | Apache-2.0 | ✖️ |
Quadrupeds.
Name | Maker | DoFs | License | MJX |
---|---|---|---|---|
ANYmal B | ANYbotics | 12 | BSD-3-Clause | ✖️ |
ANYmal C | ANYbotics | 12 | BSD-3-Clause | ✔️ |
Spot | Boston Dynamics | 12 | BSD-3-Clause | ✖️ |
Unitree A1 | Unitree Robotics | 12 | BSD-3-Clause | ✖️ |
Unitree Go1 | Unitree Robotics | 12 | BSD-3-Clause | ✖️ |
Unitree Go2 | Unitree Robotics | 12 | BSD-3-Clause | ✔️ |
Google Barkour v0 | Google DeepMind | 12 | Apache-2.0 | ✔️ |
Google Barkour vB | Google DeepMind | 12 | Apache-2.0 | ✔️ |
Biomechanical.
Name | Maker | DoFs | License | MJX |
---|---|---|---|---|
flybody | Google DeepMind, HHMI Janelia Research Campus | 102 | Apache-2.0 | ✖️ |
Miscellaneous.
Name | Maker | DoFs | License | MJX |
---|---|---|---|---|
D435i | Intel Realsense | 0 | Apache-2.0 | ✖️ |
If you use Menagerie in your work, please use the following citation:
@software{menagerie2022github,
author = {Zakka, Kevin and Tassa, Yuval and {MuJoCo Menagerie Contributors}},
title = {{MuJoCo Menagerie: A collection of high-quality simulation models for MuJoCo}},
url = {http://github.com/google-deepmind/mujoco_menagerie},
year = {2022},
}
The models in this repository are based on third-party models designed by many talented people, and would not have been possible without their generous open-source contributions. We would like to acknowledge all the designers and engineers who made MuJoCo Menagerie possible.
We'd like to thank Pedro Vergani for his help with visuals and design.
The main effort required to make this repository publicly available was undertaken by Kevin Zakka, with help from the Robotics Simulation team at Google DeepMind.
XML and asset files in each individual model directory of this repository are
subject to different license terms. Please consult the LICENSE
files under
each specific model subdirectory for the relevant license and copyright
information.
All other content is Copyright 2022 DeepMind Technologies Limited and licensed under the Apache License, Version 2.0. A copy of this license is provided in the top-level LICENSE file in this repository. You can also obtain it from https://www.apache.org/licenses/LICENSE-2.0.
This is not an officially supported Google product.