MuJoCo API

MuJoCo

MuJoCo.Wrappers.show_docsFunction
show_docs(obj, field::Symbol)

Prints the documentation for the field of obj (as in obj.field) to the console.

obj can be supplied as a type instead if no instances are available.

Example Usage

Usage with a direct type:

julia> show_docs(Model, :nv)
Model.nv: number of degrees of freedom = dim(qvel)

Usage with an instance:

julia> model, data = MuJoCo.sample_model_and_data();
julia> show_docs(model, :nq)
Model.nq: number of generalized coordinates = dim(qpos)
julia> show_docs(data, :qvel)
Data.qvel: velocity (nv x 1)
source
MuJoCo.init_dataMethod
init_data(model::Model)

Creates an instance of the data required for the step! simulation.

Returns a Data object, wrapping the underlying mjData object.

source
MuJoCo.init_visualiserMethod
init_visualiser()

Loads the packages necessary for the running the visualiser.

Add the following packages to your project to be able to use the visualisation features, or run "install_visualiser()".

Packages:

  • BangBang
  • FFMPEG
  • GLFW
  • Observables
  • PrettyTables
  • Printf
  • StaticArrays
source
MuJoCo.install_visualiserMethod
install_visualiser()

Installs the necessary packages for the running the visualiser into the current running environment.

Packages:

  • BangBang
  • FFMPEG
  • GLFW
  • Observables
  • PrettyTables
  • Printf
  • StaticArrays
source
MuJoCo.load_modelMethod
load_model(path)

Determines the type of file by the extension and loads the model into memory.

To use this model in a simulator, you will also need the corresponding data, obtained using init_data.

Expected files types: 'xml', 'mjcf', or 'mjb' (or uppercase variants).

Examples

model = load_model(MuJoCo.humanoid_model_file())
data = init_data(model)
source
MuJoCo.mj_addMMethod
mj_addM(m, d, dst, rownnz, rowadr, colind)

Add inertia matrix to destination matrix. Destination can be sparse uncompressed, or dense when all int* are NULL

Arguments

  • m::Model -> Constant.
  • d::Data
  • dst::Vector{Float64} -> A vector of variable size. dst should be a vector, not a matrix. dst should be of size nM.
  • rownnz::Vector{Int32} -> A vector of variable size. rownnz should be a vector, not a matrix. rownnz should be of size nv.
  • rowadr::Vector{Int32} -> A vector of variable size. rowadr should be a vector, not a matrix. rowadr should be of size nv.
  • colind::Vector{Int32} -> A vector of variable size. colind should be a vector, not a matrix. colind should be of size nM.
source
MuJoCo.mj_angmomMatMethod
mj_angmomMat(m, d, mat, body)

Compute subtree angular momentum matrix.

Arguments

  • m::Model -> Constant.
  • d::Data
  • mat::Matrix{Float64} -> A matrix of variable size. mat should be of shape (3, nv).
  • body::Int32
source
MuJoCo.mj_applyFTMethod
mj_applyFT(m, d, force, torque, point, body, qfrc_target)

Apply Cartesian force and torque (outside xfrc_applied mechanism).

Arguments

  • m::Model -> Constant.
  • d::Data
  • force::Vector{Float64} -> A vector of size 3. force should be a vector of size 3. Constant.
  • torque::Vector{Float64} -> A vector of size 3. torque should be a vector of size 3. Constant.
  • point::Vector{Float64} -> A vector of size 3. point should be a vector of size 3. Constant.
  • body::Int32
  • qfrc_target::Vector{Float64} -> A vector of variable size. qfrc_target should be a vector, not a matrix. qfrc_target should be of size nv.
source
MuJoCo.mj_arrayMethod
mj_array([element_type=mjtNum], dims...)

Allocates an array compatible with the underlying MuJoCo C API.

The C API treats arrays as row-major, while by default arrays in Julia are column-major. This function will create an array which is accessed in a row-major way, but can be treated by a normal array in your Julia code.

Arguments

  • element_type: Defaults to mjtNum (typically Float64).
  • dims: The dimensionality of output array. Can either be a tuple of integers or a series of integers.
source
MuJoCo.mj_constraintUpdateMethod
mj_constraintUpdate(m, d, jar, cost, flg_coneHessian)

Compute efcstate, efcforce, qfrc_constraint, and (optionally) cone Hessians. If cost is not NULL, set cost = s(jar) where jar = Jacqacc-aref.

Arguments

  • m::Model -> Constant.
  • d::Data
  • jar::Vector{Float64} -> A vector of variable size. jar should be a vector, not a matrix. size of jar should equal nefc. Constant.
  • cost::Vector{Float64} -> An optional vector of size 1. cost should be a vector of size 1. Can set to nothing if not required.
  • flg_coneHessian::Int32
source
MuJoCo.mj_differentiatePosMethod
mj_differentiatePos(m, qvel, dt, qpos1, qpos2)

Compute velocity by finite-differencing two positions.

Arguments

  • m::Model -> Constant.
  • qvel::Vector{Float64} -> A vector of variable size. qvel should be a vector, not a matrix. qvel should be of size nv.
  • dt::Float64
  • qpos1::Vector{Float64} -> A vector of variable size. qpos1 should be a vector, not a matrix. qpos1 should be of size nq. Constant.
  • qpos2::Vector{Float64} -> A vector of variable size. qpos2 should be a vector, not a matrix. qpos2 should be of size nq. Constant.
source
MuJoCo.mj_fullMMethod
mj_fullM(m, dst, M)

Convert sparse inertia matrix M into full (i.e. dense) matrix.

Arguments

  • m::Model -> Constant.
  • dst::Matrix{Float64} -> A matrix of variable size. dst should be of shape (nv, nv).
  • M::Vector{Float64} -> A vector of variable size. M should be a vector, not a matrix. M should be of size nM. Constant.
source
MuJoCo.mj_geomDistanceMethod
mj_geomDistance(m, d, geom1, geom2, distmax, fromto)

Returns smallest signed distance between two geoms and optionally segment from geom1 to geom2.

Arguments

  • m::Model -> Constant.
  • d::Data -> Constant.
  • geom1::Int32
  • geom2::Int32
  • distmax::Float64
  • fromto::Matrix{Float64} -> An optional matrix of variable size. fromto should be of size 6. Can set to nothing if not required.
source
MuJoCo.mj_getStateMethod
mj_getState(m, d, state, spec)

Get state.

Arguments

  • m::Model -> Constant.
  • d::Data -> Constant.
  • state::Vector{Float64} -> A vector of variable size. state should be a vector, not a matrix. state size should equal mj_stateSize(m, spec).
  • spec::Int32
source
MuJoCo.mj_integratePosMethod
mj_integratePos(m, qpos, qvel, dt)

Integrate position with given velocity.

Arguments

  • m::Model -> Constant.
  • qpos::Vector{Float64} -> A vector of variable size. qpos should be a vector, not a matrix. qpos should be of size nq.
  • qvel::Vector{Float64} -> A vector of variable size. qvel should be a vector, not a matrix. qvel should be of size nv. Constant.
  • dt::Float64
source
MuJoCo.mj_jacMethod
mj_jac(m, d, jacp, jacr, point, body)

Compute 3/6-by-nv end-effector Jacobian of global point attached to given body.

Arguments

  • m::Model -> Constant.
  • d::Data
  • jacp::Matrix{Float64} -> An optional matrix of variable size. jacp should be of shape (3, nv). Can set to nothing if not required.
  • jacr::Matrix{Float64} -> An optional matrix of variable size. jacr should be of shape (3, nv). Can set to nothing if not required.
  • point::Vector{Float64} -> A vector of size 3. point should be a vector of size 3. Constant.
  • body::Int32
source
MuJoCo.mj_jacBodyMethod
mj_jacBody(m, d, jacp, jacr, body)

Compute body frame end-effector Jacobian.

Arguments

  • m::Model -> Constant.
  • d::Data
  • jacp::Matrix{Float64} -> An optional matrix of variable size. jacp should be of shape (3, nv). Can set to nothing if not required.
  • jacr::Matrix{Float64} -> An optional matrix of variable size. jacr should be of shape (3, nv). Can set to nothing if not required.
  • body::Int32
source
MuJoCo.mj_jacBodyComMethod
mj_jacBodyCom(m, d, jacp, jacr, body)

Compute body center-of-mass end-effector Jacobian.

Arguments

  • m::Model -> Constant.
  • d::Data
  • jacp::Matrix{Float64} -> An optional matrix of variable size. jacp should be of shape (3, nv). Can set to nothing if not required.
  • jacr::Matrix{Float64} -> An optional matrix of variable size. jacr should be of shape (3, nv). Can set to nothing if not required.
  • body::Int32
source
MuJoCo.mj_jacGeomMethod
mj_jacGeom(m, d, jacp, jacr, geom)

Compute geom end-effector Jacobian.

Arguments

  • m::Model -> Constant.
  • d::Data
  • jacp::Matrix{Float64} -> An optional matrix of variable size. jacp should be of shape (3, nv). Can set to nothing if not required.
  • jacr::Matrix{Float64} -> An optional matrix of variable size. jacr should be of shape (3, nv). Can set to nothing if not required.
  • geom::Int32
source
MuJoCo.mj_jacPointAxisMethod
mj_jacPointAxis(m, d, jacp, jacr, point, axis, body)

Compute translation end-effector Jacobian of point, and rotation Jacobian of axis.

Arguments

  • m::Model -> Constant.
  • d::Data
  • jacp::Matrix{Float64} -> An optional matrix of variable size. jacp should be of shape (3, nv). Can set to nothing if not required.
  • jacr::Matrix{Float64} -> An optional matrix of variable size. jacr should be of shape (3, nv). Can set to nothing if not required.
  • point::Vector{Float64} -> A vector of size 3. point should be a vector of size 3. Constant.
  • axis::Vector{Float64} -> A vector of size 3. axis should be a vector of size 3. Constant.
  • body::Int32
source
MuJoCo.mj_jacSiteMethod
mj_jacSite(m, d, jacp, jacr, site)

Compute site end-effector Jacobian.

Arguments

  • m::Model -> Constant.
  • d::Data
  • jacp::Matrix{Float64} -> An optional matrix of variable size. jacp should be of shape (3, nv). Can set to nothing if not required.
  • jacr::Matrix{Float64} -> An optional matrix of variable size. jacr should be of shape (3, nv). Can set to nothing if not required.
  • site::Int32
source
MuJoCo.mj_jacSubtreeComMethod
mj_jacSubtreeCom(m, d, jacp, body)

Compute subtree center-of-mass end-effector Jacobian.

Arguments

  • m::Model -> Constant.
  • d::Data
  • jacp::Matrix{Float64} -> An optional matrix of variable size. jacp should be of shape (3, nv). Can set to nothing if not required.
  • body::Int32
source
MuJoCo.mj_mulJacTVecMethod
mj_mulJacTVec(m, d, res, vec)

Multiply dense or sparse constraint Jacobian transpose by vector.

Arguments

  • m::Model -> Constant.
  • d::Data
  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix. res should be of length nv.
  • vec::Vector{Float64} -> A vector of variable size. vec should be a vector, not a matrix. vec should be of length nefc. Constant.
source
MuJoCo.mj_mulJacVecMethod
mj_mulJacVec(m, d, res, vec)

Multiply dense or sparse constraint Jacobian by vector.

Arguments

  • m::Model -> Constant.
  • d::Data
  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix. res should be of length nefc.
  • vec::Vector{Float64} -> A vector of variable size. vec should be a vector, not a matrix. vec should be of length nv. Constant.
source
MuJoCo.mj_mulMMethod
mj_mulM(m, d, res, vec)

Multiply vector by inertia matrix.

Arguments

  • m::Model -> Constant.
  • d::Data -> Constant.
  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix. res should be of size nv.
  • vec::Vector{Float64} -> A vector of variable size. vec should be a vector, not a matrix. vec should be of size nv. Constant.
source
MuJoCo.mj_mulM2Method
mj_mulM2(m, d, res, vec)

Multiply vector by (inertia matrix)^(1/2).

Arguments

  • m::Model -> Constant.
  • d::Data -> Constant.
  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix. res should be of size nv.
  • vec::Vector{Float64} -> A vector of variable size. vec should be a vector, not a matrix. vec should be of size nv. Constant.
source
MuJoCo.mj_multiRayMethod
mj_multiRay(m, d, pnt, vec, geomgroup, flg_static, bodyexclude, geomid, dist, nray, cutoff)

Intersect multiple rays emanating from a single point. Similar semantics to mj_ray, but vec is an array of (nray x 3) directions.

Arguments

  • m::Model -> Constant.
  • d::Data
  • pnt::Vector{Float64} -> A vector of size 3. pnt should be a vector of size 3. Constant.
  • vec::Vector{Float64} -> A vector of variable size. vec should be a vector, not a matrix. vec should be of size 3*nray. Constant.
  • geomgroup::Vector{UInt8} -> An optional vector of size 6. geomgroup should be a vector of size 6. Can set to nothing if not required. Constant.
  • flg_static::UInt8
  • bodyexclude::Int32
  • geomid::Vector{Int32} -> A vector of variable size. geomid should be a vector, not a matrix. dist and geomid should be of size nray.
  • dist::Vector{Float64} -> A vector of variable size. dist should be a vector, not a matrix. dist and geomid should be of size nray.
  • nray::Int32
  • cutoff::Float64
source
MuJoCo.mj_normalizeQuatMethod
mj_normalizeQuat(m, qpos)

Normalize all quaternions in qpos-type vector.

Arguments

  • m::Model -> Constant.
  • qpos::Vector{Float64} -> A vector of variable size. qpos should be a vector, not a matrix. qpos should be of size nq.
source
MuJoCo.mj_rayMethod
mj_ray(m, d, pnt, vec, geomgroup, flg_static, bodyexclude, geomid)

Intersect ray (pnt+x*vec, x>=0) with visible geoms, except geoms in bodyexclude. Return distance (x) to nearest surface, or -1 if no intersection and output geomid. geomgroup, flg_static are as in mjvOption; geomgroup==NULL skips group exclusion.

Arguments

  • m::Model -> Constant.
  • d::Data -> Constant.
  • pnt::Vector{Float64} -> A vector of size 3. pnt should be a vector of size 3. Constant.
  • vec::Vector{Float64} -> A vector of size 3. vec should be a vector of size 3. Constant.
  • geomgroup::Vector{UInt8} -> An optional vector of size 6. geomgroup should be a vector of size 6. Can set to nothing if not required. Constant.
  • flg_static::UInt8
  • bodyexclude::Int32
  • geomid::Vector{Int32} -> A vector of size 1. geomid should be a vector of size 1.
source
MuJoCo.mj_rneMethod
mj_rne(m, d, flg_acc, result)

RNE: compute M(qpos)*qacc + C(qpos,qvel); flg_acc=0 removes inertial term.

Arguments

  • m::Model -> Constant.
  • d::Data
  • flg_acc::Int32
  • result::Vector{Float64} -> A vector of variable size. result should be a vector, not a matrix. result should have length nv.
source
MuJoCo.mj_setStateMethod
mj_setState(m, d, state, spec)

Set state.

Arguments

  • m::Model -> Constant.
  • d::Data
  • state::Vector{Float64} -> A vector of variable size. state should be a vector, not a matrix. state size should equal mj_stateSize(m, spec).
  • spec::Int32
source
MuJoCo.mj_solveMMethod
mj_solveM(m, d, x, y)

Solve linear system M * x = y using factorization: x = inv(L'DL)*y

Arguments

  • m::Model -> Constant.
  • d::Data
  • x::Matrix{Float64} -> A matrix of variable size.
  • y::Matrix{Float64} -> A matrix of variable size. Constant.
source
MuJoCo.mj_solveM2Method
mj_solveM2(m, d, x, y)

Half of linear solve: x = sqrt(inv(D))inv(L')y

Arguments

  • m::Model -> Constant.
  • d::Data
  • x::Matrix{Float64} -> A matrix of variable size.
  • y::Matrix{Float64} -> A matrix of variable size. Constant.
source
MuJoCo.mj_zerosMethod
mj_zeros([element_type=mjtNum], dims...)

Allocates an array full of zeros, compatible with the underlying MuJoCo C API.

The C API treats arrays as row-major, while by default arrays in Julia are column-major. This function will create an array which is accessed in a row-major way, but can be treated by a normal array in your Julia code.

Arguments

  • element_type: The element type of the array. Defaults to mjtNum (typically Float64).
  • dims: The dimensionality of output array. Can either be a tuple of integers or a series of integers.
source
MuJoCo.mjd_inverseFDMethod
mjd_inverseFD(m, d, eps, flg_actuation, DfDq, DfDv, DfDa, DsDq, DsDv, DsDa, DmDq)

Finite differenced Jacobians of (force, sensors) = mjinverse(state, acceleration) All outputs are optional. Output dimensions (transposed w.r.t Control Theory convention): DfDq: (nv x nv) DfDv: (nv x nv) DfDa: (nv x nv) DsDq: (nv x nsensordata) DsDv: (nv x nsensordata) DsDa: (nv x nsensordata) DmDq: (nv x nM) single-letter shortcuts: inputs: q=qpos, v=qvel, a=qacc outputs: f=qfrcinverse, s=sensordata, m=qM notes: optionally computes mass matrix Jacobian DmDq flgactuation specifies whether to subtract qfrcactuator from qfrc_inverse

Arguments

  • m::Model -> Constant.
  • d::Data
  • eps::Float64
  • flg_actuation::UInt8
  • DfDq::Matrix{Float64} -> An optional matrix of variable size. DfDq should be of shape (nv, nv). Can set to nothing if not required.
  • DfDv::Matrix{Float64} -> An optional matrix of variable size. DfDv should be of shape (nv, nv). Can set to nothing if not required.
  • DfDa::Matrix{Float64} -> An optional matrix of variable size. DfDa should be of shape (nv, nv). Can set to nothing if not required.
  • DsDq::Matrix{Float64} -> An optional matrix of variable size. DsDq should be of shape (nv, nsensordata). Can set to nothing if not required.
  • DsDv::Matrix{Float64} -> An optional matrix of variable size. DsDv should be of shape (nv, nsensordata). Can set to nothing if not required.
  • DsDa::Matrix{Float64} -> An optional matrix of variable size. DsDa should be of shape (nv, nsensordata). Can set to nothing if not required.
  • DmDq::Matrix{Float64} -> An optional matrix of variable size. DmDq should be of shape (nv, nM). Can set to nothing if not required.
source
MuJoCo.mjd_subQuatMethod
mjd_subQuat(qa, qb, Da, Db)

Derivatives of mju_subQuat.

Arguments

  • qa::Vector{Float64} -> A vector of variable size. qa should be a vector, not a matrix. qa must have size 4. Constant.
  • qb::Vector{Float64} -> A vector of variable size. qb should be a vector, not a matrix. qb must have size 4. Constant.
  • Da::Matrix{Float64} -> An optional matrix of variable size. Da must have size 9. Can set to nothing if not required.
  • Db::Matrix{Float64} -> An optional matrix of variable size. Db must have size 9. Can set to nothing if not required.
source
MuJoCo.mjd_transitionFDMethod
mjd_transitionFD(m, d, eps, flg_centered, A, B, C, D)

Finite differenced transition matrices (control theory notation) d(x_next) = Adx + Bdu d(sensor) = Cdx + Ddu required output matrix dimensions: A: (2nv+na x 2nv+na) B: (2nv+na x nu) D: (nsensordata x 2nv+na) C: (nsensordata x nu)

Arguments

  • m::Model -> Constant.
  • d::Data
  • eps::Float64
  • flg_centered::UInt8
  • A::Matrix{Float64} -> An optional matrix of variable size. A should be of shape (2nv+na, 2nv+na). Can set to nothing if not required.
  • B::Matrix{Float64} -> An optional matrix of variable size. B should be of shape (2*nv+na, nu). Can set to nothing if not required.
  • C::Matrix{Float64} -> An optional matrix of variable size. C should be of shape (nsensordata, 2*nv+na). Can set to nothing if not required.
  • D::Matrix{Float64} -> An optional matrix of variable size. D should be of shape (nsensordata, nu). Can set to nothing if not required.
source
MuJoCo.mju_L1Method
mju_L1(vec)

Return L1 norm: sum(abs(vec)).

Arguments

  • vec::Vector{Float64} -> A vector of variable size. vec should be a vector, not a matrix.
source
MuJoCo.mju_addMethod
mju_add(res, vec1, vec2)

Set res = vec1 + vec2.

Arguments

  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix. res and vec1 should have the same size. res and vec2 should have the same size.
  • vec1::Vector{Float64} -> A vector of variable size. vec1 should be a vector, not a matrix. res and vec1 should have the same size. Constant.
  • vec2::Vector{Float64} -> A vector of variable size. vec2 should be a vector, not a matrix. res and vec2 should have the same size. Constant.
source
MuJoCo.mju_addSclMethod
mju_addScl(res, vec1, vec2, scl)

Set res = vec1 + vec2*scl.

Arguments

  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix. res and vec1 should have the same size. res and vec2 should have the same size.
  • vec1::Vector{Float64} -> A vector of variable size. vec1 should be a vector, not a matrix. res and vec1 should have the same size. Constant.
  • vec2::Vector{Float64} -> A vector of variable size. vec2 should be a vector, not a matrix. res and vec2 should have the same size. Constant.
  • scl::Float64
source
MuJoCo.mju_addToMethod
mju_addTo(res, vec)

Set res = res + vec.

Arguments

  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix. res and vec should have the same size.
  • vec::Vector{Float64} -> A vector of variable size. vec should be a vector, not a matrix. res and vec should have the same size. Constant.
source
MuJoCo.mju_addToSclMethod
mju_addToScl(res, vec, scl)

Set res = res + vec*scl.

Arguments

  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix. res and vec should have the same size.
  • vec::Vector{Float64} -> A vector of variable size. vec should be a vector, not a matrix. res and vec should have the same size. Constant.
  • scl::Float64
source
MuJoCo.mju_band2DenseMethod
mju_band2Dense(res, mat, ntotal, nband, ndense, flg_sym)

Convert banded matrix to dense matrix, fill upper triangle if flg_sym>0.

Arguments

  • res::Matrix{Float64} -> A matrix of variable size. res should have ntotal rows. res should have ntotal columns.
  • mat::Vector{Float64} -> A vector of variable size. mat should be a vector, not a matrix. Constant.
  • ntotal::Int32 -> res should have ntotal rows. res should have ntotal columns.
  • nband::Int32
  • ndense::Int32
  • flg_sym::UInt8
source
MuJoCo.mju_bandMulMatVecMethod
mju_bandMulMatVec(res, mat, vec, ntotal, nband, ndense, nVec, flg_sym)

Multiply band-diagonal matrix with nvec vectors, include upper triangle if flg_sym>0.

Arguments

  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix. res should have ntotal rows. res should have nVec columns.
  • mat::Matrix{Float64} -> A matrix of variable size. Constant.
  • vec::Matrix{Float64} -> A matrix of variable size. vec should have ntotal rows. vec should have nVec columns. Constant.
  • ntotal::Int32 -> res should have ntotal rows. vec should have ntotal rows.
  • nband::Int32
  • ndense::Int32
  • nVec::Int32 -> res should have nVec columns. vec should have nVec columns.
  • flg_sym::UInt8
source
MuJoCo.mju_boxQPMethod
mju_boxQP(res, R, index, H, g, lower, upper)

minimize 0.5x'Hx + x'g s.t. lower <= x <= upper, return rank or -1 if failed inputs: n - problem dimension H - SPD matrix nn g - bias vector n lower - lower bounds n upper - upper bounds n res - solution warmstart n return value: nfree <= n - rank of unconstrained subspace, -1 if failure outputs (required): res - solution n R - subspace Cholesky factor nfreenfree allocated: n(n+7) outputs (optional): index - set of free dimensions nfree allocated: n notes: the initial value of res is used to warmstart the solver R must have allocatd size n(n+7), but only nfree*nfree values are used in output index (if given) must have allocated size n, but only nfree values are used in output only the lower triangles of H and R and are read from and written to, respectively the convenience function mju_boxQPmalloc allocates the required data structures

Arguments

  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix.
  • R::Matrix{Float64} -> A matrix of variable size. size of R should be n*(n+7).
  • index::Vector{Int32} -> An optional vector of variable size. index should be a vector, not a matrix. size of index should equal n. Can set to nothing if not required.
  • H::Matrix{Float64} -> A matrix of variable size. H should be of shape (n, n). Constant.
  • g::Vector{Float64} -> A vector of variable size. g should be a vector, not a matrix. size of g should equal n. Constant.
  • lower::Vector{Float64} -> An optional vector of variable size. lower should be a vector, not a matrix. size of lower should equal n. Can set to nothing if not required. Constant.
  • upper::Vector{Float64} -> An optional vector of variable size. upper should be a vector, not a matrix. size of upper should equal n. Can set to nothing if not required. Constant.
source
MuJoCo.mju_cholFactorMethod
mju_cholFactor(mat, mindiag)

Cholesky decomposition: mat = L*L'; return rank, decomposition performed in-place into mat.

Arguments

  • mat::Matrix{Float64} -> A matrix of variable size. mat should be a square matrix.
  • mindiag::Float64
source
MuJoCo.mju_cholFactorBandMethod
mju_cholFactorBand(mat, ntotal, nband, ndense, diagadd, diagmul)

Band-dense Cholesky decomposition. Returns minimum value in the factorized diagonal, or 0 if rank-deficient. mat has (ntotal-ndense) x nband + ndense x ntotal elements. The first (ntotal-ndense) x nband store the band part, left of diagonal, inclusive. The second ndense x ntotal store the band part as entire dense rows. Add diagadd+diagmul*mat_ii to diagonal before factorization.

Arguments

  • mat::Vector{Float64} -> A vector of variable size. mat should be a vector, not a matrix.
  • ntotal::Int32
  • nband::Int32
  • ndense::Int32
  • diagadd::Float64
  • diagmul::Float64
source
MuJoCo.mju_cholSolveMethod
mju_cholSolve(res, mat, vec)

Solve (mat*mat') * res = vec, where mat is a Cholesky factor.

Arguments

  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix.
  • mat::Matrix{Float64} -> A matrix of variable size. mat should be a square matrix. Constant.
  • vec::Vector{Float64} -> A vector of variable size. vec should be a vector, not a matrix. Constant.
source
MuJoCo.mju_cholSolveBandMethod
mju_cholSolveBand(res, mat, vec, ntotal, nband, ndense)

Solve (matmat')res = vec where mat is a band-dense Cholesky factor.

Arguments

  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix. size of res should equal ntotal.
  • mat::Vector{Float64} -> A vector of variable size. mat should be a vector, not a matrix. Constant.
  • vec::Vector{Float64} -> A vector of variable size. vec should be a vector, not a matrix. size of vec should equal ntotal. Constant.
  • ntotal::Int32
  • nband::Int32
  • ndense::Int32
source
MuJoCo.mju_cholUpdateMethod
mju_cholUpdate(mat, x, flg_plus)

Cholesky rank-one update: LL' +/- xx'; return rank.

Arguments

  • mat::Matrix{Float64} -> A matrix of variable size. mat should be a square matrix.
  • x::Vector{Float64} -> A vector of variable size. x should be a vector, not a matrix.
  • flg_plus::Int32
source
MuJoCo.mju_copyMethod
mju_copy(res, data)

Set res = vec.

Arguments

  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix. res and data should have the same size.
  • data::Vector{Float64} -> A vector of variable size. data should be a vector, not a matrix. res and data should have the same size. Constant.
source
MuJoCo.mju_d2nMethod
mju_d2n(res, vec)

Convert from double to mjtNum.

Arguments

  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix. res and vec should have the same size.
  • vec::Vector{Float64} -> A vector of variable size. vec should be a vector, not a matrix. res and vec should have the same size. Constant.
source
MuJoCo.mju_decodePyramidMethod
mju_decodePyramid(force, pyramid, mu)

Convert pyramid representation to contact force.

Arguments

  • force::Vector{Float64} -> A vector of variable size. force should be a vector, not a matrix.
  • pyramid::Vector{Float64} -> A vector of variable size. pyramid should be a vector, not a matrix. Constant.
  • mu::Vector{Float64} -> A vector of variable size. mu should be a vector, not a matrix. Constant.
source
MuJoCo.mju_dense2BandMethod
mju_dense2Band(res, mat, ntotal, nband, ndense)

Convert dense matrix to banded matrix.

Arguments

  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix.
  • mat::Matrix{Float64} -> A matrix of variable size. mat should have ntotal rows. mat should have ntotal columns. Constant.
  • ntotal::Int32 -> mat should have ntotal rows. mat should have ntotal columns.
  • nband::Int32
  • ndense::Int32
source
MuJoCo.mju_dotMethod
mju_dot(vec1, vec2)

Return dot-product of vec1 and vec2.

Arguments

  • vec1::Vector{Float64} -> A vector of variable size. vec1 should be a vector, not a matrix. vec1 and vec2 should have the same size. Constant.
  • vec2::Vector{Float64} -> A vector of variable size. vec2 should be a vector, not a matrix. vec1 and vec2 should have the same size. Constant.
source
MuJoCo.mju_encodePyramidMethod
mju_encodePyramid(pyramid, force, mu)

Convert contact force to pyramid representation.

Arguments

  • pyramid::Vector{Float64} -> A vector of variable size. pyramid should be a vector, not a matrix.
  • force::Vector{Float64} -> A vector of variable size. force should be a vector, not a matrix. Constant.
  • mu::Vector{Float64} -> A vector of variable size. mu should be a vector, not a matrix. Constant.
source
MuJoCo.mju_eyeMethod
mju_eye(mat)

Set mat to the identity matrix.

Arguments

  • mat::Matrix{Float64} -> A matrix of variable size. mat should be square.
source
MuJoCo.mju_f2nMethod
mju_f2n(res, vec)

Convert from float to mjtNum.

Arguments

  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix. res and vec should have the same size.
  • vec::Vector{Float32} -> A vector of variable size. vec should be a vector, not a matrix. res and vec should have the same size. Constant.
source
MuJoCo.mju_fillMethod
mju_fill(res, val)

Set res = val.

Arguments

  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix.
  • val::Float64
source
MuJoCo.mju_insertionSortMethod
mju_insertionSort(res)

Insertion sort, resulting list is in increasing order.

Arguments

  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix.
source
MuJoCo.mju_insertionSortIntMethod
mju_insertionSortInt(res)

Integer insertion sort, resulting list is in increasing order.

Arguments

  • res::Vector{Int32} -> A vector of variable size. res should be a vector, not a matrix.
source
MuJoCo.mju_isZeroMethod
mju_isZero(vec)

Return 1 if all elements are 0.

Arguments

  • vec::Vector{Float64} -> A vector of variable size. vec should be a vector, not a matrix.
source
MuJoCo.mju_mulMatMatMethod
mju_mulMatMat(res, mat1, mat2)

Multiply matrices: res = mat1 * mat2.

Arguments

  • res::Matrix{Float64} -> A matrix of variable size. #rows in res should equal #rows in mat1.
  • mat1::Matrix{Float64} -> A matrix of variable size. #columns in mat1 should equal #rows in mat2. Constant.
  • mat2::Matrix{Float64} -> A matrix of variable size. Constant.
source
MuJoCo.mju_mulMatMatTMethod
mju_mulMatMatT(res, mat1, mat2)

Multiply matrices, second argument transposed: res = mat1 * mat2'.

Arguments

  • res::Matrix{Float64} -> A matrix of variable size. #rows in res should equal #rows in mat1. #columns in res should equal #rows in mat2.
  • mat1::Matrix{Float64} -> A matrix of variable size. Constant.
  • mat2::Matrix{Float64} -> A matrix of variable size. Constant.
source
MuJoCo.mju_mulMatTMatMethod
mju_mulMatTMat(res, mat1, mat2)

Multiply matrices, first argument transposed: res = mat1' * mat2.

Arguments

  • res::Matrix{Float64} -> A matrix of variable size. #rows in res should equal #columns in mat1.
  • mat1::Matrix{Float64} -> A matrix of variable size. #rows in mat1 should equal #rows in mat2. Constant.
  • mat2::Matrix{Float64} -> A matrix of variable size. Constant.
source
MuJoCo.mju_mulMatTVecMethod
mju_mulMatTVec(res, mat, vec)

Multiply transposed matrix and vector: res = mat' * vec.

Arguments

  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix.
  • mat::Matrix{Float64} -> A matrix of variable size. Constant.
  • vec::Vector{Float64} -> A vector of variable size. vec should be a vector, not a matrix. Constant.
source
MuJoCo.mju_mulMatVecMethod
mju_mulMatVec(res, mat, vec)

Multiply matrix and vector: res = mat * vec.

Arguments

  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix.
  • mat::Matrix{Float64} -> A matrix of variable size. Constant.
  • vec::Vector{Float64} -> A vector of variable size. vec should be a vector, not a matrix. Constant.
source
MuJoCo.mju_mulVecMatVecMethod
mju_mulVecMatVec(vec1, mat, vec2)

Multiply square matrix with vectors on both sides: returns vec1' * mat * vec2.

Arguments

  • vec1::Vector{Float64} -> A vector of variable size. vec1 should be a vector, not a matrix. Constant.
  • mat::Matrix{Float64} -> A matrix of variable size. Constant.
  • vec2::Vector{Float64} -> A vector of variable size. vec2 should be a vector, not a matrix. Constant.
source
MuJoCo.mju_n2dMethod
mju_n2d(res, vec)

Convert from mjtNum to double.

Arguments

  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix. res and vec should have the same size.
  • vec::Vector{Float64} -> A vector of variable size. vec should be a vector, not a matrix. res and vec should have the same size. Constant.
source
MuJoCo.mju_n2fMethod
mju_n2f(res, vec)

Convert from mjtNum to float.

Arguments

  • res::Vector{Float32} -> A vector of variable size. res should be a vector, not a matrix. res and vec should have the same size.
  • vec::Vector{Float64} -> A vector of variable size. vec should be a vector, not a matrix. res and vec should have the same size. Constant.
source
MuJoCo.mju_normMethod
mju_norm(vec)

Return vector length (without normalizing vector).

Arguments

  • vec::Vector{Float64} -> A vector of variable size. vec should be a vector, not a matrix. Constant.
source
MuJoCo.mju_normalizeMethod
mju_normalize(vec)

Normalize vector, return length before normalization.

Arguments

  • vec::Vector{Float64} -> A vector of variable size. vec should be a vector, not a matrix.
source
MuJoCo.mju_printMatMethod
mju_printMat(mat)

Print matrix to screen.

Arguments

  • mat::Matrix{Float64} -> A matrix of variable size. Constant.
source
MuJoCo.mju_sclMethod
mju_scl(res, vec, scl)

Set res = vec*scl.

Arguments

  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix. res and vec should have the same size.
  • vec::Vector{Float64} -> A vector of variable size. vec should be a vector, not a matrix. res and vec should have the same size. Constant.
  • scl::Float64
source
MuJoCo.mju_sqrMatTDMethod
mju_sqrMatTD(res, mat, diag)

Set res = mat' * diag * mat if diag is not NULL, and res = mat' * mat otherwise.

Arguments

  • res::Matrix{Float64} -> A matrix of variable size. #rows in res should equal #columns in mat.
  • mat::Matrix{Float64} -> A matrix of variable size. Constant.
  • diag::Vector{Float64} -> An optional vector of variable size. diag should be a vector, not a matrix. Can set to nothing if not required.
source
MuJoCo.mju_subMethod
mju_sub(res, vec1, vec2)

Set res = vec1 - vec2.

Arguments

  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix. res and vec1 should have the same size. res and vec2 should have the same size.
  • vec1::Vector{Float64} -> A vector of variable size. vec1 should be a vector, not a matrix. res and vec1 should have the same size. Constant.
  • vec2::Vector{Float64} -> A vector of variable size. vec2 should be a vector, not a matrix. res and vec2 should have the same size. Constant.
source
MuJoCo.mju_subFromMethod
mju_subFrom(res, vec)

Set res = res - vec.

Arguments

  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix. res and vec should have the same size.
  • vec::Vector{Float64} -> A vector of variable size. vec should be a vector, not a matrix. res and vec should have the same size. Constant.
source
MuJoCo.mju_sumMethod
mju_sum(vec)

Return sum(vec).

Arguments

  • vec::Vector{Float64} -> A vector of variable size. vec should be a vector, not a matrix.
source
MuJoCo.mju_symmetrizeMethod
mju_symmetrize(res, mat)

Symmetrize square matrix res = (mat + mat')/2.

Arguments

  • res::Matrix{Float64} -> A matrix of variable size. res and mat should have the same shape.
  • mat::Matrix{Float64} -> A matrix of variable size. mat should be square. res and mat should have the same shape. Constant.
source
MuJoCo.mju_transposeMethod
mju_transpose(res, mat)

Transpose matrix: res = mat'.

Arguments

  • res::Matrix{Float64} -> A matrix of variable size. #columns in res should equal #rows in mat. #rows in res should equal #columns in mat.
  • mat::Matrix{Float64} -> A matrix of variable size. Constant.
source
MuJoCo.mju_zeroMethod
mju_zero(res)

Set res = 0.

Arguments

  • res::Vector{Float64} -> A vector of variable size. res should be a vector, not a matrix.
source
MuJoCo.resetkey!Method
resetkey!(m::Model, d::Data, [keyframe = 1])

Resets the data struct to values in the supplied keyframe.

If no keyframe is specified, the first keyframe is used. The keyframe is a 1-based index into the list supplied by the model's specification.

source
MuJoCo.sample_model_and_dataMethod
sample_model_and_data()

A utility module to create and initialise example Model and Data objects, reflecting the underlying mjModel and mjData structs to provide REPL code completition to aid development.

Returns a (model, data) tuple.

source
MuJoCo.set_physics_state!Method
set_physics_state!(m::Model, d::Data, x::AbstractVector)

Set the state vector of a MuJoCo model.

The state vector is [joint positions, joint velocities, actuator states] with dimension (nq, nv, na). Call forward! after setting the state to compute all derived quantities in the Data object according to the new state.

See also mj_setState and get_physics_state.

source
MuJoCo.step!Method
step!(model::Model, data::Data)

Runs the simulation forward one time step, modifying the underlying data object.

source
MuJoCo.timestepMethod
timestep(model::MODEL_TYPES)

Extract the solver time-step for the given model.

source

Visualiser

MuJoCo.Visualiser.visualise!Function
visualise!(m::Model, d::Data; controller=nothing, trajectories=nothing, resolution=nothing)

Starts an interactive visualization of a MuJoCo model specified by an instance of Model and Data.

The visualizer has three "modes" that allow you to visualize passive dynamics, run a controller interactively, or play back recorded trajectories. The passive dynamics mode is always available, while the controller and trajectory modes are specified by the keyword arguments below.

Press F1 for help after running the visualiser to print the available mouse/button options in the terminal. Switch between modes with CTRL+RightArrow and CTRL+LeftArrow (or CMD for Mac). The different visualiser modes are ordered as follows:

  1. Controller mode (if controller keyword is provided)
  2. Trajectory mode (if trajectories keyword is provided)
  3. Passive mode (always available)

Keywords

  • controller: a callback function with the signature controller(m, d), called at each timestep, that applies a control input to the system (or does any other operation you like).

  • trajectories: a single trajectory or Vector of trajectories, where each trajectory is an AbstractMatrix of states with size (nx, T) where nx = model.nq + model.nv + model.na and T is the length of the trajectory. Note that each trajectory can have a different length.

  • resolution: a specific initial window resolution, useful for recording videos. Set this to nothing to use default value of 2/3s of the screen size.

Examples

using MuJoCo
install_visualiser() # Run this to install dependencies only once
init_visualiser()    # Load required dependencies into session

# Load a model
model, data = MuJoCo.sample_model_and_data()

# Simulate and record a trajectory
T = 200
nx = model.nq + model.nv + model.na
states = zeros(nx, T)
for t in 1:T
    states[:,t] = get_physics_state(model, data)
    step!(model, data)
end

# Define a controller
function ctrl!(m,d)
    d.ctrl .= 2*rand(m.nu) .- 1
end

# Run the visualiser
reset!(model, data)
visualise!(model, data, controller=ctrl!, trajectories = states)
source

Named Access

MuJoCo.Wrappers.NamedAccess.actuatorFunction
actuator([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, ctrl, length, moment, velocity, force)

source
MuJoCo.Wrappers.NamedAccess.bodyFunction
body([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, applied, xpos, xquat, xmat, xipos, ximat, com, cinert, crb, cvel, linvel, angmom, cacc, int, ext)

source
MuJoCo.Wrappers.NamedAccess.camFunction
cam([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, xpos, xmat)

source
MuJoCo.Wrappers.NamedAccess.eqFunction
eq([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, type, obj1id, obj2id, active0, solref, solimp, data)

source
MuJoCo.Wrappers.NamedAccess.excludeFunction
exclude([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, signature)

source
MuJoCo.Wrappers.NamedAccess.geomFunction
geom([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, xpos, xmat)

source
MuJoCo.Wrappers.NamedAccess.hfieldFunction
hfield([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, size, nrow, ncol, adr)

source
MuJoCo.Wrappers.NamedAccess.jntFunction
jnt([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, xanchor, xaxis)

source
MuJoCo.Wrappers.NamedAccess.keyFunction
key([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, time, qpos, qvel, act, mpos, mquat, ctrl)

source
MuJoCo.Wrappers.NamedAccess.lightFunction
light([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, xpos, xdir)

source
MuJoCo.Wrappers.NamedAccess.matFunction
mat([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, texid, texuniform, texrepeat, emission, specular, shininess, reflectance, rgba)

source
MuJoCo.Wrappers.NamedAccess.meshFunction
mesh([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, vertadr, vertnum, texcoordadr, faceadr, facenum, graphadr)

source
MuJoCo.Wrappers.NamedAccess.numericFunction
numeric([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, adr, size)

source
MuJoCo.Wrappers.NamedAccess.pairFunction
pair([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, dim, geom1, geom2, signature, solref, solimp, margin, gap, friction)

source
MuJoCo.Wrappers.NamedAccess.sensorFunction
sensor([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name)

source
MuJoCo.Wrappers.NamedAccess.siteFunction
site([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, xpos, xmat)

source
MuJoCo.Wrappers.NamedAccess.skinFunction
skin([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, matid, rgba, inflate, vertadr, vertnum, texcoordadr, faceadr, facenum, boneadr, bonenum)

source
MuJoCo.Wrappers.NamedAccess.tendonFunction
tendon([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, wrapadr, wrapnum, Jrownnz, Jrowadr, J_colind, length, J, velocity)

source
MuJoCo.Wrappers.NamedAccess.texFunction
tex([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, type, height, width, adr)

source
MuJoCo.Wrappers.NamedAccess.tupleFunction
tuple([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, adr, size)

source