Skip to content

Commit 87539db

Browse files
committed
Version 2.1.5: Fix GLAD loading on Linux, experimental multi-CCD.
PiperOrigin-RevId: 441482552 Change-Id: I16b7ba81cd81ca2293a9a12bfa08a40ab24c70bb
1 parent 55c1c91 commit 87539db

File tree

18 files changed

+134
-85
lines changed

18 files changed

+134
-85
lines changed

doc/APIreference.rst

Lines changed: 26 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -111,7 +111,10 @@ mjtEnableBit
111111
mjENBL_FWDINV = 1<<2, // compare forward and inverse dynamics
112112
mjENBL_SENSORNOISE = 1<<3, // add noise to sensor data
113113
114-
mjNENABLE = 4 // number of enable flags
114+
// experimental features:
115+
mjENBL_MULTICCD = 1<<30, // multi-point convex collision detection
116+
117+
mjNENABLE = 5 // number of enable flags
115118
} mjtEnableBit;
116119
117120
| Defined in `mjmodel.h <https://github.com/deepmind/mujoco/blob/main/include/mjmodel.h>`_
@@ -2898,13 +2901,13 @@ mjcb_control
28982901
28992902
extern mjfGeneric mjcb_control;
29002903
2901-
| This is the most commonly used callback. It implements a control law, by writing in the vector of controls
2902-
``mjData.ctrl``. It can also write in ``mjData.qfrc_applied`` and ``mjData.xfrc_applied``. The values written in these
2903-
vectors can depend on position, velocity and all other quantities derived from them, but cannot depend on contact
2904-
forces and other quantities that are computed after the control is specified. If the callback accesses the latter
2905-
fields, their values do not correspond to the current time step.
2904+
This is the most commonly used callback. It implements a control law, by writing in the vector of controls
2905+
``mjData.ctrl``. It can also write in ``mjData.qfrc_applied`` and ``mjData.xfrc_applied``. The values written in these
2906+
vectors can depend on position, velocity and all other quantities derived from them, but cannot depend on contact forces
2907+
and other quantities that are computed after the control is specified. If the callback accesses the latter fields, their
2908+
values do not correspond to the current time step.
29062909

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

3414-
| These are the main entry points to the simulator. Most users will only need to call ``mj_step``, which computes
3417+
These are the main entry points to the simulator. Most users will only need to call ``mj_step``, which computes
34153418
everything and advanced the simulation state by one time step. Controls and applied forces must either be set in advance
34163419
(in mjData.ctrl, qfrc_applied and xfrc_applied), or a control callback mjcb_control must be installed which will be
34173420
called just before the controls and applied forces are needed. Alternatively, one can use ``mj_step1`` and ``mj_step2``
34183421
which break down the simulation pipeline into computations that are executed before and after the controls are needed;
34193422
in this way one can set controls that depend on the results from ``mj_step1``. Keep in mind though that the RK4 solver
34203423
does not work with mj_step1/2.
34213424

3422-
| mj_forward performs the same computations as ``mj_step`` but without the integration. It is useful after loading or
3423-
resetting a model (to put the entire mjData in a valid state), and also for out-of-order computations that involve
3424-
sampling or finite-difference approximations.
3425-
3426-
| mj_inverse runs the inverse dynamics, and writes its output in mjData.qfrc_inverse. Note that mjData.qacc must be set
3427-
before calling this function. Given the state (qpos, qvel, act), mj_forward maps from force to acceleration, while
3428-
mj_inverse maps from acceleration to force. Mathematically these functions are inverse of each other, but numerically
3429-
this may not always be the case because the forward dynamics rely on a constraint optimization algorithm which is
3430-
usually terminated early. The difference between the results of forward and inverse dynamics can be computed with the
3431-
function :ref:`mj_compareFwdInv`, which can be though of as another solver accuracy check (as well as a general sanity
3432-
check).
3433-
3434-
| The skip version of mj_forward and mj_inverse are useful for example when qpos was unchanged but qvel was changed
3435-
(usually in the context of finite differencing). Then there is no point repeating the computations that only depend on
3436-
qpos. Calling the dynamics with skipstage = mjSTAGE_POS will achieve these savings.
3425+
mj_forward performs the same computations as ``mj_step`` but without the integration. It is useful after loading or
3426+
resetting a model (to put the entire mjData in a valid state), and also for out-of-order computations that involve
3427+
sampling or finite-difference approximations.
3428+
3429+
mj_inverse runs the inverse dynamics, and writes its output in mjData.qfrc_inverse. Note that mjData.qacc must be set
3430+
before calling this function. Given the state (qpos, qvel, act), mj_forward maps from force to acceleration, while
3431+
mj_inverse maps from acceleration to force. Mathematically these functions are inverse of each other, but numerically
3432+
this may not always be the case because the forward dynamics rely on a constraint optimization algorithm which is
3433+
usually terminated early. The difference between the results of forward and inverse dynamics can be computed with the
3434+
function :ref:`mj_compareFwdInv`, which can be though of as another solver accuracy check (as well as a general sanity
3435+
check).
3436+
3437+
The skip version of mj_forward and mj_inverse are useful for example when qpos was unchanged but qvel was changed
3438+
(usually in the context of finite differencing). Then there is no point repeating the computations that only depend on
3439+
qpos. Calling the dynamics with skipstage = mjSTAGE_POS will achieve these savings.
34373440

34383441
.. _mj_step:
34393442

doc/XMLreference.rst

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

17951803
.. _size:
17961804

17971805
**size** (*)
1798-
~~~~~~~~~~~~~~~~~~~~~~~~~
1806+
~~~~~~~~~~~~
17991807

18001808
This element specifies size parameters that cannot be inferred from the number of elements in the model. Unlike the
18011809
fields of mjOption which can be modified at runtime, sizes are structural parameters and should not be modified after

doc/changelog.rst

Lines changed: 30 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -2,17 +2,38 @@
22
Changelog
33
=========
44

5-
Version 2.1.4 (Apr. 4, 2022)
5+
Version 2.1.5 (Apr. 13, 2022)
66
-----------------------------
77

88
General
99
^^^^^^^
1010

11+
1. Added an experimental feature: multi-contact convex collision detection, activated by an enable flag. See full
12+
description :ref:`here <option-flag>`.
13+
14+
Bug fixes
15+
^^^^^^^^^
16+
17+
2. GLAD initialization logic on Linux now calls ``dlopen`` to load a GL platform dynamic library if a
18+
``*GetProcAddress`` function is not already present in the process' global symbol table. In particular, processes
19+
that use GLFW to set up a rendering context that are not explicitly linked against ``libGLX.so`` (this applies to the
20+
Python interpreter, for example) will now work correctly rather than fail with a ``gladLoadGL`` error when
21+
``mjr_makeContext`` is called.
22+
23+
#. In the Python bindings, named indexers for scalar fields (e.g. the ``ctrl`` field for actuators) now return a NumPy
24+
array of shape ``(1,)`` rather than ``()``. This allows values to be assigned to these fields more straightforwardly.
25+
26+
Version 2.1.4 (Apr. 4, 2022)
27+
----------------------------
28+
29+
General
30+
^^^^^^^
31+
1132
1. MuJoCo now uses GLAD to manage OpenGL API access instead of GLEW. On Linux, there is no longer a need to link against
1233
different GL wrangling libraries depending on whether GLX, EGL, or OSMesa is being used. Instead, users can simply
1334
use GLX, EGL, or OSMesa to create a GL context and ``mjr_makeContext`` will detect which one is being used.
1435

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

1839
Binary build
@@ -26,21 +47,21 @@ Binary build
2647
Simulate
2748
^^^^^^^^
2849

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

31-
#. Contact frame visualisation is added to the Simulate GUI.
52+
#. Contact frame visualisation was added to the Simulate GUI.
3253

33-
#. Rename "set key", "reset to key" to "save key" and "load key", respectively.
54+
#. Renamed "set key", "reset to key" to "save key" and "load key", respectively.
3455

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

3859
Bug fixes
3960
^^^^^^^^^
4061

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

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

@@ -57,13 +78,13 @@ General
5778
Python bindings
5879
^^^^^^^^^^^^^^^
5980

60-
3. Add a ``free()`` method to ``MjrContext``.
81+
3. Added a ``free()`` method to ``MjrContext``.
6182
#. Enums now support arithmetic and bitwise operations with numbers.
6283

6384
Bug fixes
6485
^^^^^^^^^
6586

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

6990

doc/overview.rst

Lines changed: 26 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -354,15 +354,15 @@ purpose of including an asset is to reference it, and referencing can only be do
354354
undefined.
355355

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

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

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

598615
Units are undefined

doc/programming.rst

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -19,9 +19,9 @@ library:
1919
2020
Windows: mujoco.dll (stub library: mujoco.lib)
2121
22-
Linux: mujoco.so.2.1.4
22+
Linux: mujoco.so.2.1.5
2323
24-
macOS: mujoco.2.1.4.dylib
24+
macOS: mujoco.2.1.5.dylib
2525
2626
Even though MuJoCo is a single dynamic library with unified C API, it contains several modules, some of which are
2727
implemented in C++. We have taken advantage of the convenience of C++ for functionality that is used before the

doc/unity.rst

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -29,14 +29,14 @@ _____
2929

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

3535
Linux
3636
_____
3737

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

4141
Windows
4242
_______

include/mjmodel.h

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -69,7 +69,10 @@ typedef enum mjtEnableBit_ { // enable optional feature bitflags
6969
mjENBL_FWDINV = 1<<2, // record solver statistics
7070
mjENBL_SENSORNOISE = 1<<3, // add noise to sensor data
7171

72-
mjNENABLE = 4 // number of enable flags
72+
// experimental features:
73+
mjENBL_MULTICCD = 1<<30, // multi-point convex collision detection
74+
75+
mjNENABLE = 5 // number of enable flags
7376
} mjtEnableBit;
7477

7578

include/mujoco.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ extern "C" {
2424
#endif
2525

2626
// header version; should match the library version as returned by mj_version()
27-
#define mjVERSION_HEADER 214
27+
#define mjVERSION_HEADER 215
2828

2929
// needed to define size_t, fabs and log10
3030
#include "stdlib.h"

introspect/enums.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,8 @@
5151
('mjENBL_ENERGY', 2),
5252
('mjENBL_FWDINV', 4),
5353
('mjENBL_SENSORNOISE', 8),
54-
('mjNENABLE', 4),
54+
('mjENBL_MULTICCD', 1073741824),
55+
('mjNENABLE', 5),
5556
]),
5657
)),
5758
('mjtJoint',

introspect/enums_test.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,8 @@ def test_mjtEnableBit(self): # pylint: disable=invalid-name
4242
('mjENBL_ENERGY', 1<<1),
4343
('mjENBL_FWDINV', 1<<2),
4444
('mjENBL_SENSORNOISE', 1<<3),
45-
('mjNENABLE', 4)))
45+
('mjENBL_MULTICCD', 1<<30),
46+
('mjNENABLE', 5)))
4647

4748
# values mostly increment by one with occasional overrides
4849
def test_mjtGeom(self): # pylint: disable=invalid-name

0 commit comments

Comments
 (0)