Package Overview

This page is a work-in-progress and will be updated later

Models with Named Access

Many MuJoCo models attach names to the various joints and bodies that make up the model. It is often convenient to select a single part of the body and access information that may be contained in the larger arrays of model or data. MuJoCo.jl provides a few wrapper functions that allow us to access the underlying data.

As an example, let's investigate the torso of our humanoid. If you display the torso object in the REPL, you can see the fields that can be accessed in this object.

import MuJoCo as MJ
model, data = MJ.sample_model_and_data();
MJ.step!(model, data);
torso = MJ.body(data, "torso")
DataBody:
id:       1
name:     "torso"
applied:  (6 x  )	Float64	[0.0, 0.0, 0.0, 0.0, 0.0, 0.0] (4 s.f.)
xpos:     (3 x  )	Float64	[0.0, 0.0, 1.282] (4 s.f.)
xquat:    (4 x  )	Float64	[1.0, 0.0, 0.0, 0.0] (4 s.f.)
xmat:     (9 x  )	Float64	[1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] (4 s.f.)
xipos:    (3 x  )	Float64	[-0.003864, 0.0, 1.236] (4 s.f.)
ximat:    (9 x  )	Float64	[0.9965, 0.0, 0.08305, 0.0, 1.0, 0.0, -0.08305, 0.0, 0.9965] (4 s.f.)
com:      (3 x  )	Float64	[0.01569, 0.0, 0.8498] (4 s.f.)
cinert:   (10 x  )	Float64	[0.9224, 0.9055, 0.03353, 0.0, 0.04248, 0.0, -0.1144, 0.0, 2.258, 5.854] (4 s.f.)
crb:      (10 x  )	Float64	[7.797, 7.482, 0.905, 0.0, -0.4014, 1.356e-18, 1.874e-16, 0.0, 8.438e-15, 40.84] (4 s.f.)
cvel:     (6 x  )	Float64	[0.0, 0.0, 0.0, 0.0, 0.0, 0.0] (4 s.f.)
linvel:   (3 x  )	Float64	[0.0, 0.0, 0.0] (4 s.f.)
angmom:   (3 x  )	Float64	[0.0, 0.0, 0.0] (4 s.f.)
cacc:     (6 x  )	Float64	[0.0, 0.0, 0.0, 0.0, 0.0, 0.0] (4 s.f.)
int:      (6 x  )	Float64	[0.0, 0.0, 0.0, 0.0, 0.0, 0.0] (4 s.f.)
ext:      (6 x  )	Float64	[0.0, 0.0, 0.0, 0.0, 0.0, 0.0] (4 s.f.)

For example, torso.com will give you a 3-dimensional vector of the torso's centre of mass coordinates.

torso.com
3-element view(transpose(::UnsafeArrays.UnsafeArray{Float64, 2}), 2, Base.OneTo(3)) with eltype Float64:
 0.015685595769818515
 0.0
 0.8498401745105665

All other functions that generate a named wrapper around an object are documented in Named Access.

Row vs. Column-Major Arrays

MuJoCo's underlying C API expects arrays to be row-major, while by default, all Julia arrays are column-major. However, Julia is high level enough to allow us to mimic the use of a row-major array by changing the type of the object, while keeping the array access patterns the same.

We have included mj_array and mj_zeros to make life easier when passing arrays to MuJoCo functions that directly mutate their arguments (eg: mjd_transitionFD and many others). An array initialised with either mj_array or mj_zeros will be a transpose(<:AbstractArray) and can be treated just the same as any other Julia array, but its memory will be accessed in row-major order. This means that the C API will correctly fill your arrays. Using these functions also still allows for performance specialisation based on the type.

Let's look at an example. Suppose we want to compute a Jacobian for the humanoid's torso. There are model.nv degrees of freedom in the humanoid, and the torso's centre of mass is a 3-element vector. The Jacobian should therefore be a 3 x nv array. To ensure the order of elements is correct, we compute it with

jac_torso = MJ.mj_zeros(3, model.nv)
MJ.mj_jacSubtreeCom(model, data, jac_torso, torso.id)
@show jac_torso
3×27 transpose(::Matrix{Float64}) with eltype Float64:
 1.0  0.0  0.0   0.0          -0.43216    …   0.00759728  -0.00466693
 0.0  1.0  0.0   0.43216       0.0           -0.00846557  -0.00233347
 0.0  0.0  1.0  -2.37843e-18  -0.0156856      0.00846557   0.00233347
Beware the row-major order

Passing a 3 x nv array directly to mj_jacSubtreeCom will not raise an error, but the order of elements in the Jacobian will be incorrect. For example:

jac_torso_wrong = zeros(3, model.nv)
MJ.mj_jacSubtreeCom(model, data, jac_torso_wrong, torso.id)
@show jac_torso_wrong
3×27 Matrix{Float64}:
 1.0   0.0           0.0        0.0         …  -0.00927389  -0.00927389
 0.0  -0.43216      -0.312595  -0.00153332      0.00846557   0.00846557
 0.0   2.37843e-18   0.0       -0.0787638       0.00233347   0.00233347

More examples of working with matrices in MuJoCo are provided in Balancing a Cart-Pole and Humanoid LQR. For more information on row-major vs column major, see the Wikipedia page.

Wrapped Functions

Similar to the Python API, we have wrapped several functions to allow the use of native Julia arrays. The majority of functions that take arrays as arguments have been wrapped to apply some basic bounds checks for the size of the arrays, along with a restriction of the type that can be passed in.

Some of the function signatures have been changed to remove superfluous arguments that can be inferred by the data stored in the Julia arrays, for example:

println(methods(MJ.mju_add).ms[1])
mju_add(res::AbstractVecOrMat{Float64}, vec1::AbstractVecOrMat{Float64}, vec2::AbstractVecOrMat{Float64}) @ MuJoCo ~/work/MuJoCo.jl/MuJoCo.jl/src/function_constraints.jl:1332

vs the original:

println(methods(MJ.LibMuJoCo.mju_add).ms[1])
mju_add(res, vec1, vec2, n) @ MuJoCo.LibMuJoCo ~/work/MuJoCo.jl/MuJoCo.jl/src/LibMuJoCo/functions.jl:2384

The mj_ functions that have been wrapped are the defaults and can be found in src/function_constraints.jl and are documented in the MuJoCo API. If required, the original functions can be accessed inside the submodule LibMuJoCo.

Tips and Tricks

  1. This library is a wrapper for MuJoCo. The documentation for MuJoCo is very comprehensive and should be referred to for any queries regarding usage of the simulator.

  2. All functions or structs beginning with mj directly use the underlying C API.

  3. When writing code, keep a REPL open with a sample data and model object (such as generated in the above examples), and use tab-completition (double tap tab) to see what information is available. Check the MuJoCo docs or the LibMuJoCo Index to read the documentation for the parameters.

  4. Read documentation for the field names of the objects using the show_docs function, e.g. type show_docs(model, :nv) or show_docs(Model, :nv) in the REPL to get a print out of the docs for that field.