newton.solvers.SolverMuJoCo#

class newton.solvers.SolverMuJoCo(model, *, mjw_model=None, mjw_data=None, separate_envs_to_worlds=None, njmax=None, ncon_per_env=None, iterations=20, ls_iterations=10, solver='cg', integrator='euler', cone='pyramidal', impratio=1.0, use_mujoco_cpu=False, disable_contacts=False, default_actuator_gear=None, actuator_gears=None, update_data_interval=1, save_to_mjcf=None, contact_stiffness_time_const=0.02, ls_parallel=False, use_mujoco_contacts=True, joint_solref_limit=None, joint_solimp_limit=None)[source]#

Bases: SolverBase

This solver provides an interface to simulate physics using the MuJoCo physics engine, optimized with GPU acceleration through mujoco_warp. It supports both MuJoCo and mujoco_warp backends, enabling efficient simulation of articulated systems with contacts and constraints.

Note

  • This solver requires mujoco_warp and its dependencies to be installed.

  • For installation instructions, see the mujoco_warp repository.

Example

solver = newton.solvers.SolverMuJoCo(model)

# simulation loop
for i in range(100):
    solver.step(state_in, state_out, control, contacts, dt)
    state_in, state_out = state_out, state_in

Debugging#

To debug the SolverMuJoCo, you can save the MuJoCo model that is created from the newton.Model in the constructor of the SolverMuJoCo:

solver = newton.solvers.SolverMuJoCo(model, save_to_mjcf="model.xml")

This will save the MuJoCo model as an MJCF file, which can be opened in the MuJoCo simulator.

It is also possible to visualize the simulation running in the SolverMuJoCo through MuJoCo’s own viewer. This may help to debug the simulation and see how the MuJoCo model looks like when it is created from the Newton model.

import newton

solver = newton.solvers.SolverMuJoCo(model)

for _ in range(num_frames):
    # step the solver
    solver.step(state_in, state_out, control, contacts, dt)
    state_in, state_out = state_out, state_in

    solver.render_mujoco_viewer()
classmethod import_mujoco()#

Import the MuJoCo Warp dependencies and cache them as class variables.

static color_collision_shapes(model, selected_shapes, visualize_graph=False, shape_keys=None)#

Find a graph coloring of the collision filter pairs in the model. Shapes within the same color cannot collide with each other. Shapes can only collide with shapes of different colors.

Parameters:
  • model (Model) – The model to color the collision shapes of.

  • selected_shapes (nparray) – The indices of the collision shapes to color.

  • visualize_graph (bool) – Whether to visualize the graph coloring.

  • shape_keys (list[str]) – The keys of the shapes, only used for visualization.

Returns:

An integer array of shape (num_shapes,), where each element is the color of the corresponding shape.

Return type:

nparray

static find_body_collision_filter_pairs(model, selected_bodies, colliding_shapes)#

For shape collision filter pairs, find body collision filter pairs that are contained within.

__init__(model, *, mjw_model=None, mjw_data=None, separate_envs_to_worlds=None, njmax=None, ncon_per_env=None, iterations=20, ls_iterations=10, solver='cg', integrator='euler', cone='pyramidal', impratio=1.0, use_mujoco_cpu=False, disable_contacts=False, default_actuator_gear=None, actuator_gears=None, update_data_interval=1, save_to_mjcf=None, contact_stiffness_time_const=0.02, ls_parallel=False, use_mujoco_contacts=True, joint_solref_limit=None, joint_solimp_limit=None)#
Parameters:
  • model (Model) – the model to be simulated.

  • mjw_model (MjWarpModel | None) – Optional pre-existing MuJoCo Warp model. If provided with mjw_data, conversion from Newton model is skipped.

  • mjw_data (MjWarpData | None) – Optional pre-existing MuJoCo Warp data. If provided with mjw_model, conversion from Newton model is skipped.

  • separate_envs_to_worlds (bool | None) – If True, each Newton environment is mapped to a separate MuJoCo world. Defaults to not use_mujoco_cpu.

  • njmax (int) – Maximum number of constraints per environment (world). If None, a default value is estimated from the initial state. Note that the larger of the user-provided value or the default value is used.

  • ncon_per_env (int | None) – Number of contact points per environment (world). If None, a default value is estimated from the initial state. Note that the larger of the user-provided value or the default value is used.

  • iterations (int) – Number of solver iterations.

  • ls_iterations (int) – Number of line search iterations for the solver.

  • solver (int | str) – Solver type. Can be “cg” or “newton”, or their corresponding MuJoCo integer constants.

  • integrator (int | str) – Integrator type. Can be “euler”, “rk4”, or “implicit”, or their corresponding MuJoCo integer constants.

  • cone (int | str) – The type of contact friction cone. Can be “pyramidal”, “elliptic”, or their corresponding MuJoCo integer constants.

  • impratio (float) – Frictional-to-normal constraint impedance ratio.

  • use_mujoco_cpu (bool) – If True, use the MuJoCo-C CPU backend instead of mujoco_warp.

  • disable_contacts (bool) – If True, disable contact computation in MuJoCo.

  • register_collision_groups (bool) – If True, register collision groups from the Newton model in MuJoCo.

  • default_actuator_gear (float | None) – Default gear ratio for all actuators. Can be overridden by actuator_gears.

  • actuator_gears (dict[str, float] | None) – Dictionary mapping joint names to specific gear ratios, overriding the default_actuator_gear.

  • update_data_interval (int) – Frequency (in simulation steps) at which to update the MuJoCo Data object from the Newton state. If 0, Data is never updated after initialization.

  • save_to_mjcf (str | None) – Optional path to save the generated MJCF model file.

  • contact_stiffness_time_const (float) – Time constant for contact stiffness in MuJoCo’s solver reference model. Defaults to 0.02 (20ms). Can be set to match the simulation timestep for tighter coupling.

  • ls_parallel (bool) – If True, enable parallel line search in MuJoCo. Defaults to False.

  • use_mujoco_contacts (bool) – If True, use the MuJoCo contact solver. If False, use the Newton contact solver (newton contacts must be passed in through the step function in that case).

  • joint_solref_limit (tuple[float, float] | None) – Global solver reference parameters for all joint limits. If provided, applies these solref values to all joints created. Defaults to None (uses MuJoCo defaults).

  • joint_solimp_limit (tuple[float, float, float, float, float] | None) – Global solver impedance parameters for all joint limits. If provided, applies these solimp values to all joints created. Defaults to None (uses MuJoCo defaults).

close_mujoco_viewer()#

Close the MuJoCo viewer if it exists.

convert_to_mjc(model, state=None, *, separate_envs_to_worlds=True, iterations=20, ls_iterations=10, njmax=None, ncon_per_env=None, solver='cg', integrator='euler', disableflags=0, disable_contacts=False, impratio=1.0, tolerance=1e-8, ls_tolerance=0.01, timestep=0.01, cone='pyramidal', joint_limit_threshold=1e3, geom_solref=None, geom_solimp=(0.9, 0.95, 0.001, 0.5, 2.0), geom_friction=None, geom_condim=3, target_filename=None, default_actuator_args=None, default_actuator_gear=None, actuator_gears=None, actuated_axes=None, skip_visual_only_geoms=True, add_axes=False, mesh_maxhullvert=MESH_MAXHULLVERT, ls_parallel=False)#

Convert a Newton model and state to MuJoCo (Warp) model and data.

Parameters:
Returns:

A tuple containing the model and data objects for mujoco_warp and MuJoCo.

Return type:

tuple[MjWarpModel, MjWarpData, MjModel, MjData]

notify_model_changed(flags)#
render_mujoco_viewer(show_left_ui=True, show_right_ui=True, show_contact_points=True, show_contact_forces=False, show_transparent_geoms=True)#

Create and synchronize the MuJoCo viewer. The viewer will be created if it is not already open.

Note

The MuJoCo viewer only supports rendering Newton models with a single environment, unless use_mujoco_cpu is True or the solver was initialized with separate_envs_to_worlds set to False.

The MuJoCo viewer is only meant as a debugging tool.

Parameters:
  • show_left_ui (bool) – Whether to show the left UI.

  • show_right_ui (bool) – Whether to show the right UI.

  • show_contact_points (bool) – Whether to show contact points.

  • show_contact_forces (bool) – Whether to show contact forces.

  • show_transparent_geoms (bool) – Whether to show transparent geoms.

step(state_in, state_out, control, contacts, dt)#
update_contacts(contacts)#
update_geom_properties()#

Update geom properties including collision radius, friction, and contact parameters in the MuJoCo model.

update_joint_dof_properties()#

Update all joint dof properties including effort limits, velocity limits, friction, and armature in the MuJoCo model.

update_joint_properties()#

Update joint properties including joint positions, joint axes, and relative body transforms in the MuJoCo model.

update_model_properties()#

Update model properties including gravity in the MuJoCo model.

joint_mjc_dof_start: wp.array(dtype=wp.int32) | None#

Mapping from Newton joint index to the start index of its joint axes in MuJoCo. Only defined for the joint indices of the first environment in Newton, defaults to -1 otherwise. Shape [joint_count], dtype int32.

mjc_axis_to_actuator: wp.array(dtype=int) | None#

Mapping from Newton joint axis index to MJC actuator index. Shape [dof_count], dtype int32.

selected_bodies: wp.array(dtype=int) | None#

Indices of Newton bodies that are used in the MuJoCo model for the first environment as a basis for replicating the nworlds environments in MuJoCo Warp.

selected_joints: wp.array(dtype=int) | None#

Indices of Newton joints that are used in the MuJoCo model for the first environment as a basis for replicating the nworlds environments in MuJoCo Warp.

selected_shapes: wp.array(dtype=int) | None#

Indices of Newton shapes that are used in the MuJoCo model (includes non-instantiated visual-only shapes) for the first environment as a basis for replicating the nworlds environments in MuJoCo Warp.

shape_incoming_xform: wp.array(dtype=wp.transform) | None#

The transform applied to Newton’s shape frame to match MuJoCo’s geom frame. This only affects mesh shapes (MuJoCo aligns them with their inertial frames). Shape [shape_count], dtype transform.

to_mjc_body_index: wp.array(dtype=int) | None#

Mapping from MuJoCo body index to Newton body index (skip world body index -1). Shape [bodies_per_env], dtype int32.

to_mjc_geom_index: wp.array(dtype=wp.vec2i) | None#

Mapping from Newton shape index to MuJoCo [worldid, geom index].

to_newton_shape_index: wp.array(dtype=int, ndim=2) | None#

Mapping from MuJoCo [worldid, geom index] to Newton shape index. This is used to map MuJoCo geoms to Newton shapes.