@@ -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
29082911forces are needed. When using the RK integrator, it will be called 4 times per step. The alternative way of specifying
29092912controls and applied forces is to set them before ``mj_step ``, or use ``mj_step1 `` and ``mj_step2 ``. The latter approach
29102913allows 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 `` `
34113414Main 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
34153418everything 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
34173420called just before the controls and applied forces are needed. Alternatively, one can use ``mj_step1 `` and ``mj_step2 ``
34183421which break down the simulation pipeline into computations that are executed before and after the controls are needed;
34193422in this way one can set controls that depend on the results from ``mj_step1 ``. Keep in mind though that the RK4 solver
34203423does 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
0 commit comments