MuJoCo API
MuJoCo
MuJoCo.example_model_filesMuJoCo.example_model_files_directoryMuJoCo.forward!MuJoCo.get_physics_stateMuJoCo.humanoid_model_fileMuJoCo.init_dataMuJoCo.init_visualiserMuJoCo.install_visualiserMuJoCo.load_modelMuJoCo.mj_addMMuJoCo.mj_angmomMatMuJoCo.mj_applyFTMuJoCo.mj_arrayMuJoCo.mj_constraintUpdateMuJoCo.mj_differentiatePosMuJoCo.mj_fullMMuJoCo.mj_geomDistanceMuJoCo.mj_getStateMuJoCo.mj_integratePosMuJoCo.mj_jacMuJoCo.mj_jacBodyMuJoCo.mj_jacBodyComMuJoCo.mj_jacGeomMuJoCo.mj_jacPointAxisMuJoCo.mj_jacSiteMuJoCo.mj_jacSubtreeComMuJoCo.mj_mulJacTVecMuJoCo.mj_mulJacVecMuJoCo.mj_mulMMuJoCo.mj_mulM2MuJoCo.mj_multiRayMuJoCo.mj_normalizeQuatMuJoCo.mj_rayMuJoCo.mj_rneMuJoCo.mj_setStateMuJoCo.mj_solveMMuJoCo.mj_solveM2MuJoCo.mj_zerosMuJoCo.mjd_inverseFDMuJoCo.mjd_subQuatMuJoCo.mjd_transitionFDMuJoCo.mju_L1MuJoCo.mju_addMuJoCo.mju_addSclMuJoCo.mju_addToMuJoCo.mju_addToSclMuJoCo.mju_band2DenseMuJoCo.mju_bandMulMatVecMuJoCo.mju_boxQPMuJoCo.mju_cholFactorMuJoCo.mju_cholFactorBandMuJoCo.mju_cholSolveMuJoCo.mju_cholSolveBandMuJoCo.mju_cholUpdateMuJoCo.mju_copyMuJoCo.mju_d2nMuJoCo.mju_decodePyramidMuJoCo.mju_dense2BandMuJoCo.mju_dotMuJoCo.mju_encodePyramidMuJoCo.mju_eyeMuJoCo.mju_f2nMuJoCo.mju_fillMuJoCo.mju_insertionSortMuJoCo.mju_insertionSortIntMuJoCo.mju_isZeroMuJoCo.mju_mulMatMatMuJoCo.mju_mulMatMatTMuJoCo.mju_mulMatTMatMuJoCo.mju_mulMatTVecMuJoCo.mju_mulMatVecMuJoCo.mju_mulVecMatVecMuJoCo.mju_n2dMuJoCo.mju_n2fMuJoCo.mju_normMuJoCo.mju_normalizeMuJoCo.mju_printMatMuJoCo.mju_sclMuJoCo.mju_sqrMatTDMuJoCo.mju_subMuJoCo.mju_subFromMuJoCo.mju_sumMuJoCo.mju_symmetrizeMuJoCo.mju_transposeMuJoCo.mju_zeroMuJoCo.reset!MuJoCo.resetkey!MuJoCo.resetkey!MuJoCo.sample_model_and_dataMuJoCo.set_physics_state!MuJoCo.step!MuJoCo.timestep
MuJoCo.Wrappers.Data — Type
MuJoCo.Wrappers.Model — Type
MuJoCo.Wrappers.show_docs — Function
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)MuJoCo.example_model_files — Method
Returns the list of absolute paths to available example model files provided by MuJoCo.
MuJoCo.example_model_files_directory — Method
Returns the absolute path of the root directory containing all the example model files.
MuJoCo.forward! — Method
forward!(model::MODEL_TYPES, data::DATA_TYPES)Same as step! but without integrating in time.
MuJoCo.get_physics_state — Method
get_physics_state(m::Model, d::Data)Extract the state vector of a MuJoCo model.
The state vector is [joint positions, joint velocities, actuator states] with dimension (nq, nv, na).
See also mj_getState and set_physics_state!.
MuJoCo.humanoid_model_file — Method
Returns the absolute path to the humanoid model provided by MuJoCo.
MuJoCo.init_data — Method
init_data(model::Model)Creates an instance of the data required for the step! simulation.
Returns a Data object, wrapping the underlying mjData object.
MuJoCo.init_visualiser — Method
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
- Printf
- StaticArrays
MuJoCo.install_visualiser — Method
install_visualiser()Installs the necessary packages for the running the visualiser into the current running environment.
Packages:
- BangBang
- FFMPEG
- GLFW
- Observables
- Printf
- StaticArrays
MuJoCo.load_model — Method
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)MuJoCo.mj_addM — Method
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::Datadst::Vector{Float64}-> A vector of variable size.dstshould be a vector, not a matrix.dstshould be of size nM.rownnz::Vector{Int32}-> A vector of variable size.rownnzshould be a vector, not a matrix.rownnzshould be of size nv.rowadr::Vector{Int32}-> A vector of variable size.rowadrshould be a vector, not a matrix.rowadrshould be of size nv.colind::Vector{Int32}-> A vector of variable size.colindshould be a vector, not a matrix.colindshould be of size nM.
MuJoCo.mj_angmomMat — Method
mj_angmomMat(m, d, mat, body)Compute subtree angular momentum matrix.
Arguments
m::Model-> Constant.d::Datamat::Matrix{Float64}-> A matrix of variable size.matshould be of shape (3, nv).body::Int32
MuJoCo.mj_applyFT — Method
mj_applyFT(m, d, force, torque, point, body, qfrc_target)Apply Cartesian force and torque (outside xfrc_applied mechanism).
Arguments
m::Model-> Constant.d::Dataforce::Vector{Float64}-> A vector of size 3.forceshould be a vector of size 3. Constant.torque::Vector{Float64}-> A vector of size 3.torqueshould be a vector of size 3. Constant.point::Vector{Float64}-> A vector of size 3.pointshould be a vector of size 3. Constant.body::Int32qfrc_target::Vector{Float64}-> A vector of variable size.qfrc_targetshould be a vector, not a matrix.qfrc_targetshould be of size nv.
MuJoCo.mj_array — Method
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.
MuJoCo.mj_constraintUpdate — Method
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::Datajar::Vector{Float64}-> A vector of variable size.jarshould be a vector, not a matrix. size ofjarshould equal nefc. Constant.cost::Vector{Float64}-> An optional vector of size 1.costshould be a vector of size 1. Can set tonothingif not required.flg_coneHessian::Int32
MuJoCo.mj_differentiatePos — Method
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.qvelshould be a vector, not a matrix.qvelshould be of size nv.dt::Float64qpos1::Vector{Float64}-> A vector of variable size.qpos1should be a vector, not a matrix.qpos1should be of size nq. Constant.qpos2::Vector{Float64}-> A vector of variable size.qpos2should be a vector, not a matrix.qpos2should be of size nq. Constant.
MuJoCo.mj_fullM — Method
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.dstshould be of shape (nv, nv).M::Vector{Float64}-> A vector of variable size.Mshould be a vector, not a matrix.Mshould be of size nM. Constant.
MuJoCo.mj_geomDistance — Method
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::Int32geom2::Int32distmax::Float64fromto::Matrix{Float64}-> An optional matrix of variable size.fromtoshould be of size 6. Can set tonothingif not required.
MuJoCo.mj_getState — Method
mj_getState(m, d, state, spec)Get state.
Arguments
m::Model-> Constant.d::Data-> Constant.state::Vector{Float64}-> A vector of variable size.stateshould be a vector, not a matrix.statesize should equal mj_stateSize(m, spec).spec::Int32
MuJoCo.mj_integratePos — Method
mj_integratePos(m, qpos, qvel, dt)Integrate position with given velocity.
Arguments
m::Model-> Constant.qpos::Vector{Float64}-> A vector of variable size.qposshould be a vector, not a matrix.qposshould be of size nq.qvel::Vector{Float64}-> A vector of variable size.qvelshould be a vector, not a matrix.qvelshould be of size nv. Constant.dt::Float64
MuJoCo.mj_jac — Method
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::Datajacp::Matrix{Float64}-> An optional matrix of variable size.jacpshould be of shape (3, nv). Can set tonothingif not required.jacr::Matrix{Float64}-> An optional matrix of variable size.jacrshould be of shape (3, nv). Can set tonothingif not required.point::Vector{Float64}-> A vector of size 3.pointshould be a vector of size 3. Constant.body::Int32
MuJoCo.mj_jacBody — Method
mj_jacBody(m, d, jacp, jacr, body)Compute body frame end-effector Jacobian.
Arguments
m::Model-> Constant.d::Datajacp::Matrix{Float64}-> An optional matrix of variable size.jacpshould be of shape (3, nv). Can set tonothingif not required.jacr::Matrix{Float64}-> An optional matrix of variable size.jacrshould be of shape (3, nv). Can set tonothingif not required.body::Int32
MuJoCo.mj_jacBodyCom — Method
mj_jacBodyCom(m, d, jacp, jacr, body)Compute body center-of-mass end-effector Jacobian.
Arguments
m::Model-> Constant.d::Datajacp::Matrix{Float64}-> An optional matrix of variable size.jacpshould be of shape (3, nv). Can set tonothingif not required.jacr::Matrix{Float64}-> An optional matrix of variable size.jacrshould be of shape (3, nv). Can set tonothingif not required.body::Int32
MuJoCo.mj_jacGeom — Method
mj_jacGeom(m, d, jacp, jacr, geom)Compute geom end-effector Jacobian.
Arguments
m::Model-> Constant.d::Datajacp::Matrix{Float64}-> An optional matrix of variable size.jacpshould be of shape (3, nv). Can set tonothingif not required.jacr::Matrix{Float64}-> An optional matrix of variable size.jacrshould be of shape (3, nv). Can set tonothingif not required.geom::Int32
MuJoCo.mj_jacPointAxis — Method
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::Datajacp::Matrix{Float64}-> An optional matrix of variable size.jacpshould be of shape (3, nv). Can set tonothingif not required.jacr::Matrix{Float64}-> An optional matrix of variable size.jacrshould be of shape (3, nv). Can set tonothingif not required.point::Vector{Float64}-> A vector of size 3.pointshould be a vector of size 3. Constant.axis::Vector{Float64}-> A vector of size 3.axisshould be a vector of size 3. Constant.body::Int32
MuJoCo.mj_jacSite — Method
mj_jacSite(m, d, jacp, jacr, site)Compute site end-effector Jacobian.
Arguments
m::Model-> Constant.d::Datajacp::Matrix{Float64}-> An optional matrix of variable size.jacpshould be of shape (3, nv). Can set tonothingif not required.jacr::Matrix{Float64}-> An optional matrix of variable size.jacrshould be of shape (3, nv). Can set tonothingif not required.site::Int32
MuJoCo.mj_jacSubtreeCom — Method
mj_jacSubtreeCom(m, d, jacp, body)Compute subtree center-of-mass end-effector Jacobian.
Arguments
m::Model-> Constant.d::Datajacp::Matrix{Float64}-> An optional matrix of variable size.jacpshould be of shape (3, nv). Can set tonothingif not required.body::Int32
MuJoCo.mj_mulJacTVec — Method
mj_mulJacTVec(m, d, res, vec)Multiply dense or sparse constraint Jacobian transpose by vector.
Arguments
m::Model-> Constant.d::Datares::Vector{Float64}-> A vector of variable size.resshould be a vector, not a matrix.resshould be of length nv.vec::Vector{Float64}-> A vector of variable size.vecshould be a vector, not a matrix.vecshould be of length nefc. Constant.
MuJoCo.mj_mulJacVec — Method
mj_mulJacVec(m, d, res, vec)Multiply dense or sparse constraint Jacobian by vector.
Arguments
m::Model-> Constant.d::Datares::Vector{Float64}-> A vector of variable size.resshould be a vector, not a matrix.resshould be of length nefc.vec::Vector{Float64}-> A vector of variable size.vecshould be a vector, not a matrix.vecshould be of length nv. Constant.
MuJoCo.mj_mulM — Method
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.resshould be a vector, not a matrix.resshould be of size nv.vec::Vector{Float64}-> A vector of variable size.vecshould be a vector, not a matrix.vecshould be of size nv. Constant.
MuJoCo.mj_mulM2 — Method
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.resshould be a vector, not a matrix.resshould be of size nv.vec::Vector{Float64}-> A vector of variable size.vecshould be a vector, not a matrix.vecshould be of size nv. Constant.
MuJoCo.mj_multiRay — Method
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::Datapnt::Vector{Float64}-> A vector of size 3.pntshould be a vector of size 3. Constant.vec::Vector{Float64}-> A vector of variable size.vecshould be a vector, not a matrix.vecshould be of size 3*nray. Constant.geomgroup::Vector{UInt8}-> An optional vector of size 6.geomgroupshould be a vector of size 6. Can set tonothingif not required. Constant.flg_static::UInt8bodyexclude::Int32geomid::Vector{Int32}-> A vector of variable size.geomidshould be a vector, not a matrix. dist andgeomidshould be of size nray.dist::Vector{Float64}-> A vector of variable size.distshould be a vector, not a matrix.distand geomid should be of size nray.nray::Int32cutoff::Float64
MuJoCo.mj_normalizeQuat — Method
mj_normalizeQuat(m, qpos)Normalize all quaternions in qpos-type vector.
Arguments
m::Model-> Constant.qpos::Vector{Float64}-> A vector of variable size.qposshould be a vector, not a matrix.qposshould be of size nq.
MuJoCo.mj_ray — Method
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.pntshould be a vector of size 3. Constant.vec::Vector{Float64}-> A vector of size 3.vecshould be a vector of size 3. Constant.geomgroup::Vector{UInt8}-> An optional vector of size 6.geomgroupshould be a vector of size 6. Can set tonothingif not required. Constant.flg_static::UInt8bodyexclude::Int32geomid::Vector{Int32}-> A vector of size 1.geomidshould be a vector of size 1.
MuJoCo.mj_rne — Method
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::Dataflg_acc::Int32result::Vector{Float64}-> A vector of variable size.resultshould be a vector, not a matrix.resultshould have length nv.
MuJoCo.mj_setState — Method
mj_setState(m, d, state, spec)Set state.
Arguments
m::Model-> Constant.d::Datastate::Vector{Float64}-> A vector of variable size.stateshould be a vector, not a matrix.statesize should equal mj_stateSize(m, spec).spec::Int32
MuJoCo.mj_solveM — Method
mj_solveM(m, d, x, y)Solve linear system M * x = y using factorization: x = inv(L'DL)*y
Arguments
m::Model-> Constant.d::Datax::Matrix{Float64}-> A matrix of variable size.y::Matrix{Float64}-> A matrix of variable size. Constant.
MuJoCo.mj_solveM2 — Method
mj_solveM2(m, d, x, y)Half of linear solve: x = sqrt(inv(D))inv(L')y
Arguments
m::Model-> Constant.d::Datax::Matrix{Float64}-> A matrix of variable size.y::Matrix{Float64}-> A matrix of variable size. Constant.
MuJoCo.mj_zeros — Method
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.
MuJoCo.mjd_inverseFD — Method
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::Dataeps::Float64flg_actuation::UInt8DfDq::Matrix{Float64}-> An optional matrix of variable size.DfDqshould be of shape (nv, nv). Can set tonothingif not required.DfDv::Matrix{Float64}-> An optional matrix of variable size.DfDvshould be of shape (nv, nv). Can set tonothingif not required.DfDa::Matrix{Float64}-> An optional matrix of variable size.DfDashould be of shape (nv, nv). Can set tonothingif not required.DsDq::Matrix{Float64}-> An optional matrix of variable size.DsDqshould be of shape (nv, nsensordata). Can set tonothingif not required.DsDv::Matrix{Float64}-> An optional matrix of variable size.DsDvshould be of shape (nv, nsensordata). Can set tonothingif not required.DsDa::Matrix{Float64}-> An optional matrix of variable size.DsDashould be of shape (nv, nsensordata). Can set tonothingif not required.DmDq::Matrix{Float64}-> An optional matrix of variable size.DmDqshould be of shape (nv, nM). Can set tonothingif not required.
MuJoCo.mjd_subQuat — Method
mjd_subQuat(qa, qb, Da, Db)Derivatives of mju_subQuat.
Arguments
qa::Vector{Float64}-> A vector of variable size.qashould be a vector, not a matrix.qamust have size 4. Constant.qb::Vector{Float64}-> A vector of variable size.qbshould be a vector, not a matrix.qbmust have size 4. Constant.Da::Matrix{Float64}-> An optional matrix of variable size.Damust have size 9. Can set tonothingif not required.Db::Matrix{Float64}-> An optional matrix of variable size.Dbmust have size 9. Can set tonothingif not required.
MuJoCo.mjd_transitionFD — Method
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::Dataeps::Float64flg_centered::UInt8A::Matrix{Float64}-> An optional matrix of variable size.Ashould be of shape (2nv+na, 2nv+na). Can set tonothingif not required.B::Matrix{Float64}-> An optional matrix of variable size.Bshould be of shape (2*nv+na, nu). Can set tonothingif not required.C::Matrix{Float64}-> An optional matrix of variable size.Cshould be of shape (nsensordata, 2*nv+na). Can set tonothingif not required.D::Matrix{Float64}-> An optional matrix of variable size.Dshould be of shape (nsensordata, nu). Can set tonothingif not required.
MuJoCo.mju_L1 — Method
mju_L1(vec)Return L1 norm: sum(abs(vec)).
Arguments
vec::Vector{Float64}-> A vector of variable size.vecshould be a vector, not a matrix.
MuJoCo.mju_add — Method
mju_add(res, vec1, vec2)Set res = vec1 + vec2.
Arguments
res::Vector{Float64}-> A vector of variable size.resshould be a vector, not a matrix.resand vec1 should have the same size.resand vec2 should have the same size.vec1::Vector{Float64}-> A vector of variable size.vec1should be a vector, not a matrix. res andvec1should have the same size. Constant.vec2::Vector{Float64}-> A vector of variable size.vec2should be a vector, not a matrix. res andvec2should have the same size. Constant.
MuJoCo.mju_addScl — Method
mju_addScl(res, vec1, vec2, scl)Set res = vec1 + vec2*scl.
Arguments
res::Vector{Float64}-> A vector of variable size.resshould be a vector, not a matrix.resand vec1 should have the same size.resand vec2 should have the same size.vec1::Vector{Float64}-> A vector of variable size.vec1should be a vector, not a matrix. res andvec1should have the same size. Constant.vec2::Vector{Float64}-> A vector of variable size.vec2should be a vector, not a matrix. res andvec2should have the same size. Constant.scl::Float64
MuJoCo.mju_addTo — Method
mju_addTo(res, vec)Set res = res + vec.
Arguments
res::Vector{Float64}-> A vector of variable size.resshould be a vector, not a matrix.resand vec should have the same size.vec::Vector{Float64}-> A vector of variable size.vecshould be a vector, not a matrix. res andvecshould have the same size. Constant.
MuJoCo.mju_addToScl — Method
mju_addToScl(res, vec, scl)Set res = res + vec*scl.
Arguments
res::Vector{Float64}-> A vector of variable size.resshould be a vector, not a matrix.resand vec should have the same size.vec::Vector{Float64}-> A vector of variable size.vecshould be a vector, not a matrix. res andvecshould have the same size. Constant.scl::Float64
MuJoCo.mju_band2Dense — Method
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.resshould have ntotal rows.resshould have ntotal columns.mat::Vector{Float64}-> A vector of variable size.matshould be a vector, not a matrix. Constant.ntotal::Int32-> res should haventotalrows. res should haventotalcolumns.nband::Int32ndense::Int32flg_sym::UInt8
MuJoCo.mju_bandMulMatVec — Method
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.resshould be a vector, not a matrix.resshould have ntotal rows.resshould have nVec columns.mat::Matrix{Float64}-> A matrix of variable size. Constant.vec::Matrix{Float64}-> A matrix of variable size.vecshould have ntotal rows.vecshould have nVec columns. Constant.ntotal::Int32-> res should haventotalrows. vec should haventotalrows.nband::Int32ndense::Int32nVec::Int32-> res should havenVeccolumns. vec should havenVeccolumns.flg_sym::UInt8
MuJoCo.mju_boxQP — Method
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.resshould be a vector, not a matrix.R::Matrix{Float64}-> A matrix of variable size. size ofRshould be n*(n+7).index::Vector{Int32}-> An optional vector of variable size.indexshould be a vector, not a matrix. size ofindexshould equal n. Can set tonothingif not required.H::Matrix{Float64}-> A matrix of variable size.Hshould be of shape (n, n). Constant.g::Vector{Float64}-> A vector of variable size.gshould be a vector, not a matrix. size ofgshould equal n. Constant.lower::Vector{Float64}-> An optional vector of variable size.lowershould be a vector, not a matrix. size oflowershould equal n. Can set tonothingif not required. Constant.upper::Vector{Float64}-> An optional vector of variable size.uppershould be a vector, not a matrix. size ofuppershould equal n. Can set tonothingif not required. Constant.
MuJoCo.mju_cholFactor — Method
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.matshould be a square matrix.mindiag::Float64
MuJoCo.mju_cholFactorBand — Method
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.matshould be a vector, not a matrix.ntotal::Int32nband::Int32ndense::Int32diagadd::Float64diagmul::Float64
MuJoCo.mju_cholSolve — Method
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.resshould be a vector, not a matrix.mat::Matrix{Float64}-> A matrix of variable size.matshould be a square matrix. Constant.vec::Vector{Float64}-> A vector of variable size.vecshould be a vector, not a matrix. Constant.
MuJoCo.mju_cholSolveBand — Method
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.resshould be a vector, not a matrix. size ofresshould equal ntotal.mat::Vector{Float64}-> A vector of variable size.matshould be a vector, not a matrix. Constant.vec::Vector{Float64}-> A vector of variable size.vecshould be a vector, not a matrix. size ofvecshould equal ntotal. Constant.ntotal::Int32nband::Int32ndense::Int32
MuJoCo.mju_cholUpdate — Method
mju_cholUpdate(mat, x, flg_plus)Cholesky rank-one update: LL' +/- xx'; return rank.
Arguments
mat::Matrix{Float64}-> A matrix of variable size.matshould be a square matrix.x::Vector{Float64}-> A vector of variable size.xshould be a vector, not a matrix.flg_plus::Int32
MuJoCo.mju_copy — Method
mju_copy(res, data)Set res = vec.
Arguments
res::Vector{Float64}-> A vector of variable size.resshould be a vector, not a matrix.resand data should have the same size.data::Vector{Float64}-> A vector of variable size.datashould be a vector, not a matrix. res anddatashould have the same size. Constant.
MuJoCo.mju_d2n — Method
mju_d2n(res, vec)Convert from double to mjtNum.
Arguments
res::Vector{Float64}-> A vector of variable size.resshould be a vector, not a matrix.resand vec should have the same size.vec::Vector{Float64}-> A vector of variable size.vecshould be a vector, not a matrix. res andvecshould have the same size. Constant.
MuJoCo.mju_decodePyramid — Method
mju_decodePyramid(force, pyramid, mu)Convert pyramid representation to contact force.
Arguments
force::Vector{Float64}-> A vector of variable size.forceshould be a vector, not a matrix.pyramid::Vector{Float64}-> A vector of variable size.pyramidshould be a vector, not a matrix. Constant.mu::Vector{Float64}-> A vector of variable size.mushould be a vector, not a matrix. Constant.
MuJoCo.mju_dense2Band — Method
mju_dense2Band(res, mat, ntotal, nband, ndense)Convert dense matrix to banded matrix.
Arguments
res::Vector{Float64}-> A vector of variable size.resshould be a vector, not a matrix.mat::Matrix{Float64}-> A matrix of variable size.matshould have ntotal rows.matshould have ntotal columns. Constant.ntotal::Int32-> mat should haventotalrows. mat should haventotalcolumns.nband::Int32ndense::Int32
MuJoCo.mju_dot — Method
mju_dot(vec1, vec2)Return dot-product of vec1 and vec2.
Arguments
vec1::Vector{Float64}-> A vector of variable size.vec1should be a vector, not a matrix.vec1and vec2 should have the same size. Constant.vec2::Vector{Float64}-> A vector of variable size.vec2should be a vector, not a matrix. vec1 andvec2should have the same size. Constant.
MuJoCo.mju_encodePyramid — Method
mju_encodePyramid(pyramid, force, mu)Convert contact force to pyramid representation.
Arguments
pyramid::Vector{Float64}-> A vector of variable size.pyramidshould be a vector, not a matrix.force::Vector{Float64}-> A vector of variable size.forceshould be a vector, not a matrix. Constant.mu::Vector{Float64}-> A vector of variable size.mushould be a vector, not a matrix. Constant.
MuJoCo.mju_eye — Method
mju_eye(mat)Set mat to the identity matrix.
Arguments
mat::Matrix{Float64}-> A matrix of variable size.matshould be square.
MuJoCo.mju_f2n — Method
mju_f2n(res, vec)Convert from float to mjtNum.
Arguments
res::Vector{Float64}-> A vector of variable size.resshould be a vector, not a matrix.resand vec should have the same size.vec::Vector{Float32}-> A vector of variable size.vecshould be a vector, not a matrix. res andvecshould have the same size. Constant.
MuJoCo.mju_fill — Method
mju_fill(res, val)Set res = val.
Arguments
res::Vector{Float64}-> A vector of variable size.resshould be a vector, not a matrix.val::Float64
MuJoCo.mju_insertionSort — Method
mju_insertionSort(res)Insertion sort, resulting list is in increasing order.
Arguments
res::Vector{Float64}-> A vector of variable size.resshould be a vector, not a matrix.
MuJoCo.mju_insertionSortInt — Method
mju_insertionSortInt(res)Integer insertion sort, resulting list is in increasing order.
Arguments
res::Vector{Int32}-> A vector of variable size.resshould be a vector, not a matrix.
MuJoCo.mju_isZero — Method
mju_isZero(vec)Return 1 if all elements are 0.
Arguments
vec::Vector{Float64}-> A vector of variable size.vecshould be a vector, not a matrix.
MuJoCo.mju_mulMatMat — Method
mju_mulMatMat(res, mat1, mat2)Multiply matrices: res = mat1 * mat2.
Arguments
res::Matrix{Float64}-> A matrix of variable size. #rows inresshould equal #rows in mat1.mat1::Matrix{Float64}-> A matrix of variable size. #columns inmat1should equal #rows in mat2. Constant.mat2::Matrix{Float64}-> A matrix of variable size. Constant.
MuJoCo.mju_mulMatMatT — Method
mju_mulMatMatT(res, mat1, mat2)Multiply matrices, second argument transposed: res = mat1 * mat2'.
Arguments
res::Matrix{Float64}-> A matrix of variable size. #rows inresshould equal #rows in mat1. #columns inresshould equal #rows in mat2.mat1::Matrix{Float64}-> A matrix of variable size. Constant.mat2::Matrix{Float64}-> A matrix of variable size. Constant.
MuJoCo.mju_mulMatTMat — Method
mju_mulMatTMat(res, mat1, mat2)Multiply matrices, first argument transposed: res = mat1' * mat2.
Arguments
res::Matrix{Float64}-> A matrix of variable size. #rows inresshould equal #columns in mat1.mat1::Matrix{Float64}-> A matrix of variable size. #rows inmat1should equal #rows in mat2. Constant.mat2::Matrix{Float64}-> A matrix of variable size. Constant.
MuJoCo.mju_mulMatTVec — Method
mju_mulMatTVec(res, mat, vec)Multiply transposed matrix and vector: res = mat' * vec.
Arguments
res::Vector{Float64}-> A vector of variable size.resshould be a vector, not a matrix.mat::Matrix{Float64}-> A matrix of variable size. Constant.vec::Vector{Float64}-> A vector of variable size.vecshould be a vector, not a matrix. Constant.
MuJoCo.mju_mulMatVec — Method
mju_mulMatVec(res, mat, vec)Multiply matrix and vector: res = mat * vec.
Arguments
res::Vector{Float64}-> A vector of variable size.resshould be a vector, not a matrix.mat::Matrix{Float64}-> A matrix of variable size. Constant.vec::Vector{Float64}-> A vector of variable size.vecshould be a vector, not a matrix. Constant.
MuJoCo.mju_mulVecMatVec — Method
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.vec1should be a vector, not a matrix. Constant.mat::Matrix{Float64}-> A matrix of variable size. Constant.vec2::Vector{Float64}-> A vector of variable size.vec2should be a vector, not a matrix. Constant.
MuJoCo.mju_n2d — Method
mju_n2d(res, vec)Convert from mjtNum to double.
Arguments
res::Vector{Float64}-> A vector of variable size.resshould be a vector, not a matrix.resand vec should have the same size.vec::Vector{Float64}-> A vector of variable size.vecshould be a vector, not a matrix. res andvecshould have the same size. Constant.
MuJoCo.mju_n2f — Method
mju_n2f(res, vec)Convert from mjtNum to float.
Arguments
res::Vector{Float32}-> A vector of variable size.resshould be a vector, not a matrix.resand vec should have the same size.vec::Vector{Float64}-> A vector of variable size.vecshould be a vector, not a matrix. res andvecshould have the same size. Constant.
MuJoCo.mju_norm — Method
mju_norm(vec)Return vector length (without normalizing vector).
Arguments
vec::Vector{Float64}-> A vector of variable size.vecshould be a vector, not a matrix. Constant.
MuJoCo.mju_normalize — Method
mju_normalize(vec)Normalize vector, return length before normalization.
Arguments
vec::Vector{Float64}-> A vector of variable size.vecshould be a vector, not a matrix.
MuJoCo.mju_printMat — Method
mju_printMat(mat)Print matrix to screen.
Arguments
mat::Matrix{Float64}-> A matrix of variable size. Constant.
MuJoCo.mju_scl — Method
mju_scl(res, vec, scl)Set res = vec*scl.
Arguments
res::Vector{Float64}-> A vector of variable size.resshould be a vector, not a matrix.resand vec should have the same size.vec::Vector{Float64}-> A vector of variable size.vecshould be a vector, not a matrix. res andvecshould have the same size. Constant.scl::Float64
MuJoCo.mju_sqrMatTD — Method
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 inresshould equal #columns in mat.mat::Matrix{Float64}-> A matrix of variable size. Constant.diag::Vector{Float64}-> An optional vector of variable size.diagshould be a vector, not a matrix. Can set tonothingif not required.
MuJoCo.mju_sub — Method
mju_sub(res, vec1, vec2)Set res = vec1 - vec2.
Arguments
res::Vector{Float64}-> A vector of variable size.resshould be a vector, not a matrix.resand vec1 should have the same size.resand vec2 should have the same size.vec1::Vector{Float64}-> A vector of variable size.vec1should be a vector, not a matrix. res andvec1should have the same size. Constant.vec2::Vector{Float64}-> A vector of variable size.vec2should be a vector, not a matrix. res andvec2should have the same size. Constant.
MuJoCo.mju_subFrom — Method
mju_subFrom(res, vec)Set res = res - vec.
Arguments
res::Vector{Float64}-> A vector of variable size.resshould be a vector, not a matrix.resand vec should have the same size.vec::Vector{Float64}-> A vector of variable size.vecshould be a vector, not a matrix. res andvecshould have the same size. Constant.
MuJoCo.mju_sum — Method
mju_sum(vec)Return sum(vec).
Arguments
vec::Vector{Float64}-> A vector of variable size.vecshould be a vector, not a matrix.
MuJoCo.mju_symmetrize — Method
mju_symmetrize(res, mat)Symmetrize square matrix res = (mat + mat')/2.
Arguments
res::Matrix{Float64}-> A matrix of variable size.resand mat should have the same shape.mat::Matrix{Float64}-> A matrix of variable size.matshould be square. res andmatshould have the same shape. Constant.
MuJoCo.mju_transpose — Method
mju_transpose(res, mat)Transpose matrix: res = mat'.
Arguments
res::Matrix{Float64}-> A matrix of variable size. #columns inresshould equal #rows in mat. #rows inresshould equal #columns in mat.mat::Matrix{Float64}-> A matrix of variable size. Constant.
MuJoCo.mju_zero — Method
mju_zero(res)Set res = 0.
Arguments
res::Vector{Float64}-> A vector of variable size.resshould be a vector, not a matrix.
MuJoCo.reset! — Method
reset!(m::Model, d::Data)Resets the data values to their default states. You may equivalently use mj_resetData.
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.
MuJoCo.resetkey! — Method
Resets the data struct to values in the first key frame.
MuJoCo.sample_model_and_data — Method
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.
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.
MuJoCo.step! — Method
step!(model::Model, data::Data)Runs the simulation forward one time step, modifying the underlying data object.
MuJoCo.timestep — Method
timestep(model::MODEL_TYPES)Extract the solver time-step for the given model.
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:
- Controller mode (if
controllerkeyword is provided) - Trajectory mode (if
trajectorieskeyword is provided) - Passive mode (always available)
Keywords
controller: a callback function with the signaturecontroller(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 orVectorof trajectories, where each trajectory is anAbstractMatrixof states with size(nx, T)wherenx = model.nq + model.nv + model.naandTis 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)Named Access
MuJoCo.Wrappers.NamedAccess.actuatorMuJoCo.Wrappers.NamedAccess.bodyMuJoCo.Wrappers.NamedAccess.camMuJoCo.Wrappers.NamedAccess.eqMuJoCo.Wrappers.NamedAccess.excludeMuJoCo.Wrappers.NamedAccess.geomMuJoCo.Wrappers.NamedAccess.hfieldMuJoCo.Wrappers.NamedAccess.jntMuJoCo.Wrappers.NamedAccess.keyMuJoCo.Wrappers.NamedAccess.lightMuJoCo.Wrappers.NamedAccess.matMuJoCo.Wrappers.NamedAccess.meshMuJoCo.Wrappers.NamedAccess.numericMuJoCo.Wrappers.NamedAccess.pairMuJoCo.Wrappers.NamedAccess.sensorMuJoCo.Wrappers.NamedAccess.siteMuJoCo.Wrappers.NamedAccess.skinMuJoCo.Wrappers.NamedAccess.tendonMuJoCo.Wrappers.NamedAccess.texMuJoCo.Wrappers.NamedAccess.tuple
MuJoCo.Wrappers.NamedAccess.actuator — Function
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)
MuJoCo.Wrappers.NamedAccess.body — Function
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)
MuJoCo.Wrappers.NamedAccess.cam — Function
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)
MuJoCo.Wrappers.NamedAccess.eq — Function
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)
MuJoCo.Wrappers.NamedAccess.exclude — Function
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)
MuJoCo.Wrappers.NamedAccess.geom — Function
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)
MuJoCo.Wrappers.NamedAccess.hfield — Function
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)
MuJoCo.Wrappers.NamedAccess.jnt — Function
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)
MuJoCo.Wrappers.NamedAccess.key — Function
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)
MuJoCo.Wrappers.NamedAccess.light — Function
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)
MuJoCo.Wrappers.NamedAccess.mat — Function
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)
MuJoCo.Wrappers.NamedAccess.mesh — Function
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)
MuJoCo.Wrappers.NamedAccess.numeric — Function
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)
MuJoCo.Wrappers.NamedAccess.pair — Function
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)
MuJoCo.Wrappers.NamedAccess.sensor — Function
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)
MuJoCo.Wrappers.NamedAccess.site — Function
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)
MuJoCo.Wrappers.NamedAccess.skin — Function
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)
MuJoCo.Wrappers.NamedAccess.tendon — Function
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)
MuJoCo.Wrappers.NamedAccess.tex — Function
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)
MuJoCo.Wrappers.NamedAccess.tuple — Function
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)