Documentation

Overview

Mujoco Toolbox

A toolbox for working with MuJoCo simulations.

This package provides various utilities and controllers to facilitate a faster simulation process.

Modules

  • sim: Contains the Simulation class for interfacing with MuJoCo.

  • controllers: Includes pre-built functions for controlling simulations.

  • assets: Contains pre-defined assets for building MuJoCo models.

Constants

  • CAPTURE_PARAMETERS: List of MjData fields to capture during simulation.

  • MAX_GEOM_SCALAR: Scalar value for mujoco.Renderer.max_geom.

  • PROGRESS_BAR_ENABLED: Boolean flag to enable or disable progress bar.

This project is licensed under the MIT License. See the LICENSE file for details.

Documentation

[See Here](https://MGross21.github.io/mujoco-toolbox/)

Notes

This package is still under development. Some features may not be fully implemented or may change in future releases. Please refer to the documentation for the most up-to-date information. [Report any issues here](https://github.com/MGross21/mujoco-toolbox/issues).

class mujoco_toolbox.Builder(*inputs: str, meshdir: str = 'meshes/')[source]

Bases: object

A class to build and manipulate MuJoCo XML models.

static merge(inputs: Sequence[str | Builder], meshdir: str = 'meshes/') Builder[source]

Merge multiple Builder objects and/or XML strings into one Builder.

Parameters:
  • inputs – Sequence of Builder objects and/or XML strings or file paths.

  • meshdir – Mesh directory (default: “meshes/”).

Returns:

Merged Builder instance.

Raises:

ValueError – If no inputs are provided.

save(file_path: str) str[source]
mujoco_toolbox.CAPTURE_PARAMETERS: set = {'act', 'ctrl', 'qacc', 'qpos', 'qvel', 'sensordata', 'time', 'xmat', 'xpos', 'xquat'}

MjData default fields to capture during simulation. For possible types, see [MuJoCo API](https://mujoco.readthedocs.io/en/stable/APIreference/APItypes.html#mjdata).

Capture All:

>>> from mujoco_toolbox import mjtb
>>> mjtb.CAPTURE_PARAMETERS = {"all"}

Default:

>>> mjtb.CAPTURE_PARAMETERS = {
...     "time",
...     "qpos",
...     "qvel",
...     "act",
...     "qacc",
...     "xpos",
...     "xquat",
...     "xmat",
...     "ctrl",
...     "sensordata",
... }
class mujoco_toolbox.Simulation(*args: Any, **kwargs: Any)[source]

Bases: object

Simulation class for managing MuJoCo simulations.

body_data(body_name: str, data_name: str | None = None) dict[str, ndarray] | ndarray[source]

Get the data for a specific body in the simulation.

Parameters:
  • body_name (str) – The name of the body to retrieve data for.

  • data_name (str) – The name of the data to retrieve.

Returns:

The data for the specified body.

Return type:

dict[str, np.ndarray] | np.ndarray

f2t(frame: int) float[source]

Convert frame index to time.

id2name(id: int) str[source]

Get the name of a body given its ID.

Parameters:

id (int) – The ID of the body.

Returns:

The name of the body.

Return type:

str

launch(show_menu: bool = True) None[source]

Open a window to display the simulation in real time.

name2id(name: str) int[source]

Get the name of a body given its index.

Parameters:

name (str) – The name of the body.

Returns:

The index of the body.

Return type:

int

reload() Simulation[source]

Reload the model and data objects.

Returns:

Self for method chaining.

Return type:

Simulation

run(*, render: bool = False, camera: str | None = None, interactive: bool = False, show_menu: bool = True, multi_thread: bool = False) Simulation[source]

Run the simulation with optional rendering.

Parameters:
  • render (bool) – If True, renders the simulation.

  • camera (str) – The camera view to render from, defaults to None.

  • data_rate (int) – How often to capture data, expressed as frames

  • second. (per)

  • interactive (bool) – If True, opens an interactive viewer window.

  • show_menu (bool) – Shows the menu in the interactive viewer.

  • True. (Interactive must be)

  • multi_thread (bool) – If True, runs the simulation in multi-threaded

  • mode.

Returns:

The current Simulation object for method chaining.

Return type:

self

save(title: str = 'render', codec: str = 'gif', frame_idx: int | tuple[int, int] | None = None, time_idx: float | tuple[float, float] | None = None) str[source]

Save specific frame(s) as a video or GIF to a file.

Parameters:
  • title (str, optional) – Filename for the saved media.

  • codec (str, optional) – Video codec/format. Defaults to “gif”.

  • frame_idx (int or tuple, optional) – Single frame index or (start, stop) frame indices.

  • time_idx (float or tuple, optional) – Single time or (start, end) times in seconds.

Returns:

Absolute path to the saved file.

Return type:

str

Raises:

ValueError – If no frames are captured or invalid input parameters.

show(title: str | None = None, codec: str = 'gif', frame_idx: int | tuple[int, int] | None = None, time_idx: float | tuple[float, float] | None = None) None[source]

Render specific frame(s) as a video or GIF in a window.

Parameters:
  • title (str, optional) – Title for the rendered media.

  • codec (str, optional) – Video codec/format. Defaults to “gif”.

  • frame_idx (int or tuple, optional) – Single frame index or (start, stop) frame indices.

  • time_idx (float or tuple, optional) – Single time or (start, end) times in seconds.

Raises:

ValueError – If no frames are captured or invalid input parameters.

t2f(t: float) int[source]

Convert time to frame index.

to_yaml(name: str = 'Model') None[source]

Save simulation data to a YAML file.

Parameters:

name (str) – The filename for the YAML file.

Returns:

None

mujoco_toolbox.cos(model, data, **kwargs) None[source]

A simple cosine wave controller for the simulation.

Parameters:
  • amplitude (float) – The amplitude of the cosine wave (default=1).

  • frequency (float) – The frequency of the cosine wave (default=1).

  • phase (float) – The phase shift of the cosine wave (default=0).

  • joint (list[int]) – The joint to apply the cosine wave to (default=all).

  • delay (float) – The delay before applying the cosine wave (default=0).

Returns:

None

mujoco_toolbox.glovebox(*, width: float = 1.25, depth: float = 0.75, height: float = 1.0, glass_thickness: float = 0.05, pos_x: float = 0, pos_y: float = 0) str[source]

Create a glovebox with the given dimensions (in meters).

mujoco_toolbox.random(model, data, **kwargs) None[source]

A random controller for the simulation.

Parameters:
  • amplitude (float) – The maximum amplitude of the random signal (default=1).

  • joint (list[int]) – The joints to apply the random signal to (default=all).

  • axis (int) – The axis to apply the random signal to (default=None).

  • delay (float) – The delay before applying the random signal (default=0).

Returns:

None

mujoco_toolbox.real_time(model, data, *args, **kwargs) None[source]

A real-time controller for the simulation.

Parameters:

controller_params (dict) – Dictionary of parameters to pass to the controller.

Returns:

None

mujoco_toolbox.sin(model, data, **kwargs) None[source]

A simple sine wave controller for the simulation.

Parameters:
  • amplitude (float) – The amplitude of the sine wave (default=1).

  • frequency (float) – The frequency of the sine wave (default=1).

  • phase (float) – The phase shift of the sine wave (default=0).

  • joint (list[int]) – The joint to apply the sine wave to (default=all).

  • delay (float) – The delay before applying the sine wave (default=0).

Returns:

None

mujoco_toolbox.step(model, data, **kwargs) None[source]

A step controller for the simulation.

Parameters:
  • amplitude (float) – The amplitude of the step signal (default=1).

  • joint (list[int]) – The joints to apply the step signal to (default=all).

  • axis (int) – The axis to apply the step signal to (default=None).

  • delay (float) – The delay before applying the step signal (default=0).

Returns:

None