Changelog#

Version 3.1.3 (March 5th, 2024)#

General#

  1. Added the inheritrange attribute to position and intvelocity actuators, allowing convenient setting of the actuator’s ctrlrange or actrange (respectively), according to the range of the transmission target (joint or tendon). See position/inheritrange for details.

  2. Deprecated mj_makeEmptyFileVFS in favor of mj_addBufferVFS. mjVFS now computes checksums of its internal file buffers. mj_addBufferVFS allocates an empty buffer with a given name in an mjVFS and copies the data buffer into it, combining and replacing the deprecated two-step process of calling mj_makeEmptyFileVFS followed by a direct copy into the given mjVFS internal file buffer.

  3. Added mj_angmomMat which computes the 3 x nv angular momentum matrix \(H(q)\), providing the linear mapping from generalized velocities to subtree angular momentum \(h = H \dot q\). Contribution by @v-r-a.

MJX#

  1. Improved performance of getting and putting device data.

    • Use tobytes() for numpy array serialization, which is orders of magnitude faster than converting to tuples.

    • Avoid reallocating host mjData arrays when array shapes are unchanged.

    • Speed up calculation of mjx.ncon for models with many geoms.

    • Avoid calling mjx.ncon in mjx.get_data_into when nc can be derived from mjx.Data.

  2. Fixed a bug in mjx-viewer that prevented it from running. Updated mjx-viewer to use newer mjx.get_data_into function call.

  3. Fixed a bug in mjx.euler that applied incorrect damping when using dense mass matrices.

  4. Fixed a bug in mjx.solve that was causing slow convergence when using mjSOL_NEWTON in mjtSolver.

  5. Added support for mjOption.impratio to mjx.Model.

  6. Added support for cameras in mjx.Model and mjx.Data. Fixes #1422.

  7. Added an implementation of broadphase using top_k and bounding spheres.

Python bindings#

  1. Fixed incorrect data types in the bindings for the geom, vert, elem, and flex array members of the mjContact struct, and all array members of the mjrContext struct.

Version 3.1.2 (February 05, 2024)#

General#

  1. Improved the discardvisual compiler flag, which now discards all visual-only assets. See discardvisual for details.

  2. Removed the timer for midphase colllision detection, it is now folded in with the narrowphase timer. This is because timing the two phases seperately required fine-grained timers inside the collision functions; these functions are so small and fast that the timer itself was incurring a measurable cost.

  3. Added the flag bvactive to visual/global, allowing users to turn off visualisation of active bounding volumes (the red/green boxes in this this changelog item). For models with very high-resolution meshes, the computation required for this visualization can slow down simulation speed. Fixes #1279.

  4. Height-field elevation data can now be specified directly in XML with the elevation attribute (and not only with PNG files). See example model.

MJX#

  1. Added dyntype filterexact.

  2. Added site transmission.

  3. Updated MJX colab tutorial with more stable quadruped environment.

  4. Added mjx.ray which mirrors mj_ray for planes, spheres, capsules, boxes, and meshes.

  5. Added mjx.is_sparse which mirrors mj_isSparse and mjx.full_m which mirrors mj_fullM.

  6. Added support for specifying sparse or dense mass matrices via jacobian: [dense, sparse, auto], “auto”.

  7. Raise a not implemented error when nonzero frictionloss is present. Fixes #1344.

Python bindings#

  1. Improved the implementation of the rollout module. Note the changes below are breaking, dependent code will require modification.

    • Uses mjSTATE_FULLPHYSICS as state spec, enabling divergence detection by inspecting time.

    • Allows user-defined control spec for any combination of user input fields as controls.

    • Outputs are no longer squeezed and always have dim=3.

  2. The sync function for the passive viewer can now pick up changes to rendering flags in user_scn, as requested in #1190.

Bug fixes#

  1. Fixed a bug that prevented the use of pins with plugins if flexes are not in the worldbody. Fixes #1270.

  2. Fixed a bug in the muscle model that led to non-zero values outside the lower bound of the length range. Fixes #1342.

Version 3.1.1 (December 18, 2023)#

Bug fixes#

  1. Fixed a bug (introduced in 3.1.0) where box-box collisions produced no contacts if one box was deeply embedded in the other.

  2. Fixed a bug in simulate where the “LOADING…” message was not showing correctly.

  3. Fixed a crash in the Python passive viewer, when used with models containing Flex objects.

  4. Fixed a bug in MJX where site_xmat was ignored in get_data and put_data

  5. Fixed a bug in MJX where efc_address was sometimes incorrectly calculated in get_data.

Version 3.1.0 (December 12, 2023)#

General#

  1. Improved convergence of Signed Distance Function (SDF) collisions by using line search and a new objective function for the optimization. This allows to decrease the number of initial points needed for finding the contacts and is more robust for very small or large geom sizes.

  2. Added frame to MJCF, a meta-element which defines a pure coordinate transformation on its direct children, without requiring a body.

  3. Added the kv attribute to the position and intvelocity actuators, for specifying actuator-applied damping. This can be used to implement a PD controller with 0 reference velocity. When using this attribute, it is recommended to use the implicitfast or implicit integrators.

Plugins#

  1. Allow actuator plugins to use activation variables in mjData.act as their internal state, rather than mjData.plugin_state. Actuator plugins can now specify callbacks that compute activation variables, and they can be used with built-in dyntype actuator dynamics.

  2. Added the pid actuator plugin, a configurable PID controller that implements the Integral term, which is not available with native MuJoCo actuators.

MJX#

  1. Added site_xpos and site_xmat to MJX.

  2. Added put_data, put_model, get_data to replace device_put and device_get_into, which will be deprecated. These new functions correctly translate fields that are the result of intermediate calculations such as efc_J.

Bug fixes#

  1. Fix bug in Cartesian actuation with movable refsite, as when using body-centric Cartesian actuators on a quadruped. Before this fix such actuators could lead to non-conservation of momentum.

  2. Fix bug that prevented using flex with simulate.

  3. Fix bug that prevented the use of elasticity plugins in combination with pinned flex vertices.

  4. Release Python wheels targeting macOS 10.16 to support x86_64 systems where SYSTEM_VERSION_COMPAT is set. The minimum supported version is still 11.0, but we release these wheels to fix compatibility for those users. See #1213.

  5. Fixed mass computation of meshes: Use the correct mesh volume instead of approximating it using the inertia box.

Version 3.0.1 (November 15, 2023)#

General#

  1. Added sub-terms of total passive forces in mjData.qfrc_passive to mjData: qfrc_{spring, damper, gravcomp, fluid}. The sum of these vectors equals qfrc_passive.

  1. Added actuatorgroupdisable attribute and associated mjOption.disableactuator integer bitfield, which can be used to disable sets of actuators at runtime according to their group. Fixes #1092. See Group disable.

    • The first 6 actuator groups are toggleable in the simulate viewer. See example model and associated screen-capture on the right.

  2. Increased mjMAXUIITEM (maximum number of UI elements per section in Simulate) to 200.

MJX#

  1. Added support for Newton solver (mjSOL_NEWTON in mjtSolver). The Newton solver significantly speeds up simulation on GPU:

    Steps-per-second, Conjugate Gradient vs. Newton on A100#

    Model

    CG

    Newton

    Speedup

    Humanoid

    640,000

    1,020,000

    1.6 x

    Barkour v0

    1,290,000

    1,750,000

    1.35 x

    Shadow Hand

    215,000

    270,000

    1.25 x

    Humanoid is the standard MuJoCo humanoid, Google Barkour and the Shadow Hand are both available in the MuJoCo Menagerie.

  2. Added support for joint equality constraints (mjEQ_JOINT in mjtEq).

  3. Fixed bug where mixed jnt_limited joints were not being constrained correctly.

  4. Made device_put type validation more verbose (fixes #1113).

  5. Removed empty EFC rows from MJX, for joints with no limits (fixes #1117).

  6. Fixed bug in scan.body_tree that led to incorrect smooth dynamics for some kinematic tree layouts.

Python bindings#

  1. Fix the macOS mjpython launcher to work with the Python interpreter from Apple Command Line Tools.

  2. Fixed a crash when copying instances of mujoco.MjData for models that use plugins. Introduced a model attribute to MjData which is reference to the model that was used to create that MjData instance.

Simulate#

  1. simulate: correct handling of “Pause update”, “Fullscreen” and “VSync” buttons.

Documentation#

  1. Added cell to the tutorial colab providing an example of procedural camera control:

  2. Added documentation for the User Interface framework.

  3. Fixed typos and supported fields in docs (fixes #1105 and #1106).

Bug fixes#

  1. Fixed bug relating to welds modified with torquescale.

Version 3.0.0 (October 18, 2023)#

New features#

  1. Added simulation on GPU and TPU via the new MuJoCo XLA (MJX) (MJX) Python module. Python users can now natively run MuJoCo simulations at millions of steps per second on Google TPU or their own accelerator hardware.

    • MJX is designed to work with on-device reinforcement learning algorithms. This Colab notebook demonstrates using MJX along with reinforcement learning to train humanoid and quadruped robots to locomote: colab

    • The MJX API is compatible with MuJoCo but is missing some features in this release. See the outline of MJX feature parity for more details.

  1. Added new signed distance field (SDF) collision primitive. SDFs can take any shape and are not constrained to be convex. Collision points are found by minimizing the maximum of the two colliding SDFs via gradient descent.

    • Added new SDF plugin for defining implicit geometries. The plugin must define methods computing an SDF and its gradient at query points. See the documentation for more details.

  1. Added new low-level model element called flex, used to define deformable objects. These simplicial complexes can be of dimension 1, 2 or 3, corresponding to stretchable lines, triangles or tetrahedra. Two new MJCF elements are used to define flexes. The top-level deformable section contains the low-level flex definition. The flexcomp element, similar to composite is a convenience macro for creating deformables, and supports the GMSH tetrahedral file format.

    • Added shell passive force plugin, computing bending forces using a constant precomputed Hessian (cotangent operator).

    Note: This feature is still under development and subject to change. In particular, deformable object functionality is currently available both via deformable and composite, and both are modifiable by the first-party elasticity plugins. We expect some of this functionality to be unified in the future.

  1. Added constraint island discovery with mj_island. Constraint islands are disjoint sets of constraints and degrees-of-freedom that do not interact. The only solver which currently supports islands is CG. Island discovery can be activated using a new enable flag. If island discovery is enabled, geoms, contacts and tendons will be colored according to the corresponding island, see video. Island discovery is currently disabled for models that have deformable objects (see previous item).

  2. Added mjThreadPool and mjTask which allow for multi-threaded operations within the MuJoCo engine pipeline. If engine-internal threading is enabled, the following operations will be multi-threaded:

    • Island constraint resolution, if island discovery is enabled and the CG solver is selected. The 22 humanoids model shows a 3x speedup compared to the single threaded simulation.

    • Inertia-related computations and collision detection will happen in parallel.

    Engine-internal threading is a work in progress and currently only available in first-party code via the testspeed utility, exposed with the npoolthread flag.

  3. Added capability to initialize composite particles from OBJ files. Fixes #642 and #674.

General#

Breaking API changes

  1. Removed the macros mjMARKSTACK and mjFREESTACK.

    Migration: These macros have been replaced by new functions mj_markStack and mj_freeStack. These functions manage the mjData stack in a fully encapsulated way (i.e., without introducing a local variable at the call site).

  2. Renamed mj_stackAlloc to mj_stackAllocNum. The new function mj_stackAllocByte allocates an arbitrary number of bytes and has an additional argument for specifying the alignment of the returned pointer.

    Migration: The functionality for allocating mjtNum arrays is now available via mj_stackAllocNum.

  3. Renamed the nstack field in mjModel and mjData to narena. Changed narena, pstack, and maxuse_stack to count number of bytes rather than number of mjtNum⁠s.

  4. Changed mjData.solver, the array used to collect solver diagnostic information. This array of mjSolverStat structs is now of length mjNISLAND * mjNSOLVER, interpreted as as a matrix. Each row of length mjNSOLVER contains separate solver statistics for each constraint island. If the solver does not use islands, only row 0 is filled.

    • The new constant mjNISLAND was set to 20.

    • mjNSOLVER was reduced from 1000 to 200.

    • Added mjData.solver_nisland: the number of islands for which the solver ran.

    • Renamed mjData.solver_iter to solver_niter. Both this member and mjData.solver_nnz are now integer vectors of length mjNISLAND.

  5. Removed mjOption.collision and the associated option/collision attribute.

    Migration:

    • For models which have <option collision="all"/>, delete the attribute.

    • For models which have <option collision="dynamic"/>, delete all pair elements.

    • For models which have <option collision="predefined"/>, disable all dynamic collisions (determined via contype/conaffinity) by first deleting all contype and conaffinity attributes in the model and then setting them globally to 0 using
      <default> <geom contype="0" conaffinity="0"/> </default>.

  6. Removed the rope and cloth composite objects.

    Migration: Users should use the cable and shell elasticity plugins.

  7. Added mjData.eq_active user input variable, for enabling/disabling the state of equality constraints. Renamed mjModel.eq_active to mjModel.eq_active0, which now has the semantic of “initial value of mjData.eq_active”. Fixes #876.

    Migration: Replace uses of mjModel.eq_active with mjData.eq_active.

  8. Changed the default of autolimits from “false” to “true”. This is a minor breaking change. The potential breakage applies to models which have elements with “range” defined and “limited” not set. Such models cannot be loaded since version 2.2.2 (July 2022).

  1. Added a new dyntype, filterexact, which updates first-order filter states with the exact formula rather than with Euler integration.

  2. Added an actuator attribute, actearly, which uses semi-implicit integration for actuator forces: using the next step’s actuator state to compute the current actuator forces.

  3. Renamed actuatorforcerange and actuatorforcelimited, introduced in the previous version to actuatorfrcrange and actuatorfrclimited, respectively.

  4. Added the flag eulerdamp, which disables implicit integration of joint damping in the Euler integrator. See the Numerical Integration section for more details.

  5. Added the flag invdiscrete, which enables discrete-time inverse dynamics for all integrators other than RK4. See the flag documentation for more details.

  6. Added ls_iterations and ls_tolerance options for adjusting linesearch stopping criteria in CG and Newton solvers. These can be useful for performance tuning.

  7. Added mesh_pos and mesh_quat fields to mjModel to store the normalizing transformation applied to mesh assets. Fixes #409.

  8. Added camera resolution attribute and camprojection sensor. If camera resolution is set to positive values, the camera projection sensor will report the location of a target site, projected onto the camera image, in pixel coordinates.

  9. Added camera calibration attributes:

  10. Implemented reversed Z rendering for better depth precision. An enum mjtDepthMap was added with values mjDEPTH_ZERONEAR and mjDEPTH_ZEROFAR, which can be used to set the new readDepthMap attribute in mjrContext to control how the depth returned by mjr_readPixels is mapped from znear to zfar. Contribution #978 by Levi Burner.

  11. Deleted the code sample testxml. The functionality provided by this utility is implemented in the WriteReadCompare test.

  12. Deleted the code sample derivative. Functionality provided by mjd_transitionFD.

Python bindings#

  1. Fixed #870 where calling update_scene with an invalid camera name used the default camera.

  2. Added user_scn to the passive viewer handle, which allows users to add custom visualization geoms (#1023).

  3. Added optional boolean keyword arguments show_left_ui and show_right_ui to the functions viewer.launch and viewer.launch_passive, which allow users to launch a viewer with UI panels hidden.

Simulate#

  1. Added state history mechanism to simulate and the managed Python viewer. State history can be viewed by scrubbing the History slider and (more precisely) with the left and right arrow keys. See screen capture:

  2. The LOADING... label is now shown correctly. Contribution #1070 by Levi Burner.

Documentation#

  1. Added detailed documentation of fluid force modeling, and an illustrative example model showing tumbling cards using the ellipsoid-based fluid model.

Bug fixes#

  1. Fixed a bug that was causing geom margin to be ignored during the construction of midphase collision trees.

  2. Fixed a bug that was generating incorrect values in efc_diagApprox for weld equality constraints.

Version 2.3.7 (July 20, 2023)#

General#

  1. Added primitive collider for sphere-cylinder contacts, previously this pair used the generic convex-convex collider.

  2. Added joint-actuatorforcerange for clamping total actuator force at joints and sensor-jointactuatorfrc for measuring total actuation force applied at a joint. The most important use case for joint-level actuator force clamping is to ensure that Cartesian actuator forces are realizable by individual motors at the joints. See Force limits for details.

  3. Added an optional content_type attribute to hfield, texture, and mesh assets. This attribute supports a formatted Media Type (previously known as MIME type) string used to determine the type of the asset file without resorting to pulling the type from the file extension.

  4. Added analytic derivatives for quaternion subtraction and integration (rotation with an angular velocity). Derivatives are in the 3D tangent space.

  5. Added mjv_connector which has identical functionality to mjv_makeConnector, but with more convenient “from-to” argument parametrization. mjv_makeConnector is now deprecated.

  6. Bumped oldest supported MacOS from version 10.12 to 11. MacOS 11 is the oldest version still maintained by Apple.

Python bindings#

  1. The passive viewer handle now exposes update_hfield, update_mesh, and update_texture methods to allow users to update renderable assets. (Issues #812, #958, #965).

  2. Allow a custom keyboard event callback to be specified in the passive viewer (#766).

  3. Fix GLFW crash when Python exits while the passive viewer is running (#790).

Models#

  1. Added simple car example model.

Version 2.3.6 (June 20, 2023)#

Note

MuJoCo 2.3.6 is the last version to officially support Python 3.7.

Models#

  1. Added 3x3x3 cube example model. See README for details.

Bug fixes#

  1. Fixed a bug that was causing an incorrect computation of the mesh bounding box and coordinate frame if the volume was invalid. In such case, now MuJoCo only accepts a non-watertight geometry if shellinertia is equal to true.

  2. Fixed the sparse Jacobian multiplication logic that is used to compute derivatives for tendon damping and fluid force, which affects the behaviour of the implicit and implicitfast integrators.

  3. Fixes to mj_ray, in line with geom visualisation conventions:

    • Planes and height-fields respect the geom_group and flg_static arguments. Before this change, rays would intersect planes and height-fields unconditionally.

    • flg_static now applies to all static geoms, not just those which are direct children of the world body.

Plugins#

  1. Added touch-grid sensor plugin. See documentation for details, and associated touch_grid.xml example model. The plugin includes in-scene visualisation.

Simulate#

  1. Added Visualization tab to simulate UI, corresponding to elements of the visual MJCF element. After modifying values in the GUI, a saved XML will contain the new values. The modifyable members of mjStatistic (extent, meansize and center) are computed by the compiler and therefore do not have defaults. In order for these attributes to appear in the saved XML, a value must be specified in the loaded XML.

Before / After
  1. Increased text width for UI elements in the default spacing. [before / after]:

General#

  1. Added mj_getState and mj_setState for getting and setting the simulation state as a concatenated vector of floating point numbers. See the State section for details.

  2. Added mjContact.solreffriction, allowing different solref parameters for the normal and frictional axes of contacts when using elliptic friction cones. This attribute is required for elastic frictional collisions, see associated example model mimicking the spin-bounce recoil behaviour of elastic rubber balls. This is an advanced option currently only supported by explicit contact pairs, using the solreffriction attribute.

  3. Added mjd_inverseFD for finite-differenced inverse-dynamics derivatives.

  4. Added functions for operations on banded-then-dense “arrowhead” matrices. Such matrices are common when doing direct trajectory optimization. See mju_cholFactorBand documentation for details.

  5. Added mj_multiRay function for intersecting multiple rays emanating from a single point. This is significantly faster than calling mj_ray multiple times.

  6. Ray-mesh collisions are now up to 10x faster, using a bounding volume hierarchy of mesh faces.

  7. Increased mjMAXUIITEM (maximum number of UI elements per section in Simulate) to 100.

  8. Added documentation for resource providers.

  9. Changed the formula for mju_sigmoid, a finite-support sigmoid \(s \colon \mathbf R \rightarrow [0, 1]\). Previously, the smooth part consisted of two stitched quadratics, once continuously differentiable. It is now a single quintic, twice continuously differentiable:

\[s(x) = \begin{cases} 0, & & x \le 0 \\ 6x^5 - 15x^4 + 10x^3, & 0 \lt & x \lt 1 \\ 1, & 1 \le & x \qquad \end{cases} \]
  1. Added optional tausmooth attribute to muscle actuators. When positive, the time-constant \(\tau\) of muscle activation/deactivation uses mju_sigmoid to transition smoothly between the two extremal values given by the Millard et al. (2013) muscle model, within a range of width tausmooth. See Muscle actuators for more details. Relatedly, mju_muscleDynamics now takes 3 parameters instead of 2, adding the new smoothing-width parameter.

  2. Moved public C macro definitions out of mujoco.h into a new public header file called mjmacro.h. The new file is included by mujoco.h so this change does not break existing user code.

  3. Added instrumentation for the Address Sanitizer (ASAN) and Memory Sanitizer (MSAN) to detect memory bugs when allocating from the mjData stack and arena.

  4. Removed pstack and parena from the output of mj_printData, since these are implementation details of the mjData allocators that are affected by diagnostic paddings in instrumented builds.

  5. Removed the mj_activate and mj_deactivate functions. These had been kept around for compatibility with old user code from when MuJoCo was closed source, but have been no-op functions since open sourcing.

Version 2.3.5 (April 25, 2023)#

Bug fixes#

  1. Fix asset loading bug that prevented OBJ and PNG files from being read from disk when mjVFS is used.

  2. Fix occasional segmentation faults on macOS when mouse perturbations are applied in the Python passive viewer.

Plugins#

  1. The visualize callback in mjpPlugin now receives an mjvOption as an input argument.

Version 2.3.4 (April 20, 2023)#

Note

This version is affected by an asset loading bug that prevents OBJ and PNG files from being read from disk when mjVFS is used. Users are advised to skip to version 2.3.5 instead.

General#

  1. Removed the “global” setting of the compiler/coordinate attribute. This rarely-used setting complicates the compiler logic and is blocking future improvements. In order to convert older models which used this option, load and save them in MuJoCo 2.3.3 or older.

_images/ellipsoidinertia.gif
  1. Added visual-global flag ellipsoidinertia to visualize equivalent body inertias with ellipsoids instead of the default boxes.

  2. Added midphase and broadphase collision statistics to mjData.

  3. Added documentation for engine plugins.

  4. Added struct information to the introspect module.

  5. Added a new extension mechanism called resource providers. This extensible mechanism allows MuJoCo to read assets from data sources other than the local OS filesystem or the Virtual file system.

Python bindings#

  1. Offscreen rendering on macOS is no longer restricted to the main thread. This is achieved by using the low-level Core OpenGL (CGL) API to create the OpenGL context, rather than going via GLFW which relies on Cocoa’s NSOpenGL. The resulting context is not tied to a Cocoa window, and is therefore not tied to the main thread.

  2. Fixed a race condition in viewer.launch_passive and viewer.launch_repl. These functions could previously return before an internal call to mj_forward. This allows user code to continue and potentially modify physics state concurrently with the internal mj_forward, resulting in e.g. MuJoCo stack overflow error or segmentation fault.

  3. The viewer.launch_passive function now returns a handle which can be used to interact with the viewer. The passive viewer now also requires an explicit call to sync on its handle to pick up any update to the physics state. This is to avoid race conditions that can result in visual artifacts. See documentation for details.

  4. The viewer.launch_repl function has been removed since its functionality is superceded by launch_passive.

  5. Added a small number of missing struct fields discovered through the new introspect metadata.

Bug fixes#

  1. Fixed bug in the handling of ellipsoid-based fluid model forces in the new implicitfast integrator.

  2. Removed spurious whole-arena copying in mj_copyData, which can considerably slow down the copying operation.

  3. Make shellinertia ignore exactmeshinertia, which is only used for legacy volume computations (#759).

Version 2.3.3 (March 20, 2023)#

General#

  1. Improvements to implicit integration:

    • The derivatives of the RNE algorithm are now computed using sparse math, leading to significant speed improvements for large models when using the implicit integrator.

    • A new integrator called implicitfast was added. It is similar to the existing implicit integrator, but skips the derivatives of Coriolis and centripetal forces. See the numerical integration section for a detailed motivation and discussion. The implicitfast integrator is recommended for all new models and will become the default integrator in a future version.

    The table below shows the compute cost of the 627-DoF humanoid100 model using different integrators. “implicit (old)” uses dense RNE derivatives, “implicit (new)” is after the sparsification mentioned above. Timings were measured on a single core of an AMD 3995WX CPU.

timing

Euler

implicitfast

implicit (new)

implicit (old)

one step (ms)

0.5

0.53

0.77

5.0

steps/second

2000

1900

1300

200

_images/midphase.gif
  1. Added a collision mid-phase for pruning geoms in body pairs, see documentation for more details. This is based on static AABB bounding volume hierarchy (a BVH binary tree) in the body inertial frame. The GIF on the right is cut from this longer video.

  2. The mjd_transitionFD function no longer triggers sensor calculation unless explicitly requested.

  3. Corrected the spelling of the inteval attribute to interval in the mjLROpt struct.

  4. Mesh texture and normal mappings are now 3-per-triangle rather than 1-per-vertex. Mesh vertices are no longer duplicated in order to circumvent this limitation as they previously were.

  5. The non-zeros for the sparse constraint Jacobian matrix are now precounted and used for matrix memory allocation. For instance, the constraint Jacobian matrix from the humanoid100 model, which previously required ~500,000 mjtNum’s, now only requires ~6000. Very large models can now load and run with the CG solver.

  6. Modified mju_error and mju_warning to be variadic functions (support for printf-like arguments). The functions mju_error_i, mju_error_s, mju_warning_i, and mju_warning_s are now deprecated.

  7. Implemented a performant mju_sqrMatTDSparse function that doesn’t require dense memory allocation.

  8. Added mj_stackAllocInt to get correct size for allocating ints on mjData stack. Reducing stack memory usage by 10% - 15%.

Python bindings#

  1. Fixed IPython history corruption when using viewer.launch_repl. The launch_repl function now provides seamless continuation of an IPython interactive shell session, and is no longer considered experimental feature.

  2. Added viewer.launch_passive which launches the interactive viewer in a passive, non-blocking mode. Calls to launch_passive return immediately, allowing user code to continue execution, with the viewer automatically reflecting any changes to the physics state. (Note that this functionality is currently in experimental/beta stage, and is not yet described in our viewer documentation.)

  3. Added the mjpython launcher for macOS, which is required for viewer.launch_passive to function there.

  4. Removed efc_ fields from joint indexers. Since the introduction of arena memory, these fields now have dynamic sizes that change between time steps depending on the number of active constraints, breaking strict correspondence between joints and efc_ rows.

  5. Added a number of missing fields to the bindings of mjVisual and mjvPerturb structs.

Simulate#

  1. Implemented a workaround for broken VSync on macOS so that the frame rate is correctly capped when the Vertical Sync toggle is enabled.

_images/contactlabel.png
  1. Added optional labels to contact visualization, indicating which two geoms are contacting (names if defined, ids otherwise). This can be useful in cluttered scenes.


Version 2.3.2 (February 7, 2023)#

General#

  1. A more performant mju_transposeSparse has been implemented that doesn’t require dense memory allocation. For a constraint Jacobian matrix from the humanoid100.xml model, this function is 35% faster.

  2. The function mj_name2id is now implemented using a hash function instead of a linear search for better performance.

  3. Geom names are now parsed from URDF. Any duplicate names are ignored. mj_printData output now contains contacting geom names.

Bug fixes#

  1. Fixed a bug that for shellinertia equal to true caused the mesh orientation to be overwritten by the principal components of the shell inertia, while the vertex coordinates are rotated using the volumetric inertia. Now the volumetric inertia orientation is used also in the shell case.

  2. Fixed misalignment bug in mesh-to-primitive fitting when using the bounding box fitting option fitaabb.

_images/meshfit.png
  1. The launch_repl functionality in the Python viewer has been fixed.

  2. Set time correctly in mjd_transitionFD, to support time-dependent user code.

  3. Fixed sensor data dimension validation when user type sensors are present.

  4. Fixed incorrect plugin error message when a null nsensordata callback is encountered during model compilation.

  5. Correctly end the timer (TM_END) mj_fwdConstraint returns early.

  6. Fixed an infinite loop in mj_deleteFileVFS.

Simulate#

  1. Increased precision of simulate sensor plot y-axis by 1 digit (#719).

  2. Body labels are now drawn at the body frame rather than inertial frame, unless inertia is being visualised.

Plugins#

  1. The reset callback now receives instance-specific plugin_state and plugin_data as arguments, rather than the entire mjData. Since reset is called inside mj_resetData before any physics forwarding call has been made, it is an error to read anything from mjData at this stage.

  2. The capabilities field in mjpPlugin is renamed capabilityflags to more clearly indicate that this is a bit field.

Version 2.3.1 (December 6, 2022)#

Python bindings#

  1. The simulate GUI is now available through the mujoco Python package as mujoco.viewer. See documentation for details. (Contribution by Levi Burner.)

  2. The Renderer class from the MuJoCo tutorial Colab is now available directly in the native Python bindings.

General#

  1. The tendon springlength attribute can now take two values. Given two non-decreasing values, springlength specifies a deadband range for spring stiffness. If the tendon length is between the two values, the force is 0. If length is outside this range, the force behaves like a regular spring, with the spring resting length corresponding to the nearest springlength value. This can be used to create tendons whose limits are enforced by springs rather than constraints, which are cheaper and easier to analyse. See tendon_springlength.xml example model.

    Attention

    This is a minor breaking API change. mjModel.tendon_lengthspring now has size ntendon x 2 rather than ntendon x 1.

  2. Removed the requirement that stateless actuators come before stateful actuators.

  3. Added mju_fill, mju_symmetrize and mju_eye utility functions.

  4. Added gravcomp attribute to body, implementing gravity compensation and buoyancy. See balloons.xml example model.

  5. Renamed the cable plugin library to elasticity.

  6. Added actdim attribute to general actuators. Values greater than 1 are only allowed for dyntype user, as native activation dynamics are all scalar. Added example test implementing 2nd-order activation dynamics to engine_forward_test.cc.

  7. Improved particle composite type, which now permits a user-specified geometry and multiple joints. See the two new examples: particle_free.xml and particle_free2d.xml.

  8. Performance improvements for non-AVX configurations:

  9. Added new solid passive force plugin:

    • This is new force field compatible with the composite particles.

    • Generates a tetrahedral mesh having particles with mass concentrated at vertices.

    • Uses a piecewise-constant strain model equivalent to finite elements but expressed in a coordinate-free formulation. This implies that all quantities can be precomputed except edge elongation, as in a mass-spring model.

    • Only suitable for small strains (large displacements but small deformations). Tetrahedra may invert if subject to large loads.

  10. Added API functions mj_loadPluginLibrary and mj_loadAllPluginLibraries. The first function is identical to dlopen on a POSIX system, and to LoadLibraryA on Windows. The second function scans a specified directory for all dynamic libraries file and loads each library found. Dynamic libraries opened by these functions are assumed to register one or more MuJoCo plugins on load.

  11. Added an optional visualize callback to plugins, which is called during mjv_updateScene. This callback allows custom plugin visualizations. Enable stress visualization for the Cable plugin as an example.

  12. Sensors of type user no longer require objtype, objname and needstage. If unspecified, the objtype is now mjOBJ_UNKNOWN. user sensors datatype default is now “real”, needstage default is now “acc”.

  13. Added support for capsules in URDF import.

  14. On macOS, issue an informative error message when run under Rosetta 2 translation on an Apple Silicon machine. Pre-built MuJoCo binaries make use of AVX instructions on x86-64 machines, which is not supported by Rosetta 2. (Before this version, users only get a cryptic “Illegal instruction” message.)

Bug fixes#

  1. Fixed bug in mj_addFileVFS that was causing the file path to be ignored (introduced in 2.1.4).

Simulate#

  1. Renamed the directory in which the simulate application searches for plugins from plugin to mujoco_plugin.

  2. Mouse force perturbations are now applied at the selection point rather than the body center of mass.

Version 2.3.0 (October 18, 2022)#

General#

  1. The contact array and arrays prefixed with efc_ in mjData were moved out of the buffer into a new arena memory space. These arrays are no longer allocated with fixed sizes when mjData is created. Instead, the exact memory requirement is determined during each call to mj_forward (specifically, in mj_collision and mj_makeConstraint) and the arrays are allocated from the arena space. The stack now also shares its available memory with arena. This change reduces the memory footprint of mjData in models that do not use the PGS solver, and will allow for significant memory reductions in the future. See the Memory allocation section for details.

  2. Added colab notebook tutorial showing how to balance the humanoid on one leg with a Linear Quadratic Regulator. The notebook uses MuJoCo’s native Python bindings, and includes a draft Renderer class, for easy rendering in Python.
    Try it yourself: LQRopenincolab

  3. Updates to humanoid model: - Added two keyframes (stand-on-one-leg and squat). - Increased maximum hip flexion angle. - Added hamstring tendons which couple the hip and knee at high hip flexion angles. - General cosmetic improvements, including improved use of defaults and better naming scheme.

  4. Added mju_boxQP and allocation function mju_boxQPmalloc for solving the box-constrained Quadratic Program:

    \[x^* = \text{argmin} \; \tfrac{1}{2} x^T H x + x^T g \quad \text{s.t.} \quad l \le x \le u\]

    The algorithm, introduced in Tassa et al. 2014, converges after 2-5 Cholesky factorisations, independent of problem size.

  5. Added mju_mulVecMatVec to multiply a square matrix \(M\) with vectors \(x\) and \(y\) on both sides. The function returns \(x^TMy\).

  6. Added new plugin API. Plugins allow developers to extend MuJoCo’s capability without modifying core engine code. The plugin mechanism is intended to replace the existing callbacks, though these will remain for the time being as an option for simple use cases and backward compatibility. The new mechanism manages stateful plugins and supports multiple plugins from different sources, allowing MuJoCo extensions to be introduced in a modular fashion, rather than as global overrides. Note the new mechanism is currently undocumented except in code, as we test it internally. If you are interested in using the plugin mechanism, please get in touch first.

  7. Added assetdir compiler option, which sets the values of both meshdir and texturedir. Values in the latter attributes take precedence over assetdir.

  8. Added realtime option to visual for starting a simulation at a slower speed.

  9. Added new cable composite type:

    • Cable elements are connected with ball joints.

    • The initial parameter specifies the joint at the starting boundary: free, ball, or none.

    • The boundary bodies are exposed with the names B_last and B_first.

    • The vertex initial positions can be specified directly in the XML with the parameter vertex.

    • The orientation of the body frame is the orientation of the material frame of the curve.

  10. Added new cable passive force plugin:

    • Twist and bending stiffness can be set separately with the parameters twist and bend.

    • The stress-free configuration can be set to be the initial one or flat with the flag flat.

    • New cable.xml example showing the formation of plectoneme.

    • New coil.xml example showing a curved equilibrium configuration.

    • New belt.xml example showing interaction between twist and anisotropy.

    • Added test using cantilever exact solution.

Python bindings#

  1. Added id and name properties to named accessor objects. These provide more Pythonic API access to mj_name2id and mj_id2name respectively.

  2. The length of MjData.contact is now ncon rather than nconmax, allowing it to be straightforwardly used as an iterator without needing to check ncon.

  3. Fix a memory leak when a Python callable is installed as callback (#527).

Version 2.2.2 (September 7, 2022)#

General#

  1. Added adhesion actuators mimicking vacuum grippers and adhesive biomechanical appendages.

  2. Added related example model and video:

  3. Added mj_jacSubtreeCom for computing the translational Jacobian of the center-of-mass of a subtree.

  4. Added torquescale and anchor attributes to weld constraints. torquescale sets the torque-to-force ratio exerted by the constraint, anchor sets the point at which the weld wrench is applied. See weld for more details.

  5. Increased mjNEQDATA, the row length of equality constraint parameters in mjModel.eq_data, from 7 to 11.

  6. Added visualisation of anchor points for both connect and weld constraints (activated by the ‘N’ key in simulate).

  7. Added weld.xml showing different uses of new weld attributes.

  8. Cartesian 6D end-effector control is now possible by adding a reference site to actuators with site transmission. See description of new refsite attribute in the actuator documentation and refsite.xml example model.

  9. Added autolimits compiler option. If true, joint and tendon limited attributes and actuator ctrllimited, forcelimited and actlimited attributes will automatically be set to true if the corresponding range is defined and false otherwise.

    If autolimits="false" (the default) models where a range attribute is specified without the limited attribute will fail to compile. A future release will change the default of autolimits to true, and this compilation error allows users to catch this future change of behavior.

    Attention

    This is a breaking change. In models where a range was defined but limited was unspecified, explicitly set limited to false or remove the range to maintain the current behavior of your model.

  10. Added moment of inertia computation for all well-formed meshes. This option is activated by setting the compiler flag exactmeshinertia to true (defaults to false). This default may change in the future.

  11. Added parameter shellinertia to geom, for locating the inferred inertia on the boundary (shell). Currently only meshes are supported.

  12. For meshes from which volumetric inertia is inferred, raise error if the orientation of mesh faces is not consistent. If this occurs, fix the mesh in e.g., MeshLab or Blender.

  13. Added catenary visualisation for hanging tendons. The model seen in the video can be found here.

  14. Added azimuth and elevation attributes to visual/global, defining the initial orientation of the free camera at model load time.

  15. Added mjv_defaultFreeCamera which sets the default free camera, respecting the above attributes.

  16. simulate now supports taking a screenshot via a button in the File section or via Ctrl-P.

  17. Improvements to time synchronisation in simulate, in particular report actual real-time factor if different from requested factor (if e.g., the timestep is so small that simulation cannot keep up with real-time).

  18. Added a disable flag for sensors.

  19. mju_mulQuat and mju_mulQuatAxis support in place computation. For example
    mju_mulQuat(a, a, b); sets the quaternion a equal to the product of a and b.

  20. Added sensor matrices to mjd_transitionFD (note this is an API change).

Deleted/deprecated features#

  1. Removed distance constraints.

Bug fixes#

  1. Fixed rendering of some transparent geoms in reflection.

  2. Fixed intvelocity defaults parsing.

Version 2.2.1 (July 18, 2022)#

General#

  1. Added mjd_transitionFD to compute efficient finite difference approximations of the state-transition and control-transition matrices, see here for more details.

  2. Added derivatives for the ellipsoid fluid model.

  3. Added ctrl attribute to keyframes.

  4. Added clock sensor which measures time.

  5. Added visualisation groups to skins.

  6. Added actuator visualisation for free and ball joints and for actuators with site transmission.

  7. Added visualisation for actuator activations.

  8. Added <actuator-intvelocity> actuator shortcut for “integrated velocity” actuators, documented here.

  9. Added <actuator-damper> actuator shortcut for active-damping actuators, documented here.

  10. mju_rotVecMat and mju_rotVecMatT now support in-place multiplication.

  11. mjData.ctrl values are no longer clamped in-place, remain untouched by the engine.

  12. Arrays in mjData’s buffer now align to 64-byte boundaries rather than 8-byte.

  13. Added memory poisoning when building with Address Sanitizer (ASAN) and Memory Sanitizer (MSAN). This allows ASAN to detect reads and writes to regions in mjModel.buffer and mjData.buffer that do not lie within an array, and for MSAN to detect reads from uninitialised fields in mjData following mj_resetData.

  14. Added a slider-crank example model.

Bug fixes#

  1. Activation clamping was not being applied in the implicit integrator.

  2. Stricter parsing of orientation specifiers. Before this change, a specification that included both quat and an alternative specifier e.g., <geom ... quat=".1 .2 .3 .4" euler="10 20 30">, would lead to the quat being ignored and only euler being used. After this change a parse error will be thrown.

  3. Stricter parsing of XML attributes. Before this change an erroneous XML snippet like <geom size="1/2 3 4"> would have been parsed as size="1 0 0" and no error would have been thrown. Now throws an error.

  4. Trying to load a NaN via XML like <geom size="1 NaN 4">, while allowed for debugging purposes, will now print a warning.

  5. Fixed null pointer dereference in mj_loadModel.

  6. Fixed memory leaks when loading an invalid model from MJB.

  7. Integer overflows are now avoided when computing mjModel buffer sizes.

  8. Added missing warning string for mjWARN_BADCTRL.

Packaging#

  1. Changed MacOS packaging so that the copy of mujoco.framework embedded in MuJoCo.app can be used to build applications externally.

Version 2.2.0 (May 23, 2022)#

Open Sourcing#

  1. MuJoCo is now fully open-source software. Newly available top level directories are:

    a. src/: All source files. Subdirectories correspond to the modules described in the Programming chapter introduction:

    • src/engine/: Core engine.

    • src/xml/: XML parser.

    • src/user/: Model compiler.

    • src/visualize/: Abstract visualizer.

    • src/ui/: UI framework.

    1. test/: Tests and corresponding asset files.

    2. dist/: Files related to packaging and binary distribution.

  2. Added contributor’s guide and style guide.

General#

  1. Added analytic derivatives of smooth (unconstrained) dynamics forces, with respect to velocities:

    • Centripetal and Coriolis forces computed by the Recursive Newton-Euler algorithm.

    • Damping and fluid-drag passive forces.

    • Actuation forces.

  2. Added implicit integrator. Using the analytic derivatives above, a new implicit-in-velocity integrator was added. This integrator lies between the Euler and Runge Kutta integrators in terms of both stability and computational cost. It is most useful for models which use fluid drag (e.g. for flying or swimming) and for models which use velocity actuators. For more details, see the Numerical Integration section.

  3. Added actlimited and actrange attributes to general actuators, for clamping actuator internal states (activations). This clamping is useful for integrated-velocity actuators, see the Activation clamping section for details.

  4. mjData fields qfrc_unc (unconstrained forces) and qacc_unc (unconstrained accelerations) were renamed qfrc_smooth and qacc_smooth, respectively. While “unconstrained” is precise, “smooth” is more intelligible than “unc”.

  5. Public headers have been moved from /include to /include/mujoco/, in line with the directory layout common in other open source projects. Developers are encouraged to include MuJoCo public headers in their own codebase via #include <mujoco/filename.h>.

  6. The default shadow resolution specified by the shadowsize attribute was increased from 1024 to 4096.

  7. Saved XMLs now use 2-space indents.

Bug fixes#

  1. Antialiasing was disabled for segmentation rendering. Before this change, if the offsamples attribute was greater than 0 (the default value is 4), pixels that overlapped with multiple geoms would receive averaged segmentation IDs, leading to incorrect or non-existent IDs. After this change offsamples is ignored during segmentation rendering.

  2. The value of the enable flag for the experimental multiCCD feature was made sequential with other enable flags. Sequentiality is assumed in the simulate UI and elsewhere.

  3. Fix issue of duplicated meshes when saving models with OBJ meshes using mj_saveLastXML.

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 here.

Bug fixes#

  1. 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.

  2. 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.

  2. 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#

  1. The _nogl dynamic library is no longer provided on Linux and Windows. The switch to GLAD allows us to resolve OpenGL symbols when mjr_makeContext is called rather than when the library is loaded. As a result, the MuJoCo library no longer has an explicit dynamic dependency on OpenGL, and can be used on system where OpenGL is not present.

Simulate#

  1. Fixed a bug in simulate where pressing ‘[’ or ‘]’ when a model is not loaded causes a crash.

  2. Contact frame visualisation was added to the Simulate GUI.

  3. Renamed “set key”, “reset to key” to “save key” and “load key”, respectively.

  4. 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#

  1. mj_resetData zeroes out the solver_nnz field.

  2. 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.

Version 2.1.3 (Mar. 23, 2022)#

General#

  1. simulate now supports cycling through cameras (with the [ and ] keys).

  2. mjVIS_STATIC toggles all static bodies, not just direct children of the world.

Python bindings#

  1. Added a free() method to MjrContext.

  2. Enums now support arithmetic and bitwise operations with numbers.

Bug fixes#

  1. Fixed rendering bug for planes, introduced in 2.1.2. This broke maze environments in dm_control.

Version 2.1.2 (Mar. 15, 2022)#

New modules#

  1. Added new Python bindings, which can be installed via pip install mujoco, and imported as import mujoco.

  2. Added new Unity plug-in.

  3. Added a new introspect module, which provides reflection-like capability for MuJoCo’s public API, currently describing functions and enums. While implemented in Python, this module is expected to be generally useful for automatic code generation targeting multiple languages. (This is not shipped as part of the mujoco Python bindings package.)

API changes#

  1. Moved definition of mjtNum floating point type into a new header mjtnum.h.

  2. Renamed header mujoco_export.h to mjexport.h.

  3. Added mj_printFormattedData, which accepts a format string for floating point numbers, for example to increase precision.

General#

  1. MuJoCo can load OBJ mesh files.

    1. Meshes containing polygons with more than 4 vertices are not supported.

    2. In OBJ files containing multiple object groups, any groups after the first one will be ignored.

    3. Added (post-release, not included in the 2.1.2 archive) textured mug example model:

      _images/mug.png
  2. Added optional frame-of-reference specification to framepos, framequat, framexaxis, frameyaxis, framezaxis, framelinvel, and frameangvel sensors. The frame-of-reference is specified by new reftype and refname attributes.

  3. Sizes of user parameters are now automatically inferred.

    1. Declarations of user parameters in the top-level size clause (e.g. nuser_body, nuser_jnt, etc.) now accept a value of -1, which is the default. This will automatically set the value to the length of the maximum associated user attribute defined in the model.

    2. Setting a value smaller than -1 will lead to a compiler error (previously a segfault).

    3. Setting a value to a length smaller than some user attribute defined in the model will lead to an error (previously additional values were ignored).

  4. Increased the maximum number of lights in an mjvScene from 8 to 100.

  5. Saved XML files only contain explicit inertial elements if the original XML included them. Inertias that were automatically inferred by the compiler’s inertiafromgeom mechanism remain unspecified.

  6. User-selected geoms are always rendered as opaque. This is useful in interactive visualizers.

  7. Static geoms now respect their geom group for visualisation. Until this change rendering of static geoms could only be toggled using the mjVIS_STATIC visualisation flag . After this change, both the geom group and the visualisation flag need to be enabled for the geom to be rendered.

  8. Pointer parameters in function declarations in mujoco.h that are supposed to represent fixed-length arrays are now spelled as arrays with extents, e.g. mjtNum quat[4] rather than mjtNum* quat. From the perspective of C and C++, this is a non-change since array types in function signatures decay to pointer types. However, it allows autogenerated code to be aware of expected input shapes.

  9. Experimental stateless fluid interaction model. As described here, fluid forces use sizes computed from body inertia. While sometimes convenient, this is very rarely a good approximation. In the new model forces act on geoms, rather than bodies, and have a several user-settable parameters. The model is activated by setting a new attribute: <geom fluidshape="ellipsoid"/>. The parameters are described succinctly here, but we leave a full description or the model and its parameters to when this feature leaves experimental status.

Bug fixes#

  1. mj_loadXML and mj_saveLastXML are now locale-independent. The Unity plugin should now work correctly for users whose system locales use commas as decimal separators.

  2. XML assets in VFS no longer need to end in a null character. Instead, the file size is determined by the size parameter of the corresponding VFS entry.

  3. Fix a vertex buffer object memory leak in mjrContext when skins are used.

  4. Camera quaternions are now normalized during XML compilation.

Binary build#

  1. Windows binaries are now built with Clang.

Version 2.1.1 (Dec. 16, 2021)#

API changes#

  1. Added mj_printFormattedModel, which accepts a format string for floating point numbers, for example to increase precision.

  2. Added mj_versionString, which returns human-readable string that represents the version of the MuJoCo binary.

  3. Converted leading underscores to trailing underscores in private instances of API struct definitions, to conform to reserved identifier directive, see C standard: Section 7.1.3.

    Attention

    This is a minor breaking change. Code which references private instances will break. To fix, replace leading underscores with trailing underscores, e.g. _mjModelmjModel_.

General#

  1. Safer string handling: replaced strcat, strcpy, and sprintf with strncat, strncpy, and snprintf respectively.

  2. Changed indentation from 4 spaces to 2 spaces, K&R bracing style, added braces to one-line conditionals.

Bug Fixes#

  1. Fixed reading from uninitialized memory in PGS solver.

  2. Computed capsule inertias are now exact. Until this change, capsule masses and inertias computed by the compiler’s inertiafromgeom mechanism were approximated by a cylinder, formed by the capsule’s cylindrical middle section, extended on both ends by half the capsule radius. Capsule inertias are now computed with the Parallel Axis theorem, applied to the two hemispherical end-caps.

    Attention

    This is a minor breaking change. Simulation of a model with automatically-computed capsule inertias will be numerically different, leading to, for example, breakage of golden-value tests.

  3. Fixed bug related to force and torque sensors. Until this change, forces and torques reported by F/T sensors ignored out-of-tree constraint wrenches except those produced by contacts. Force and torque sensors now correctly take into account the effects of connect and weld constraints.

    Note

    Forces generated by spatial tendons which are outside the kinematic tree (i.e., between bodies which have no ancestral relationship) are still not taken into account by force and torque sensors. This remains a future work item.

Code samples#

  1. testspeed: Added injection of pseudo-random control noise, turned on by default. This is to avoid settling into some fixed contact configuration and providing an unrealistic timing measure.

  2. simulate:

    1. Added slower-than-real-time functionality, which is controlled via the ‘+’ and ‘-’ keys.

    2. Added sliders for injecting Brownian noise into the controls.

    3. Added “Print Camera” button to print an MJCF clause with the pose of the current camera.

    4. The camera pose is not reset when reloading the same model file.

Updated dependencies#

  1. TinyXML was replaced with TinyXML2 6.2.0.

  2. qhull was upgraded to version 8.0.2.

  3. libCCD was upgraded to version 1.4.

  4. On Linux, libstdc++ was replaced with libc++.

Binary build#

  1. MacOS packaging. We now ship Universal binaries that natively support both Apple Silicon and Intel CPUs.

    1. MuJoCo library is now packaged as a Framework Bundle, allowing it to be incorporated more easily into Xcode projects (including Swift projects). Developers are encouraged to compile and link against MuJoCo using the -framework mujoco flag, however all header files and the libmujoco.2.1.1.dylib library can still be directly accessed inside the framework.

    2. Sample applications are now packaged into an Application Bundle called MuJoCo.app. When launched via GUI, the bundle launches the simulate executable. Other precompiled sample programs are shipped inside that bundle (in MuJoCo.app/Contents/MacOS) and can be launched via command line.

    3. Binaries are now signed and the disk image is notarized.

  2. Windows binaries and libraries are now signed.

  3. Link-time optimization is enabled on Linux and macOS, leading to an average of ~20% speedup when benchmarked on three test models (cloth.xml, humanoid.xml, and humanoid100.xml).

  4. Linux binaries are now built with LLVM/Clang instead of GCC.

  5. An AArch64 (aka ARM64) Linux build is also provided.

  6. Private symbols are no longer stripped from shared libraries on Linux and MacOS.

Sample models#

  1. Clean-up of the model/ directory.

    1. Rearranged into subdirectories which include all dependencies.

    2. Added descriptions in XML comments, cleaned up XMLs.

    3. Deleted some composite models: grid1, grid1pin, grid2, softcylinder, softellipsoid.

  2. Added descriptive animations in docs/images/models/ :

humanoid particle

Version 2.1.0 (Oct. 18, 2021)#

New features#

  1. Keyframes now have mocap_pos and mocap_quat fields (mpos and quat attributes in the XML) allowing mocap poses to be stored in keyframes.

  2. New utility functions: mju_insertionSortInt (integer insertion sort) and mju_sigmoid (constructing a sigmoid from two half-quadratics).

General#

  1. The preallocated sizes in the virtual file system (VFS) increased to 2000 and 1000, to allow for larger projects.

  2. The C structs in the mjuiItem union are now named, for compatibility.

  3. Fixed: mjcb_contactfilter type is mjfConFilt (was mjfGeneric).

  4. Fixed: The array of sensors in mjCModel was not cleared.

  5. Cleaned up cross-platform code (internal changes, not visible via the API).

  6. Fixed a bug in parsing of XML texcoord data (related to number of vertices).

  7. Fixed a bug in simulate.cc related to nkey (the number of keyframes).

  8. Accelerated collision detection in the presence of large numbers of non-colliding geoms (with contype==0 and conaffinity==0).

UI#

  1. Figure selection type changed from int to float.

  2. Figures now show data coordinates, when selection and highlight are enabled.

  3. Changed mjMAXUIMULTI to 35, mjMAXUITEXT to 300, mjMAXUIRECT to 25.

  4. Added collapsable sub-sections, implemented as separators with state: mjSEPCLOSED collapsed, mjSEPCLOSED+1 expanded.

  5. Added mjITEM_RADIOLINE item type.

  6. Added function mjui_addToSection to simplify UI section construction.

  7. Added subplot titles to mjvFigure.

Rendering#

  1. render_gl2 guards against non-finite floating point data in the axis range computation.

  2. render_gl2 draws lines from back to front for better visibility.

  3. Added function mjr_label (for text labels).

  4. mjr_render exits immediately if ngeom==0, to avoid errors from uninitialized scenes (e.g. frustrum==0).

  5. Added scissor box in mjr_render, so we don’t clear the entire window at every frame.

License manager#

  1. Removed the entire license manager. The functions mj_activate and mj_deactivate are still there for backward compatibility, but now they do nothing and it is no longer necessary to call them.

  2. Removed the remote license certificate functions mj_certXXX.

Earlier versions#

For changelogs of earlier versions please see roboti.us.