The key function here is mj_loadXML. It invokes the built-in parser and compiler, and either returns a pointer to
a valid mjModel, or NULL - in which case the user should check the error information in the user-provided string.
The model and all files referenced in it can be loaded from disk or from a VFS when provided.
Compile mjSpec to mjModel. A spec can be edited and compiled multiple times, returning a new
mjModel instance that takes the edits into account.
If compilation fails, mj_compile returns NULL; the error can be read with mjs_getError.
Recompile spec to model, preserving the state. Like mj_compile, this function compiles an mjSpec to an
mjModel, with two differences. First, rather than returning an entirely new model, it will
reallocate existing mjModel and mjData instances in-place. Second, it will preserve the
integration state, as given in the provided mjData instance, while accounting for
newly added or removed degrees of freedom. This allows the user to continue simulation with the same model and data
struct pointers while editing the model programmatically.
mj_recompile returns 0 if compilation succeed. In the case of failure, the given mjModel and mjData
instances will be deleted; as in mj_compile, the compilation error can be read with mjs_getError.
Update XML data structures with info from low-level model created with mj_loadXML, save as MJCF.
If error is not NULL, it must have size error_sz.
Note that this function only saves models that have been loaded with mj_loadXML, the legacy loading mechanism.
See the model editing chapter to understand the difference between the old and new model loading and
saving mechanisms.
Save spec to XML string, return 0 on success, -1 on failure. If the length of the output buffer is too small, returns
the required size. XML saving automatically compiles the spec before saving.
These are the main entry points to the simulator. Most users will only need to call mj_step, which computes
everything and advanced the simulation state by one time step. Controls and applied forces must either be set in advance
(in mjData.{ctrl,qfrc_applied,xfrc_applied}), or a control callback mjcb_control must be installed which
will be called just before the controls and applied forces are needed. Alternatively, one can use mj_step1 and
mj_step2 which break down the simulation pipeline into computations that are executed before and after the
controls are needed; in this way one can set controls that depend on the results from mj_step1. Keep in mind
though that the RK4 solver does not work with mj_step1/2. See Simulation pipeline for a more detailed description.
mj_forward performs the same computations as mj_step but without the integration. It is useful after loading or
resetting a model (to put the entire mjData in a valid state), and also for out-of-order computations that involve
sampling or finite-difference approximations.
mj_inverse runs the inverse dynamics, and writes its output in mjData.qfrc_inverse. Note that mjData.qacc
must be set before calling this function. Given the state (qpos, qvel, act), mj_forward maps from force to acceleration,
while mj_inverse maps from acceleration to force. Mathematically these functions are inverse of each other, but
numerically this may not always be the case because the forward dynamics rely on a constraint optimization algorithm
which is usually terminated early. The difference between the results of forward and inverse dynamics can be computed
with the function mj_compareFwdInv, which can be thought of as another solver accuracy check (as well as a
general sanity check).
The skip version of mj_forward and mj_inverse are useful for example when qpos was unchanged but qvel was
changed (usually in the context of finite differencing). Then there is no point repeating the computations that only
depend on qpos. Calling the dynamics with skipstage = mjSTAGE_POS will achieve these savings.
These are support functions that need access to mjModel and mjData, unlike the utility functions which do
not need such access. Support functions are called within the simulator but some of them can also be useful for custom
computations, and are documented in more detail below.
Copy concatenated state components specified by sig from d into state. The bits of the integer
sig correspond to element fields of mjtState. Fails with mju_error if sig is invalid.
Extract into dst the subset of components specified by dstsig from a state src previously obtained via
mj_getState with components specified by srcsig. Fails with mju_error if the bits set in dstsig
is not a subset of the bits set in srcsig.
Copy concatenated state components specified by sig from state into d. The bits of the integer
sig correspond to element fields of mjtState. Fails with mju_error if sig is invalid.
Read the control value for an actuator at a given time, taking delays into account. If no history buffer exists, return
mjData.ctrl[id]. If a history buffer exists (nsample > 0), read from the delay
buffer at time-actuator_delay[id] using the requested interpolation order:
Constant extrapolation is used outside of buffer bounds.
Note that the subtraction of the delay changes the semantic of the time argument from “time at which values were
pushed into the delay buffer” to “time at which values come out of the delay buffer”. See Delays for
details.
Read a sensor value at a given time, taking delays into account. If no history buffer exists, return a pointer to the
sensor’s slice of mjData.sensordata. If a history buffer exists (nsample > 0), read from the
history buffer at time-sensor_delay[id]. Note that the subtraction of the delay changes the semantic of the
time argument from “time at which values were pushed into the delay buffer” to “time at which values come out of the
delay buffer”. See Delays for details.
Return value semantics:
If no history buffer exists (nsample = 0), returns a pointer to the sensor’s slice of
mjData.sensordata.
If a history buffer exists (nsample > 0) and the requested time matches a stored sample
(always true for interp=0), returns a pointer to the data in the history buffer.
If interpolation is required (interp=1or2), returns NULL and writes the interpolated result to
result (must be of size dim).
Constant extrapolation is used outside of buffer bounds.
Usage:
// read sensor 0 of data size `dim` at time tmjtNumresult[dim];constmjtNum*ptr=mj_readSensor(m,d,0,t,result,/* interp = */1);constmjtNum*data=ptr?ptr:result;
Initialize the history buffer for an actuator with custom values. The times array specifies the timestamps for each
sample (must be length nsample), and values specifies the control values. If
times is NULL, the existing timestamps in the buffer are used, and only the values are updated.
See Delays for details.
Initialize the history buffer for a sensor with custom values. The times array specifies the timestamps for each
sample (must be length nsample), and values specifies the sensor values (must be of size
nsample*dim). If times is NULL, the existing timestamps in the buffer are used.
The phase argument sets the user slot, which stores the last computation time for interval sensors.
See Delays for details.
This function multiplies the constraint Jacobian mjData.efc_J by a vector. Note that the Jacobian can be either dense or
sparse; the function is aware of this setting. Multiplication by J maps velocities from joint space to constraint space.
This function computes an end-effector kinematic Jacobian, describing the local linear relationship between the
degrees-of-freedom and a given point. Given a body specified by its integer id (body) and a 3D point in the world
frame (point) treated as attached to the body, the Jacobian has both translational (jacp) and rotational
(jacr) components. Passing NULL for either pointer will skip that part of the computation. Each component is a
3-by-nv matrix. Each row of this matrix is the gradient of the corresponding coordinate of the specified point with
respect to the degrees-of-freedom. The frame with respect to which the Jacobian is computed is centered at the body
center-of-mass but aligned with the world frame. The minimal pipeline stages required for Jacobian
computations to be consistent with the current generalized positions mjData.qpos are mj_kinematics followed
by mj_comPos.
This and the remaining variants of the Jacobian function call mj_jac internally, with the center of the body, geom or
site. They are just shortcuts; the same can be achieved by calling mj_jac directly.
This function computes the time-derivative of an end-effector kinematic Jacobian computed by mj_jac.
The minimal pipeline stages required for computation to be
consistent with the current generalized positions and velocities mjData.{qpos,qvel} are
mj_kinematics, mj_comPos, mj_comVel (in that order).
This function computes the 3xnv angular momentum matrix \(H(q)\), providing the linear mapping from
generalized velocities to subtree angular momentum. More precisely if \(h\) is the subtree angular momentum of
body index body in mjData.subtree_angmom (reported by the subtreeangmom sensor)
and \(\dot q\) is the generalized velocity mjData.qvel, then \(h = H \dot q\).
Convert sparse inertia matrix M into full (i.e. dense) matrix.
dst must be of size nvxnv, M must be of the same structure as mjData.qM.
The mjData members qM and M represent the same matrix in different formats; the former is unique to
MuJoCo, the latter is standard Compressed Sparse Row (lower triangle only). The \(L^T D L\) factor of the inertia
matrix mjData.qLD uses the same CSR format as mjData.M. See
engine_support_test for
pedagogical examples.
This function can be used to apply a Cartesian force and torque to a point on a body, and add the result to the vector
mjData.qfrc_applied of all applied forces. Note that the function requires a pointer to this vector, because sometimes
we want to add the result to a different vector.
Compute object 6D acceleration (rot:lin) in object-centered frame, world/local orientation. If acceleration or force
sensors are not present in the model, mj_rnePostConstraint must be manually called in order to calculate
mjData.cacc – the total body acceleration, including contributions from the constraint solver.
Returns the smallest signed distance between two geoms and optionally the segment from geom1 to geom2.
Returned distances are bounded from above by distmax. If no collision of distance smaller than distmax is
found, the function will return distmax and fromto, if given, will be set to (0, 0, 0, 0, 0, 0).
This function subtracts two vectors in the format of qpos (and divides the result by dt), while respecting the
properties of quaternions. Recall that unit quaternions represent spatial orientations. They are points on the unit
sphere in 4D. The tangent to that sphere is a 3D plane of rotational velocities. Thus when we subtract two quaternions
in the right way, the result is a 3D vector and not a 4D vector. Thus the output qvel has dimensionality nv while the
inputs have dimensionality nq.
Scan a directory and load all dynamic libraries. Dynamic libraries in the specified directory
are assumed to register one or more plugins. Optionally, if a callback is specified, it is called
for each dynamic library encountered that registers plugins.
These are components of the simulation pipeline, called internally from mj_step, mj_forward and
mj_inverse. It is unlikely that the user will need to call them.
Integrates the simulation state using an implicit-in-velocity integrator (either “implicit” or “implicitfast”, see
Numerical Integration), and advances simulation time. See mjdata.h for fields computed by this function.
Compute the composite rigid body inertia with mj_crb, add terms due
to tendon armature. The joint-space inertia matrix is stored in both mjData.qM and
mjData.M. These arrays represent the same quantity using different layouts (parent-based and compressed sparse row,
respectively).
Sub-tree linear velocity and angular momentum: compute subtree_linvel, subtree_angmom.
This function is triggered automatically if the subtree velocity or
momentum sensors are present in the model.
It is also triggered for user sensors of stage “vel”.
Recursive Newton Euler with final computed forces and accelerations.
Computes three body-level nvx6 arrays, all defined in the subtreecom-based
c-frame and arranged in [rotation(3),translation(3)] order.
The computed force arrays cfrc_int and cfrc_ext currently suffer from a know bug, they do not take into account
the effect of spatial tendons, see issue #832.
Ray collisions, also known as ray casting, find the distance x of a ray’s intersection with a geom, where a ray is
a line emanating from the 3D point p in the direction v i.e., (p+x*v,x>=0). All functions in this
family return the distance to the nearest geom surface, or -1 if there is no intersection. Note that if p is inside
a geom, the ray will intersect the surface from the inside which still counts as an intersection.
All ray collision functions rely on quantities computed by mj_kinematics (see mjData), so must be called
after mj_kinematics, or functions that call it (e.g. mj_fwdPosition). The top level functions, which
intersect with all geoms types, are mj_ray which casts a single ray, and mj_multiRay which casts multiple
rays from a single point.
Return distance x to nearest surface, or -1 if no intersection.
If geomid is not NULL, write the id of the intersected geom or -1 if not intersection.
If normal is not NULL, write the surface normal at the intersection point. The normal always points out of the
geometry, regardless of the ray’s direction (i.e., including rays hitting the surface from the inside).
Exclude geoms in body with id bodyexclude, use -1 to include all bodies.
geomgroup is an array of length mjNGROUP, where 1 means the group should be included. Pass
NULL to skip geom group exclusion.
If flg_static is 0, static geoms will be excluded.
Virtual file system (VFS) enables the user to load all necessary files in memory, including MJB binary model files, XML
files (MJCF, URDF and included files), STL meshes, PNGs for textures and height fields, and HF files in our custom
height field format. Model and resource files in the VFS can also be constructed programmatically (say using a Python
library that writes to memory). Once all desired files are in the VFS, the user can call mj_loadModel or
mj_loadXML with a pointer to the VFS. When this pointer is not NULL, the loaders will first check the VFS for any
files they are about to load, and only access the disk if the file is not found in the VFS.
Add file to VFS. The directory argument is optional and can be NULL or empty. Returns 0 on success,
2 on name collision, or -1 when an internal error occurs.
The asset cache is a mechanism for caching assets (e.g. textures, meshes, etc.) to avoid repeated slow recompilation.
The following methods provide way to control the capacity of the cache or to disable it altogether.
Resources are the interface between resource providers and MuJoCo model compilation code.
These functions provide the means to query the resource provider and obtain resources.
.. _mju_openResource:
This function is used for mouse selection, relying on ray intersections. aspectratio is the viewport width/height. relx
and rely are the relative coordinates of the 2D point of interest in the viewport (usually mouse cursor). The function
returns the id of the geom under the specified 2D point, or -1 if there is no geom (note that they skybox if present is
not a model geom). The 3D coordinates of the clicked point are returned in selpnt. See simulate for
an illustration.
The functions in this section implement abstract visualization. The results are used by the OpenGL renderer, and can
also be used by users wishing to implement their own renderer, or hook up MuJoCo to advanced rendering tools such as
Unity or Unreal Engine. See simulate for illustration of how to use these functions.
This is the helper function used to construct a UI. The second argument points to an array of mjuiDef structs,
each corresponding to one item. The last (unused) item has its type set to -1, to mark termination. The items are added
after the end of the last used section. There is also another version of this function
(mjui_addToSection) which adds items to a specified section instead of adding them at the end
of the UI. Keep in mind that there is a maximum preallocated number of sections and items per section, given by
mjMAXUISECT and mjMAXUIITEM. Exceeding these maxima results in low-level errors.
This is the main UI update function. It needs to be called whenever the user data (pointed to by the item data pointers)
changes, or when the UI state itself changes. It is normally called by a higher-level function implemented by the user
(UiModify in simulate.cc) which also recomputes the layout of all rectangles and associated
auxiliary buffers. The function updates the pixels in the offscreen OpenGL buffer. To perform minimal updates, the user
specifies the section and the item that was modified. A value of -1 means all items and/or sections need to be updated
(which is needed following major changes.)
This function is the low-level event handler. It makes the necessary changes in the UI and returns a pointer to the item
that received the event (or NULL if no valid event was recorded). This is normally called within the event handler
implemented by the user (UiEvent in simulate.cc), and then some action is taken by user code
depending on which UI item was modified and what the state of that item is after the event is handled.
This function is called in the screen refresh loop. It copies the offscreen OpenGL buffer to the window framebuffer. If
there are multiple UIs in the application, it should be called once for each UI. Thus mjui_render is called all the
time, while mjui_update is called only when changes in the UI take place. dsffsdg
The functions below provide useful derivatives of various functions, both analytic and
finite-differenced. The latter have names with the suffix FD. Note that unlike much of the API,
outputs of derivative functions are the trailing rather than leading arguments.
Letting \(x, u\) denote the current state and control
vector in an mjData instance, and letting \(y, s\) denote the next state and sensor
values, the top-level mj_step function computes \((x,u) \rightarrow (y,s)\)mjd_transitionFD computes the four associated Jacobians using finite-differencing.
These matrices and their dimensions are:
matrix
Jacobian
dimension
A
\(\partial y / \partial x\)
2*nv+nax2*nv+na
B
\(\partial y / \partial u\)
2*nv+naxnu
C
\(\partial s / \partial x\)
nsensordatax2*nv+na
D
\(\partial s / \partial u\)
nsensordataxnu
All outputs are optional (can be NULL).
eps is the finite-differencing epsilon.
flg_centered denotes whether to use forward (0) or centered (1) differences.
The Runge-Kutta integrator (mjINT_RK4) is not supported.
Improving speed and accuracy
warmstart
If warm-starts are not disabled, the warm-start accelerations
mjData.qacc_warmstart which are present at call-time are loaded at the start of every relevant pipeline call,
to preserve determinism. If solver computations are an expensive part of the simulation, the following trick can
lead to significant speed-ups: First call mj_forward to let the solver converge, then reduce solver
iterations significantly, then call mjd_transitionFD, finally, restore the original
value of iterations. Because we are already near the solution, few iteration are required
to find the new minimum. This is especially true for the Newton solver, where the required
number of iteration for convergence near the minimum can be as low as 1.
tolerance
Accuracy can be improved if solver tolerance is set to 0. This means that all calls to
the solver will perform exactly the same number of iterations, preventing numerical errors due to early
termination. Of course, this means that solver iterations should be small, to not tread
water at the minimum. This method and the one described above can and should be combined.
Letting \(x, a\) denote the current state and acceleration vectors in an mjData instance, and
letting \(f, s\) denote the forces computed by the inverse dynamics (qfrc_inverse), the function
mj_inverse computes \((x,a) \rightarrow (f,s)\). mjd_inverseFD computes seven associated Jacobians
using finite-differencing. These matrices and their dimensions are:
matrix
Jacobian
dimension
DfDq
\(\partial f / \partial q\)
nvxnv
DfDv
\(\partial f / \partial v\)
nvxnv
DfDa
\(\partial f / \partial a\)
nvxnv
DsDq
\(\partial s / \partial q\)
nvxnsensordata
DsDv
\(\partial s / \partial v\)
nvxnsensordata
DsDa
\(\partial s / \partial a\)
nvxnsensordata
DmDq
\(\partial M / \partial q\)
nvxnM
All outputs are optional (can be NULL).
All outputs are transposed relative to Control Theory convention (i.e., column major).
DmDq, which contains a sparse representation of the nvxnvxnv tensor \(\partial M / \partial q\), is
not strictly an inverse dynamics Jacobian but is useful in related applications. It is provided as a convenience to
the user, since the required values are already computed if either of the other two \(\partial / \partial q\)
Jacobians are requested.
eps is the (forward) finite-differencing epsilon.
flg_actuation denotes whether to subtract actuation forces (qfrc_actuator) from the output of the inverse
dynamics. If this flag is positive, actuator forces are not considered as external.
The model option flag invdiscrete should correspond to the representation of mjData.qacc in order to compute
the correct derivative information.
Attention
The Runge-Kutta 4th-order integrator (mjINT_RK4) is not supported.
\({\tt \small mju\_quatIntegrate}(q, v, h)\) performs the in-place rotation \(q \leftarrow q + v h\),
where \(q \in \mathbf{S}^3\) is a unit quaternion, \(v \in \mathbf{R}^3\) is a 3D angular velocity and
\(h \in \mathbf{R^+}\) is a timestep. This is equivalent to \({\tt \small mju\_quatIntegrate}(q, s, 1.0)\),
where \(s\) is the scaled velocity \(s = h v\).
\({\tt \small mjd\_quatIntegrate}(v, h, D_q, D_v, D_h)\) computes the Jacobians of the output \(q\) with respect
to the inputs. Below, \(\bar q\) denotes the pre-modified quaternion:
Globally register a plugin. This function is thread-safe.
If an identical mjpPlugin is already registered, this function does nothing.
If a non-identical mjpPlugin with the same name is already registered, an mju_error is raised.
Two mjpPlugins are considered identical if all member function pointers and numbers are equal,
and the name and attribute strings are all identical, however the char pointers to the strings
need not be the same.
Globally register a resource provider in a thread-safe manner. The provider must have a prefix
that is not a sub-prefix or super-prefix of any current registered providers.
Return a slot number >= 0 on success, -1 on failure.
The “functions” in this section are preprocessor macros replaced with the corresponding C standard library math
functions. When MuJoCo is compiled with single precision (which is not currently available to the public, but we
sometimes use it internally) these macros are replaced with the corresponding single-precision functions (not shown
here). So one can think of them as having inputs and outputs of type mjtNum, where mjtNum is defined as double or float
depending on how MuJoCo is compiled. We will not document these functions here; see the C standard library
specification.
Coordinate transform of 6D motion or force vector in rotation:translation format.
rotnew2old is 3-by-3, NULL means no rotation; flg_force specifies force or motion type.
Band-dense Cholesky decomposition.
Add diagadd+diagmul*mat_ii to diagonal before decomposition.
Returns the minimum value of the factorized diagonal or 0 if rank-deficient.
Symmetric band-dense matrices
mju_cholFactorBand and subsequent functions containing the substring “band” operate on matrices which are a
generalization of symmetric band matrices. Symmetric band-dense or
“arrowhead” matrices have non-zeros along proximal diagonal bands and dense blocks on the bottom rows and right
columns. These matrices have the property that Cholesky factorization creates no fill-in and can therefore be
performed efficiently in-place. Matrix structure is defined by three integers:
ntotal: the number of rows (columns) of the symmetric matrix.
nband: the number of bands under (over) the diagonal, inclusive of the diagonal.
ndense: the number of dense rows (columns) at the bottom (right).
The non-zeros are stored in memory as two contiguous row-major blocks, colored green and blue in the illustration
below. The first block has size nbandx(ntotal-ndense) and contains the diagonal and the bands below it. The
second block has size ndensexntotal and contains the dense part. Total required memory is the sum of the block
sizes.
For example, consider an arrowhead matrix with nband=3, ndense=2 and ntotal=8. In this example, the
total memory required is 3*(8-2)+2*8=34 mjtNum’s, laid out as follows:
Minimize \(\tfrac{1}{2} x^T H x + x^T g \quad \text{s.t.} \quad l \le x \le u\), return rank or -1 if failed.
inputs:
n - problem dimension
H - SPD matrix n*n
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 nfree*nfree, 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 allocated size n*(n+7), but only nfree*nfree values are used as output.
index (if given) must have allocated size n, but only nfree values are used as output.
The convenience function mju_boxQPmalloc allocates the required data structures.
Only the lower triangles of H and R are read from and written to, respectively.
Set user payload, overriding the existing value for the specified key if
present. This version differs from mjs_setUserValue in that it takes a
cleanup function that will be called when the user payload is deleted.