LyceumMuJoCo

LyceumMuJoCo uses MuJoCo.jl to provide the following:

  • MuJoCo-based environments that implement the AbstractEnvironment interface.
  • The MJSim type and related utilities for combining a jlModel and jlData from MuJoCo.jl to provide a full simulation.

Note that to use MuJoCo, you'll need a valid license which you can obtain from here. Up to three thirty-day trials can be obtained for free from MuJoCo's webiste, while students are eligible for a free personal license. Once you have obtained the license file, set the environment variable MUJOCO_KEY_PATH to point to its location. On Linux machines this would look like:

$ export MUJOCO_KEY_PATH=/path/to/mjkey.txt

AbstractMuJoCoEnvironment

To create a new MuJoCo-based environment, you will need to:

  1. Define a type Env that subtypes AbstractMuJoCoEnvironment <: LyceumBase.AbstractEnvironment.
  2. Implement the AbstractEnvironment interface.
  3. Additionally, implement the method getsim(env::Env) --> MJSim that returns the underlying MJSim which is used to provide defaults and other features.
LyceumMuJoCo.AbstractMuJoCoEnvironmentType
abstract type AbstractMuJoCoEnvironment <: LyceumBase.AbstractEnvironment

The supertype for all MuJoCo-based environments. Subtypes of AbstractMuJoCoEnvironment provide default functions for state, action, and observation (e.g. setstate!). For more information, see the documentation for MJSim.

LyceumMuJoCo.getsimFunction
getsim(env::LyceumMuJoCo.AbstractMuJoCoEnvironment) -> MJSim

Return env's underlying MJSim that defines the MuJoCo physics simulation. This is used for providing default state, action, and observation functions as well as the visualizer provided by LyceumMuJoCoViz.

MJSim

LyceumMuJoCo.MJSimType
MJSim

The MJSim type couples a jlModel and jlData from MuJoCo.jl to provide a full simulation.

The following are the official/internal/minimum set of fields from jlData for state, observation, and action in MuJoCo:

  • State: (time, qpos, qvel, act, mocap_pos, mocap_quat, userdata, qacc_warmstart)
  • Observation: sensordata
  • Action: (ctrl, qfrc_applied, xfrc_applied)

MJSim follows this definition except for actions (e.g. setaction!), which is composed of justctrl` by default.

For more information, see the "State and control" section of the MuJoCo Documentation

Fields

  • m::jlModel: contains the model description and is expected to remain constant.
  • d::jlData: contains all dynamic variables and intermediate results.
  • mn::Tuple: named-access version of MJSim.m provided by AxisArrays.jl.
  • dn::Tuple: named-access version of MJSim.d provided by AxisArrays.jl.
  • initstate::Vector{mjtNum}: The initial state vector at the time when this MJSim was constructed.
  • skip::Int: the number of times the simulation is integrated, yielding an effective simulation timestep of skip * m.opt.timestep.
LyceumBase.setstate!Method
setstate!(sim, state)

Copy the components of state to their respective fields in sim.d, namely:

(time, qpos, qvel, act, mocap_pos, mocap_quat, userdata, qacc_warmstart)
LyceumBase.getstate!Method
getstate!(state, sim)

Copy the following state fields from sim.d into state:

(time, qpos, qvel, act, mocap_pos, mocap_quat, userdata, qacc_warmstart)
LyceumBase.obsspaceMethod
obsspace(sim::MJSim) -> Any

Return a description of sim's observation space.

LyceumBase.getobsMethod
getobs(sim::MJSim) -> Any

Return a copy of sim.d.sensordata.

LyceumMuJoCo.zeroctrl!Method
zeroctrl!(sim::MJSim) -> MJSim

Zero out sim.d.ctrl and compute new forward dynamics.

LyceumMuJoCo.zerofullctrl!Method
zerofullctrl!(sim::MJSim) -> MJSim

Zero out all of the fields in sim.d that contribute to forward dynamics calculations, namely ctrl, qfrc_applied, and xfrc_applied, and compute the forward dynamics.

LyceumMuJoCo.forward!Method
forward!(sim::MJSim) -> MJSim

Compute the forward dynamics of the simulation and store them in sim.d. Equivalent to mj_forward(sim.m, sim.d).

LyceumBase.timestepMethod
timestep(sim::MJSim) -> Float64

Return the effective timestep of sim. Equivalent to sim.skip * sim.m.opt.timestep.

Base.Libc.timeMethod
time(sim::MJSim) -> Float64

Return the current simulation time, in seconds, of sim. Equivalent to sim.d.time.