Skip to content

Commit

Permalink
Set nativeccd as default.
Browse files Browse the repository at this point in the history
PiperOrigin-RevId: 731343200
Change-Id: I315779017b676f3d118e0d38ee53a515272f50b8
  • Loading branch information
kbayes authored and copybara-github committed Feb 26, 2025
1 parent 4f691ee commit ed16f2d
Show file tree
Hide file tree
Showing 21 changed files with 232 additions and 157 deletions.
13 changes: 4 additions & 9 deletions doc/APIreference/functions.rst
Original file line number Diff line number Diff line change
Expand Up @@ -499,16 +499,11 @@ Returns the smallest signed distance between two geoms and optionally the segmen
Returned distances are bounded from above by ``distmax``. |br| 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).

.. admonition:: Positive ``distmax`` values
:class: note
.. admonition:: different (correct) behavior under `nativeccd`
:class: note

.. TODO: b/339596989 - Improve mjc_Convex.
For some colliders, a large, positive ``distmax`` will result in an accurate measurement. However, for collision
pairs which use the general ``mjc_Convex`` collider, the result will be approximate and likely inaccurate.
This is considered a bug to be fixed in a future release.
In order to determine whether a geom pair uses ``mjc_Convex``, inspect the table at the top of
`engine_collision_driver.c </~https://github.com/google-deepmind/mujoco/blob/main/src/engine/engine_collision_driver.c>`__.
As explained in :ref:`Collision Detection<coDistance>`, distances are inaccurate when using the
:ref:`legacy CCD pipeline<coCCD>`, and its use is discouraged.

.. _mj_contactForce:

Expand Down
13 changes: 4 additions & 9 deletions doc/APIreference/functions_override.rst
Original file line number Diff line number Diff line change
Expand Up @@ -222,16 +222,11 @@ Returns the smallest signed distance between two geoms and optionally the segmen
Returned distances are bounded from above by ``distmax``. |br| 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).

.. admonition:: Positive ``distmax`` values
:class: note
.. admonition:: different (correct) behavior under `nativeccd`
:class: note

.. TODO: b/339596989 - Improve mjc_Convex.
For some colliders, a large, positive ``distmax`` will result in an accurate measurement. However, for collision
pairs which use the general ``mjc_Convex`` collider, the result will be approximate and likely inaccurate.
This is considered a bug to be fixed in a future release.
In order to determine whether a geom pair uses ``mjc_Convex``, inspect the table at the top of
`engine_collision_driver.c </~https://github.com/google-deepmind/mujoco/blob/main/src/engine/engine_collision_driver.c>`__.
As explained in :ref:`Collision Detection<coDistance>`, distances are inaccurate when using the
:ref:`legacy CCD pipeline<coCCD>`, and its use is discouraged.

.. _mj_fullM:

Expand Down
33 changes: 13 additions & 20 deletions doc/XMLreference.rst
Original file line number Diff line number Diff line change
Expand Up @@ -582,6 +582,12 @@ from its default.
This flag disables the mid-phase collision filtering using a static AABB bounding volume hierarchy (a BVH binary
tree). If disabled, all geoms pairs that are allowed to collide are checked for collisions.

.. _option-flag-nativeccd:

:at:`nativeccd`: :at-val:`[disable, enable], "enable"`
This flag enables the native convex collision detection pipeline instead of using the
`libccd library </~https://github.com/danfis/libccd>`__, see :ref:`convex collisions<coCCD>` for more details.

.. _option-flag-eulerdamp:

:at:`eulerdamp`: :at-val:`[disable, enable], "enable"`
Expand Down Expand Up @@ -635,14 +641,12 @@ from its default.

.. _option-flag-multiccd:

:at:`multiccd`: :at-val:`[disable, enable], "disable"` |nbsp| |nbsp| |nbsp| (experimental feature)
:at:`multiccd`: :at-val:`[disable, enable], "disable"`
This flag enables multiple-contact collision detection for geom pairs that use a general-purpose convex-convex
collider e.g., mesh-mesh collisions. This can be useful when the contacting geoms have a flat surface, and the
collider 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.
to instabilities that typically manifest as sliding or wobbling. The implementation of this feature depends on the
selected convex collision pipeline, see :ref:`convex collisions<coCCD>` for more details.

.. _option-flag-island:

Expand All @@ -652,12 +656,6 @@ from its default.
allows for `island visualization <https://youtu.be/Vc1tq0fFvQA>`__.
In a future release, the constraint solver will exploit the disjoint nature of constraint islands.

.. _option-flag-nativeccd:

:at:`nativeccd`: :at-val:`[disable, enable], "disable"`
This flag enables the native convex collision detection pipeline instead of using the
`libccd library </~https://github.com/danfis/libccd>`__.

.. _compiler:

**compiler** (*)
Expand Down Expand Up @@ -6977,16 +6975,11 @@ pipeline. These 3 sensors share some common properties:
to geom-geom penetration) will be reported by :ref:`sensor/distance<sensor-distance>`.
In order to determine collision properties of non-penetrating geom pairs, a positive :at:`cutoff` is required.

.. admonition:: Positive cutoff values
.. admonition:: different (correct) behavior under `nativeccd`
:class: note

.. TODO: b/339596989 - Improve mjc_Convex.
For some colliders, a positive :at:`cutoff` will result in an accurate measurement. However, for collision
pairs which use the general ``mjc_Convex`` collider, the result will be approximate and likely inaccurate.
This is considered a bug to be fixed in a future release.
In order to determine whether a geom pair uses ``mjc_Convex``, inspect the table at the top of
`engine_collision_driver.c </~https://github.com/google-deepmind/mujoco/blob/main/src/engine/engine_collision_driver.c>`__.
As explained in :ref:`Collision Detection<coDistance>`, distances are inaccurate when using the
:ref:`legacy CCD pipeline<coCCD>`, and its use is discouraged.

:at:`geom1`, :at:`geom2`, :at:`body1`, :at:`body2`
For all 3 collision sensor types, the two colliding geoms can be specified explicitly using the :at:`geom1` and
Expand Down
23 changes: 21 additions & 2 deletions doc/changelog.rst
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,23 @@ Feature promotion
</~https://github.com/google-deepmind/mujoco/blob/main/model/flex/gripper_trilinear.xml>`__ flexes for modeling
deformable gripper pads.


- .. image:: images/computation/ccd_light.gif
:width: 20%
:align: right
:class: only-light

.. image:: images/computation/ccd_dark.gif
:width: 20%
:align: right
:class: only-dark

The native convex collision detection pipeline introduced in 3.2.3 and enabled by the
:ref:`nativeccd<option-flag-nativeccd>` flag, is now the default. See the section on
:ref:`Convex Collision Detection<coCCD>` for more details.

**Migration:** If the new pipeline breaks your workflow, set :ref:`nativeccd<option-flag-nativeccd>` to "disable".

General
^^^^^^^
- Add support for custom plots in the MuJoCo viewer by exposing a ``viewport`` property, a ``set_figures`` method,
Expand All @@ -36,6 +53,8 @@ General
.. admonition:: Breaking API changes
:class: attention

- As mentioned above, the native convex collision detection pipeline is now the default, which may break some
workflows. In this case, set :ref:`nativeccd<option-flag-nativeccd>` to "disable" to restore the old behavior.
- Added :ref:`mjs_setDeepCopy` API function. When the deep copy flag is 0, attaching a model will not copy it to the
parent, so the original references to the child can be used to modify the parent after attachment. The default
behavior is to perform such a shallow copy. The old behavior of creating a deep copy of the child model while
Expand Down Expand Up @@ -184,8 +203,8 @@ General

1. The Newton solver no longer requires ``nv*nv`` memory allocation, allowing for much larger models. See e.g.,
`100_humanoids.xml </~https://github.com/google-deepmind/mujoco/blob/main/model/humanoid/100_humanoids.xml>`__.
Two quadratic-memory allocations still remain to be fully sparsified: ``mjData.actuator_moment`` and the matrices used
by the PGS solver.
Two quadratic-memory allocations still remain to be fully sparsified: ``mjData.actuator_moment`` and the matrices
used by the PGS solver.
2. Removed the :at:`solid` and :at:`membrane` plugins and moved the associated computations into the engine. See `3D
example model </~https://github.com/google-deepmind/mujoco/blob/main/model/flex/floppy.xml>`__ and `2D example model
</~https://github.com/google-deepmind/mujoco/blob/main/model/flex/trampoline.xml>`__ for examples of flex objects
Expand Down
113 changes: 96 additions & 17 deletions doc/computation/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -1539,27 +1539,106 @@ Filtering

Checking
~~~~~~~~
Detailed collision checking, also known as *near-phase* or narrow-phase_ collision detection, is performed by functions
that depend on the geom types in the pair. The table of narrow-phase collision functions can be inspected at the top of
`engine_collision_driver.c </~https://github.com/google-deepmind/mujoco/blob/main/src/engine/engine_collision_driver.c>`__
and exposed to users who wish to install their own colliders as :ref:`mjCOLLISIONFUNC`. MuJoCo supports several
primitive geometric shapes: plane, sphere, capsule, cylinder, ellipsoid, and box. It also supports triangulated meshes and
height-fields.

Detailed collision checking is performed by functions that depend on the geom types in the pair. MuJoCo supports several
primitive geometric shapes: plane, sphere, capsule, cylinder, ellipsoid, box. It also supports triangulated meshes and
height fields.
.. _narrow-phase: https://en.wikipedia.org/wiki/Collision_detection#Narrow_phase

We have chosen to limit collision detection to *convex* geoms. All primitive types are convex. Height fields are not
convex but internally they are treated as unions of triangular prisms (using custom collision pruning beyond the filters
described above). Meshes specified by the user can be non-convex, and are rendered as such. For collision purposes
however they are replaced with their convex hulls. Mesh collisions are based on the Minkowski Portal Refinement (MPR)
algorithm as implemented in `libccd </~https://github.com/danfis/libccd>`__. It has tolerance and maximum iteration
parameters exposed as ``mjModel.opt.ccd_tolerance`` and ``mjModel.opt.ccd_iterations`` respectively. MPR operates on the
convex hull implicitly, however pre-computing that hull can substantially improve performance for large meshes. The
model compiler does that by default, using the `qhull <http://www.qhull.org/>`__ library.
With the notable exception of :ref:`SDF plugins<exSDF>` (see documentation therein), collision detection is limited to
*convex* geoms. All primitive types are convex. Height-fields are not convex but internally they are treated as a
collection of triangular prisms (using custom collision pruning beyond the filters described above). Meshes specified by
the user can be non-convex, and are rendered as such. For collision purposes however they are replaced with their convex
hulls (visualized with the 'H' key in :ref:`simulate <saSimulate>`), computed by the `qhull <http://www.qhull.org/>`__
library.

.. _coCCD:

Convex collisions
^^^^^^^^^^^^^^^^^
All collisions involving pairs of geoms that do not have an analytic collider (e.g., meshes), are handled by one of two
general-purpose convex collision detection (CCD) pipelines:

native pipeline (default)
The native CCD pipeline ("nativeccd") is implemented natively in MuJoCo, based on the Gilbert-Johnson-Keerthi and
Expanding Polytope algorithms (GJK_ / EPA_). The native pipeline is both faster and more robust than the MPR-based
pipeline.

libccd pipeline (legacy)
This legacy pipeline is based on the libccd_ library, and uses Minkowski Portal Refinement (MPR_). It is activated by
disabling the :ref:`nativeccd<option-flag-nativeccd>` flag.

.. _libccd: /~https://github.com/danfis/libccd
.. _MPR: https://en.wikipedia.org/wiki/Minkowski_Portal_Refinement
.. _GJK: https://en.wikipedia.org/wiki/Gilbert%E2%80%93Johnson%E2%80%93Keerthi_distance_algorithm
.. _EPA: http://scroll.stanford.edu/courses/cs468-01-fall/Papers/van-den-bergen.pdf

Both pipelines are controlled by a tolerance (in units of distance) and maximum iteration parameters exposed as
``mjOption.ccd_tolerance`` (:ref:`ccd_tolerance<option-ccd_tolerance>`) and ``mjOption.ccd_iterations``
(:ref:`ccd_iterations<option-ccd_iterations>`), respectively.

.. _coMultiCCD:

Multiple contacts
^^^^^^^^^^^^^^^^^
Some colliders can return more than one contact per colliding pair to model line or surface contacts, as when two flat
objects touch. For example the capsule-plane and box-plane colliders can return up to two or four contacts,
respectively. Standard general-purpose convex collision algorithms like MPR and GJK always return a single contact
point, which is problematic for surface contact scenarios (e.g., box-stacking). Both of MuJoCo's CCD pipelines can
return multiple points per contacting pair ("multiccd"). This behavior is controlled by the
:ref:`multiccd<option-flag-multiccd>` flag, but is implemented in different ways with different trade-offs:

libccd pipeline (legacy)
Multiple contact points are found by rotating the two geoms by ±1e-3 radians around the tangential axes and
re-running the collision routine. If a new contact is detected it is added, allowing for up to 4 additional contact
points. This method is effective, but increases the cost of each collision call by a factor of 5.

native pipeline
Native multiccd discovers multiple contacts using a novel analysis of the contacting surfaces at the solution,
avoiding full re-runs of the collision routine, and is thus effectively "free". Note that native multiccd currently
does not support positive contact margins. If one of the two geoms has a positive margin, native multiccd will fall
back to legacy algorithm.

.. _coDistance:

Geom distance
^^^^^^^^^^^^^

.. image:: ../images/computation/ccd_light.gif
:width: 25%
:align: right
:class: only-light

.. image:: ../images/computation/ccd_dark.gif
:width: 25%
:align: right
:class: only-dark

The narrow-phase collision functions described :ref:`above<coChecking>` drive the :ref:`mj_geomDistance` function and
associated :ref:`collision-sensors`. Due to the limitations of MPR, the legacy pipeline will return incorrect values
(top) except at very small distances relative to the geom sizes, and is discouraged for this use case. In
contrast, the GJK-based native pipeline (bottom), computes the correct values at all distances.

Convex decomposition
^^^^^^^^^^^^^^^^^^^^

In order to model a non-convex object other than a height field, the user must decompose it into a union of convex geoms
(which can be primitive shapes or meshes) and attach them to the same body. Open tools like the `CoACD library
</~https://github.com/SarahWeiii/CoACD>`__ can be used outside MuJoCo to automate this process. Finally, all built-in
collision functions can be replaced with custom callbacks. This can be used to incorporate a general-purpose "triangle
soup" collision detector for example. However we do not recommend such an approach. Pre-processing the geometry and
representing it as a union of convex geoms takes some work, but it pays off at runtime and yields both faster and more
stable simulation.
(which can be primitive shapes or meshes) and attach them to the same body. A height-field is essentially a shape that
is automatically-decomposed into prisms

Open mesh-decomposition tools like the
`CoACD library </~https://github.com/SarahWeiii/CoACD>`__ can be used outside MuJoCo to automate this process. Finally,
all built-in collision functions can be replaced with custom callbacks. This can be used to incorporate a
general-purpose "triangle soup" collision detector for example. However we do not recommend such an approach.
Pre-processing the geometry and representing it as a union of convex geoms takes some work, but it pays off at runtime
and yields both faster and more stable simulation.

The exception to this rule are :ref:`SDF plugins<exSDF>` (see documentation therein), which in
`certain cases </~https://github.com/google-deepmind/mujoco/blob/main/plugin/sdf/README.md#gear>`__ can be efficient,
but other requirements and limitations.

.. _Pipeline:

Expand Down
Binary file added doc/images/computation/ccd_dark.gif
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/images/computation/ccd_light.gif
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
6 changes: 3 additions & 3 deletions doc/includes/references.h
Original file line number Diff line number Diff line change
Expand Up @@ -429,8 +429,9 @@ typedef enum mjtDisableBit_ { // disable default feature bitflags
mjDSBL_MIDPHASE = 1<<13, // mid-phase collision filtering
mjDSBL_EULERDAMP = 1<<14, // implicit integration of joint damping in Euler integrator
mjDSBL_AUTORESET = 1<<15, // automatic reset when numerical issues are detected
mjDSBL_NATIVECCD = 1<<16, // native convex collision detection

mjNDISABLE = 16 // number of disable flags
mjNDISABLE = 17 // number of disable flags
} mjtDisableBit;
typedef enum mjtEnableBit_ { // enable optional feature bitflags
mjENBL_OVERRIDE = 1<<0, // override contact parameters
Expand All @@ -440,9 +441,8 @@ typedef enum mjtEnableBit_ { // enable optional feature bitflags
// experimental features:
mjENBL_MULTICCD = 1<<4, // multi-point convex collision detection
mjENBL_ISLAND = 1<<5, // constraint island discovery
mjENBL_NATIVECCD = 1<<6, // native convex collision detection

mjNENABLE = 7 // number of enable flags
mjNENABLE = 6 // number of enable flags
} mjtEnableBit;
typedef enum mjtJoint_ { // type of degree of freedom
mjJNT_FREE = 0, // global position and orientation (quat) (7)
Expand Down
Loading

0 comments on commit ed16f2d

Please sign in to comment.