API reference

MjSim: Basic simulation

mujoco_py.load_model_from_path(path)

Loads model from path.

mujoco_py.load_model_from_xml(xml_string)

Loads and returns a PyMjModel model from a string containing XML markup. Saves the XML string used to create the returned model in model.xml.

mujoco_py.load_model_from_mjb(path)

Loads and returns a PyMjModel model from bytes encoded MJB. MJB is a MuJoCo-custom format that includes assets like meshes/textures.

class mujoco_py.MjSim(model, data=None, nsubsteps=1, udd_callback=None)

MjSim represents a running simulation including its state.

Similar to Gym’s MujocoEnv, it internally wraps a PyMjModel and a PyMjData.

Parameters:

model : PyMjModel

The model to simulate.

data : PyMjData

Optional container for the simulation state. Will be created if None.

nsubsteps : int

Optional number of MuJoCo steps to run for every call to step(). Buffers will be swapped only once per step.

udd_callback : fn(MjSim) -> dict

Optional callback for user-defined dynamics. At every call to step(), it receives an MjSim object sim containing the current user-defined dynamics state in sim.udd_state, and returns the next udd_state after applying the user-defined dynamics. This is useful e.g. for reward functions that operate over functions of historical state.

Attributes

Methods

get_state()

Returns a copy of the simulator state.

render()

Renders view from a camera and returns image as an numpy.ndarray.

Args: - width (int): desired image width. - height (int): desired image height. - camera_name (str): name of camera in model. If None, the free

camera will be used.
  • depth (bool): if True, also return depth buffer

Returns: - rgb (uint8 array): image buffer from camera - depth (float array): depth buffer from camera (only returned

if depth=True)
reset()

Resets the simulation data and clears buffers.

save()

Saves the simulator model and state to a file as either a MuJoCo XML or MJB file. The current state is saved as a keyframe in the model file. This is useful for debugging using MuJoCo’s simulate utility.

Note that this doesn’t save the UDD-state which is part of MjSimState, since that’s not supported natively by MuJoCo. If you want to save the model together with the UDD-state, you should use the get_xml or get_mjb methods on MjModel together with MjSim.get_state and save them with e.g. pickle.

Args: - file (IO stream): stream to write model to. - format: format to use (either ‘xml’ or ‘mjb’) - keep_inertials (bool): if False, removes all <inertial>

properties derived automatically for geoms by MuJoco. Note that this removes ones that were provided by the user as well.
set_state()

Sets the state from an MjSimState. If the MjSimState was previously unflattened from a numpy array, consider set_state_from_flattened, as the defensive copy is a substantial overhead in an inner loop.

Args: - value (MjSimState): the desired state. - call_forward: optionally call sim.forward(). Called by default if

the udd_callback is set.
set_state_from_flattened()

This helper method sets the state from an array without requiring a defensive copy.

step()

Advances the simulation by calling mj_step.

If qpos or qvel have been modified directly, the user is required to call forward() before step() if their udd_callback requires access to MuJoCo state set during the forward dynamics.

class mujoco_py.MjSimState

Represents a snapshot of the simulator’s state.

This includes time, qpos, qvel, act, and udd_state.

Attributes

Methods

mujoco_py.ignore_mujoco_warnings()[source]

Class to turn off mujoco warning exceptions within a scope. Useful for large, vectorized rollouts.

PyMjData: Time-dependent data

PyMjData and related classes are automatically generated from the MuJoCo C header files. For more information on this process, see Autogenerated wrappers. Their structure therefore directly follows the MuJoCo structs.

class mujoco_py.PyMjData

Attributes

act
act_dot
active_contacts_efc_pos
actuator_force
actuator_length
actuator_moment
actuator_velocity
body_jacp
body_jacr
body_xmat
body_xpos
body_xquat
body_xvelp
body_xvelr
cacc
cam_xmat
cam_xpos
cdof
cdof_dot
cfrc_ext
cfrc_int
cinert
contact
crb
ctrl
cvel
efc_AR
efc_AR_colind
efc_AR_rowadr
efc_AR_rownnz
efc_D
efc_J
efc_JT
efc_JT_colind
efc_JT_rowadr
efc_JT_rownnz
efc_J_colind
efc_J_rowadr
efc_J_rownnz
efc_R
efc_aref
efc_b
efc_diagApprox
efc_force
efc_frictionloss
efc_id
efc_margin
efc_solimp
efc_solref
efc_state
efc_type
efc_vel
energy
geom_jacp
geom_jacr
geom_xmat
geom_xpos
geom_xvelp
geom_xvelr
light_xdir
light_xpos
maxuse_con
maxuse_efc
maxuse_stack
mocap_pos
mocap_quat
nbuffer
ncon
ne
nefc
nf
nstack
pstack
qLD
qLDiagInv
qLDiagSqrtInv
qM
qacc
qacc_unc
qacc_warmstart
qfrc_actuator
qfrc_applied
qfrc_bias
qfrc_constraint
qfrc_inverse
qfrc_passive
qfrc_unc
qpos
qvel
sensordata
set_joint_qpos
set_joint_qvel
set_mocap_pos
set_mocap_quat
site_jacp
site_jacr
site_xmat
site_xpos
site_xvelp
site_xvelr
solver
solver_fwdinv
solver_iter
solver_nnz
subtree_angmom
subtree_com
subtree_linvel
ten_length
ten_moment
ten_velocity
ten_wrapadr
ten_wrapnum
time
timer
userdata
warning
wrap_obj
wrap_xpos
xanchor
xaxis
xfrc_applied
ximat
xipos

Methods

get_body_jacp(name)

Get the entry in jacp corresponding to the body with the given name

get_body_jacr(name)

Get the entry in jacr corresponding to the body with the given name

get_body_ximat(name)

Get the entry in ximat corresponding to the body with the given name

get_body_xipos(name)

Get the entry in xipos corresponding to the body with the given name

get_body_xmat(name)

Get the entry in xmat corresponding to the body with the given name

get_body_xpos(name)

Get the entry in xpos corresponding to the body with the given name

get_body_xquat(name)

Get the entry in xquat corresponding to the body with the given name

get_body_xvelp(name)

Get the entry in xvelp corresponding to the body with the given name

get_body_xvelr(name)

Get the entry in xvelr corresponding to the body with the given name

get_cam_xmat(name)

Get the entry in xmat corresponding to the cam with the given name

get_cam_xpos(name)

Get the entry in xpos corresponding to the cam with the given name

get_camera_xmat(name)

Get the entry in xmat corresponding to the camera with the given name

get_camera_xpos(name)

Get the entry in xpos corresponding to the camera with the given name

get_geom_jacp(name)

Get the entry in jacp corresponding to the geom with the given name

get_geom_jacr(name)

Get the entry in jacr corresponding to the geom with the given name

get_geom_xmat(name)

Get the entry in xmat corresponding to the geom with the given name

get_geom_xpos(name)

Get the entry in xpos corresponding to the geom with the given name

get_geom_xvelp(name)

Get the entry in xvelp corresponding to the geom with the given name

get_geom_xvelr(name)

Get the entry in xvelr corresponding to the geom with the given name

get_joint_qpos(name)

Get the entry in qpos corresponding to the joint with the given name

get_joint_qvel(name)

Get the entry in qvel corresponding to the joint with the given name

get_joint_xanchor(name)

Get the entry in xanchor corresponding to the joint with the given name

get_joint_xaxis(name)

Get the entry in xaxis corresponding to the joint with the given name

get_light_xdir(name)

Get the entry in xdir corresponding to the light with the given name

get_light_xpos(name)

Get the entry in xpos corresponding to the light with the given name

get_mocap_pos(name)

Get the entry in pos corresponding to the mocap with the given name

get_mocap_quat(name)

Get the entry in quat corresponding to the mocap with the given name

get_site_jacp(name)

Get the entry in jacp corresponding to the site with the given name

get_site_jacr(name)

Get the entry in jacr corresponding to the site with the given name

get_site_xmat(name)

Get the entry in xmat corresponding to the site with the given name

get_site_xpos(name)

Get the entry in xpos corresponding to the site with the given name

get_site_xvelp(name)

Get the entry in xvelp corresponding to the site with the given name

get_site_xvelr(name)

Get the entry in xvelr corresponding to the site with the given name

MjSimPool: Batched simulation

class mujoco_py.MjSimPool

Keeps a pool of multiple MjSims and enables stepping them quickly in parallel.

Parameters:

sims : list of MjSim

List of simulators that make up the pool.

nsubsteps:

Number of substeps to run on step(). The individual simulators’ nsubstep will be ignored.

Attributes

Methods

static create_from_sim()

Create an MjSimPool by cloning the provided sim a total of nsims times. Returns the created MjSimPool.

Parameters:

sim : MjSim

The prototype to clone.

nsims : int

Number of clones to create.

forward()

Calls mj_forward on all simulations in parallel. If nsims is specified, than only the first nsims simulator are forwarded.

reset()

Resets all simulations in pool. If nsims is specified, than only the first nsims simulators are reset.

step()

Calls mj_step on all simulations in parallel, with nsubsteps as specified when the pool was created.

If nsims is specified, than only the first nsims simulator are stepped.

MjViewer: 3D rendering

class mujoco_py.MjViewerBasic(sim)[source]

A simple display GUI showing the scene of an MjSim with a mouse-movable camera.

MjViewer extends this class to provide more sophisticated playback and interaction controls.

Parameters:

sim : MjSim

The simulator to display.

Attributes

Methods

render()[source]

Render the current simulation state to the screen or off-screen buffer. Call this in your main loop.

class mujoco_py.MjViewer(sim)[source]

Extends MjViewerBasic to add video recording, interactive time and interaction controls.

The key bindings are as follows:

  • TAB: Switch between MuJoCo cameras.
  • H: Toggle hiding all GUI components.
  • SPACE: Pause/unpause the simulation.
  • RIGHT: Advance simulation by one step.
  • V: Start/stop video recording.
  • T: Capture screenshot.
  • I: Drop into ipdb debugger.
  • S/F: Decrease/Increase simulation playback speed.
  • C: Toggle visualization of contact forces (off by default).
  • D: Enable/disable frame skipping when rendering lags behind real time.
  • R: Toggle transparency of geoms.
  • M: Toggle display of mocap bodies.
Parameters:

sim : MjSim

The simulator to display.

Attributes

Methods

render()[source]

Render the current simulation state to the screen or off-screen buffer. Call this in your main loop.