Skip to content

Commit

Permalink
Version 2.1.5: Fix GLAD loading on Linux, experimental multi-CCD.
Browse files Browse the repository at this point in the history
PiperOrigin-RevId: 441482552
Change-Id: I16b7ba81cd81ca2293a9a12bfa08a40ab24c70bb
  • Loading branch information
saran-t committed Apr 13, 2022
1 parent 55c1c91 commit 87539db
Show file tree
Hide file tree
Showing 18 changed files with 134 additions and 85 deletions.
49 changes: 26 additions & 23 deletions doc/APIreference.rst
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,10 @@ mjtEnableBit
mjENBL_FWDINV = 1<<2, // compare forward and inverse dynamics
mjENBL_SENSORNOISE = 1<<3, // add noise to sensor data
mjNENABLE = 4 // number of enable flags
// experimental features:
mjENBL_MULTICCD = 1<<30, // multi-point convex collision detection
mjNENABLE = 5 // number of enable flags
} mjtEnableBit;
| Defined in `mjmodel.h <https://github.com/deepmind/mujoco/blob/main/include/mjmodel.h>`_
Expand Down Expand Up @@ -2898,13 +2901,13 @@ mjcb_control
extern mjfGeneric mjcb_control;
| This is the most commonly used callback. It implements a control law, by writing in the vector of controls
``mjData.ctrl``. It can also write in ``mjData.qfrc_applied`` and ``mjData.xfrc_applied``. The values written in these
vectors can depend on position, velocity and all other quantities derived from them, but cannot depend on contact
forces and other quantities that are computed after the control is specified. If the callback accesses the latter
fields, their values do not correspond to the current time step.
This is the most commonly used callback. It implements a control law, by writing in the vector of controls
``mjData.ctrl``. It can also write in ``mjData.qfrc_applied`` and ``mjData.xfrc_applied``. The values written in these
vectors can depend on position, velocity and all other quantities derived from them, but cannot depend on contact forces
and other quantities that are computed after the control is specified. If the callback accesses the latter fields, their
values do not correspond to the current time step.

| The control callback is called from within :ref:`mj_forward` and :ref:`mj_step`, just before the controls and applied
The control callback is called from within :ref:`mj_forward` and :ref:`mj_step`, just before the controls and applied
forces are needed. When using the RK integrator, it will be called 4 times per step. The alternative way of specifying
controls and applied forces is to set them before ``mj_step``, or use ``mj_step1`` and ``mj_step2``. The latter approach
allows setting the controls after the position and velocity computations have been performed by ``mj_step1``, allowing
Expand Down Expand Up @@ -3411,29 +3414,29 @@ Print internal XML schema as plain text or HTML, with style-padding or ``&nbsp;`
Main simulation
^^^^^^^^^^^^^^^

| These are the main entry points to the simulator. Most users will only need to call ``mj_step``, which computes
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 and 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 :ref:`mj_compareFwdInv`, which can be though 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.
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 :ref:`mj_compareFwdInv`, which can be though 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.

.. _mj_step:

Expand Down
12 changes: 10 additions & 2 deletions doc/XMLreference.rst
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ XML schema
| | | +-------------------------+-------------------------+-------------------------+ |
| | | | :at:`override` | :at:`energy` | :at:`fwdinv` | |
| | | +-------------------------+-------------------------+-------------------------+ |
| | | | :at:`sensornoise` | | | |
| | | | :at:`sensornoise` | :at:`multiccd` | | |
| | | +-------------------------+-------------------------+-------------------------+ |
+--------------------------+----+------------------------------------------------------------------------------------+
| |_|:el:`size` | \* | .. table:: |
Expand Down Expand Up @@ -1791,11 +1791,19 @@ from its default.
This flag enables the simulation of sensor noise. When disabled (which is the default) noise is not added to
sensordata, even if the sensors specify non-zero noise amplitudes. When enabled, zero-mean Gaussian noise is added to
the underlying deterministic sensor data. Its standard deviation is determined by the noise parameter of each sensor.
:at:`multiccd`: :at-val:`[disable, enable], "disable"` **(experimental feature)**
This flag enables multiple-contact collision detection for geom pairs that use the general-purpose convex-convex
collider based on :ref:`libccd <coChecking>` e.g., mesh-mesh collisions. This can be useful when the contacting geoms
have a flat surface, and the single contact point generated by the convex-convex collider cannot accurately capture
the surface contact, leading to instabilities that typically manifest as sliding or wobbling. Multiple contact points
are found by rotating the two geoms by ±1e-3 radians around the tangential axes and re-running the collision
function. If a new contact is detected it is added, allowing for up to 4 additional contact points. This feature is
currently considered experimental, and both the behavior and the way it is activated may change in the future.

.. _size:

**size** (*)
~~~~~~~~~~~~~~~~~~~~~~~~~
~~~~~~~~~~~~

This element specifies size parameters that cannot be inferred from the number of elements in the model. Unlike the
fields of mjOption which can be modified at runtime, sizes are structural parameters and should not be modified after
Expand Down
39 changes: 30 additions & 9 deletions doc/changelog.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,17 +2,38 @@
Changelog
=========

Version 2.1.4 (Apr. 4, 2022)
Version 2.1.5 (Apr. 13, 2022)
-----------------------------

General
^^^^^^^

1. Added an experimental feature: multi-contact convex collision detection, activated by an enable flag. See full
description :ref:`here <option-flag>`.

Bug fixes
^^^^^^^^^

2. GLAD initialization logic on Linux now calls ``dlopen`` to load a GL platform dynamic library if a
``*GetProcAddress`` function is not already present in the process' global symbol table. In particular, processes
that use GLFW to set up a rendering context that are not explicitly linked against ``libGLX.so`` (this applies to the
Python interpreter, for example) will now work correctly rather than fail with a ``gladLoadGL`` error when
``mjr_makeContext`` is called.

#. In the Python bindings, named indexers for scalar fields (e.g. the ``ctrl`` field for actuators) now return a NumPy
array of shape ``(1,)`` rather than ``()``. This allows values to be assigned to these fields more straightforwardly.

Version 2.1.4 (Apr. 4, 2022)
----------------------------

General
^^^^^^^

1. MuJoCo now uses GLAD to manage OpenGL API access instead of GLEW. On Linux, there is no longer a need to link against
different GL wrangling libraries depending on whether GLX, EGL, or OSMesa is being used. Instead, users can simply
use GLX, EGL, or OSMesa to create a GL context and ``mjr_makeContext`` will detect which one is being used.

#. Add visualisation for contact frames. This is useful when writing or modifying collision functions, when the actual
#. Added visualisation for contact frames. This is useful when writing or modifying collision functions, when the actual
direction of the x and y axes of a contact can be important.

Binary build
Expand All @@ -26,21 +47,21 @@ Binary build
Simulate
^^^^^^^^

4. Fix a bug in simulate where pressing '[' or ']' when a model is not loaded causes a crash.
4. Fixed a bug in simulate where pressing '[' or ']' when a model is not loaded causes a crash.

#. Contact frame visualisation is added to the Simulate GUI.
#. Contact frame visualisation was added to the Simulate GUI.

#. Rename "set key", "reset to key" to "save key" and "load key", respectively.
#. Renamed "set key", "reset to key" to "save key" and "load key", respectively.

#. Change bindings of F6 and F7 from the not very useful "vertical sync" and "busy wait" to the more useful cycling of
#. Changed bindings of F6 and F7 from the not very useful "vertical sync" and "busy wait" to the more useful cycling of
frames and labels.

Bug fixes
^^^^^^^^^

8. ``mj_resetData`` zeroes out the ``solver_nnz`` field.

#. Remove a special branch in ``mju_quat2mat`` for unit quaternions. Previously, ``mju_quat2mat`` skipped all
#. Removed a special branch in ``mju_quat2mat`` for unit quaternions. Previously, ``mju_quat2mat`` skipped all
computation if the real part of the quaternion equals 1.0. For very small angles (e.g. when finite differencing), the
cosine can evaluate to exactly 1.0 at double precision while the sine is still nonzero.

Expand All @@ -57,13 +78,13 @@ General
Python bindings
^^^^^^^^^^^^^^^

3. Add a ``free()`` method to ``MjrContext``.
3. Added a ``free()`` method to ``MjrContext``.
#. Enums now support arithmetic and bitwise operations with numbers.

Bug fixes
^^^^^^^^^

5. Fix rendering bug for planes, introduced in 2.1.2. This broke maze environments in
5. Fixed rendering bug for planes, introduced in 2.1.2. This broke maze environments in
`dm_control <https://github.com/deepmind/dm_control>`_.


Expand Down
35 changes: 26 additions & 9 deletions doc/overview.rst
Original file line number Diff line number Diff line change
Expand Up @@ -354,15 +354,15 @@ purpose of including an asset is to reference it, and referencing can only be do
undefined.

Mesh
MuJoCo can load triangulated meshes from binary STL files. Software such as `MeshLab <https://www.meshlab.net/>`__
can be used to convert from other formats. While any collection of triangles can be loaded and visualized as a mesh,
the collision detector works with the convex hull. There are compile-time options for scaling the mesh, as well as
fitting a primitive geometric shape to it. The mesh can also be used to automatically infer inertial properties - by
treating it as a union of triangular pyramids and combining their masses and inertias. Note that the STL format does
not support color; some software packages write color information in unused fields but this is not consistent.
Instead the mesh is colored using the material properties of the referencing geom. In contrast, all spatial
properties are determined by the mesh data. MuJoCo supports a custom binary file format that can additionally specify
normals and texture coordinates. Meshes can also be embedded directly in the XML.

MuJoCo can load triangulated meshes from OBJ files and binary STL. Software such as `MeshLab
<https://www.meshlab.net/>`__ can be used to convert from other formats. While any collection of triangles can be
loaded and visualized as a mesh, the collision detector works with the convex hull. There are compile-time options
for scaling the mesh, as well as fitting a primitive geometric shape to it. The mesh can also be used to
automatically infer inertial properties -- by treating it as a union of triangular pyramids and combining their
masses and inertias. Note that meshes have no color, instead the mesh is colored using the material properties of the
referencing geom. In contrast, all spatial properties are determined by the mesh data. MuJoCo supports both OBJ and a
custom binary file format for normals and texture coordinates. Meshes can also be embedded directly in the XML.

Skin
Skinned meshes (or skins) are meshes whose shape can deform at runtime. Their vertices are attached to rigid bodies
Expand Down Expand Up @@ -593,6 +593,23 @@ section is to preemptively clarify the aspects that are most likely to be confus
and a tutorial on selected topics. We will need to refer to material covered later in the documentation, but
nevertheless the text below is as self-contained and introductory as possible.

.. _Divergence:

Divergence
~~~~~~~~~~

Divergence of a simulation happens when elements of the state tend quickly to infinity. In MuJoCo this is usually
manifested as an :ref:`mjWARN_BADQACC<mjtwarning>` warning. Divergence is endemic to all physics simulation and is not
necessarily indicative of a bad model or bug in the simulator, but is rather a hint that the timestep is too large for
the given choice of integrator. In physics simulation there is always a tension between speed (large time steps) and
stabillity (small timesteps). A model which is well-tuned for speed has the largest possible timestep that does not
diverge, which usually means that it *can* be made to diverge under extreme conditions. In that sense *rare* cases of
divergence can actually be indicative of a well-tuned model. In all cases it should be possible to prevent divergence by
reducing the timestep and/or switching to a more stable :ref:`integrator <geIntegration>`. If that fails, the culprit is
different. For example in models where bodies are initialized in penetration, large repulsive forces could push them
away and cause divergence.


.. _Units:

Units are undefined
Expand Down
4 changes: 2 additions & 2 deletions doc/programming.rst
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,9 @@ library:
Windows: mujoco.dll (stub library: mujoco.lib)
Linux: mujoco.so.2.1.4
Linux: mujoco.so.2.1.5
macOS: mujoco.2.1.4.dylib
macOS: mujoco.2.1.5.dylib
Even though MuJoCo is a single dynamic library with unified C API, it contains several modules, some of which are
implemented in C++. We have taken advantage of the convenience of C++ for functionality that is used before the
Expand Down
4 changes: 2 additions & 2 deletions doc/unity.rst
Original file line number Diff line number Diff line change
Expand Up @@ -29,14 +29,14 @@ _____

The MuJoCo app needs to be run at least once before the native library can be used, in order to register the library as
a trusted binary. Then, copy the dynamic library file from
``/Applications/MuJoCo.app/Contents/Frameworks/MuJoCo.framework/Versions/Current/libmujoco.2.1.4.dylib`` (it can be
``/Applications/MuJoCo.app/Contents/Frameworks/MuJoCo.framework/Versions/Current/libmujoco.2.1.5.dylib`` (it can be
found by browsing the contents of ``MuJoCo.app``) and rename it as ``mujoco.dylib``.

Linux
_____

Expand the ``tar.gz`` archive to ``~/.mujoco``. Then copy the dynamic library from
``~/.mujoco/mujoco-2.1.4/lib/libmujoco.so.2.1.4`` and rename it as ``libmujoco.so``.
``~/.mujoco/mujoco-2.1.5/lib/libmujoco.so.2.1.5`` and rename it as ``libmujoco.so``.

Windows
_______
Expand Down
5 changes: 4 additions & 1 deletion include/mjmodel.h
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,10 @@ typedef enum mjtEnableBit_ { // enable optional feature bitflags
mjENBL_FWDINV = 1<<2, // record solver statistics
mjENBL_SENSORNOISE = 1<<3, // add noise to sensor data

mjNENABLE = 4 // number of enable flags
// experimental features:
mjENBL_MULTICCD = 1<<30, // multi-point convex collision detection

mjNENABLE = 5 // number of enable flags
} mjtEnableBit;


Expand Down
2 changes: 1 addition & 1 deletion include/mujoco.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ extern "C" {
#endif

// header version; should match the library version as returned by mj_version()
#define mjVERSION_HEADER 214
#define mjVERSION_HEADER 215

// needed to define size_t, fabs and log10
#include "stdlib.h"
Expand Down
3 changes: 2 additions & 1 deletion introspect/enums.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,8 @@
('mjENBL_ENERGY', 2),
('mjENBL_FWDINV', 4),
('mjENBL_SENSORNOISE', 8),
('mjNENABLE', 4),
('mjENBL_MULTICCD', 1073741824),
('mjNENABLE', 5),
]),
)),
('mjtJoint',
Expand Down
3 changes: 2 additions & 1 deletion introspect/enums_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,8 @@ def test_mjtEnableBit(self): # pylint: disable=invalid-name
('mjENBL_ENERGY', 1<<1),
('mjENBL_FWDINV', 1<<2),
('mjENBL_SENSORNOISE', 1<<3),
('mjNENABLE', 4)))
('mjENBL_MULTICCD', 1<<30),
('mjNENABLE', 5)))

# values mostly increment by one with occasional overrides
def test_mjtGeom(self): # pylint: disable=invalid-name
Expand Down
2 changes: 1 addition & 1 deletion python/mujoco/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ include(FindOrFetch)

# ==================== MUJOCO LIBRARY ==========================================
if(NOT TARGET mujoco)
find_library(MUJOCO_LIBRARY mujoco mujoco.2.1.4 HINTS ${MUJOCO_LIBRARY_DIR} REQUIRED)
find_library(MUJOCO_LIBRARY mujoco mujoco.2.1.5 HINTS ${MUJOCO_LIBRARY_DIR} REQUIRED)
find_path(MUJOCO_INCLUDE mujoco.h HINTS ${MUJOCO_INCLUDE_DIR} REQUIRED)
message("MuJoCo is at ${MUJOCO_LIBRARY}")
message("MuJoCo headers are at ${MUJOCO_INCLUDE}")
Expand Down
Loading

0 comments on commit 87539db

Please sign in to comment.