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.
Parse XML file in MJCF or URDF format, compile it, return low-level model.
If vfs is not NULL, look up files in vfs before reading from disk.
If error is not NULL, it must have size error_sz.
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.
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 spec from d into state. The bits of the integer
spec correspond to element fields of mjtState. Fails with mju_error if spec is invalid.
Copy concatenated state components specified by spec from state into d. The bits of the integer
spec correspond to element fields of mjtState. Fails with mju_error if spec is invalid.
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 ability to compute end-effector Jacobians efficiently and analytically is one of
the advantages of working in minimal coordinates.
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 multiplies the joint-space inertia matrix stored in mjData.qM by a vector. qM has a custom sparse format
that the user should not attempt to manipulate directly. Alternatively one can convert qM to a dense matrix with
mj_fullM and then user regular matrix-vector multiplication, but this is slower because it no longer benefits from
sparsity.
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.
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.
These are sub-components of the simulation pipeline, called internally from the components above. It is very unlikely
that the user will need to call them.
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 #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.
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
file they are about to load, and only access the disk if the file is not found in the VFS. The file names stored in the
VFS have their name and extension but the path information is stripped; this can be bypassed however by using a custom
path symbol in the file names, say “mydir_myfile.xml”.
The entire VFS is contained in the data structure mjVFS. All utility functions for maintaining the VFS operate on
this data structure. The common usage pattern is to first clear it with mj_defaultVFS, then add disk files to it with
mj_addFileVFS (which allocates memory buffers and loads the file content in memory), then call mj_loadXML or
mj_loadModel, and then clear everything with mj_deleteVFS.
Add file to VFS. The directory argument is optional and can be NULL or empty. Returns 0 on success, 1 when VFS is full,
2 on name collision, or -1 when an internal error occurs.
Set perturb pos,quat in d->mocap when selected body is mocap, and in d->qpos otherwise.
Write d->qpos only if flg_paused and subtree root for selected body has free joint.
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 rendered, and can
also be used by users wishing to implement their own rendered, or hook up MuJoCo to advanced rendering tools such as
Unity or Unreal Engine. See simulate for illustration of how to use these functions.
Set (type, size, pos, mat) for connector-type geom between given points.
Assume that mjv_initGeom was already called to set all other properties.
Width of mjGEOM_LINE is denominated in pixels.
Deprecated: use mjv_connector.
Set (type, size, pos, mat) for connector-type geom between given points.
Assume that mjv_initGeom was already called to set all other properties.
Width of mjGEOM_LINE is denominated in pixels.
Blit from src viewpoint in current framebuffer to dst viewport in other framebuffer.
If src, dst have different size and flg_depth==0, color is interpolated with GL_LINEAR.
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.
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 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.
The convenience function mju_boxQPmalloc allocates the required data structures.
Only the lower triangles of H and R and are read from and written to, respectively.
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.
Accuracy can be somewhat improved if solver iterations are set to a
fixed (small) value and solver tolerance is set to 0. This insures that
all calls to the solver will perform exactly the same number of iterations.
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.
\({\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. This function
returns a slot number > 0 on success.