newton.solvers.SolverMuJoCo#
- class newton.solvers.SolverMuJoCo(model, *, mjw_model=None, mjw_data=None, separate_worlds=None, njmax=None, nconmax=None, iterations=20, ls_iterations=10, solver='cg', integrator='implicitfast', 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, ls_parallel=False, use_mujoco_contacts=True, tolerance=1e-6, ls_tolerance=0.01, include_sites=True)[source]#
Bases:
SolverBaseThis 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.Modelin 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.
- classmethod register_custom_attributes(builder)#
Declare custom attributes to be allocated on the Model object within the
mujoconamespace. Note that we declare all custom attributes with thenewton.ModelBuilder.CustomAttribute.usd_attribute_nameset to"mjc"here to leverage the MuJoCo USD schema where attributes are named"mjc:attr"rather than"newton:mujoco:attr".
- 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:
- 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_worlds=None, njmax=None, nconmax=None, iterations=20, ls_iterations=10, solver='cg', integrator='implicitfast', 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, ls_parallel=False, use_mujoco_contacts=True, tolerance=1e-6, ls_tolerance=0.01, include_sites=True)#
- 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_worlds (bool | None) – If True, each Newton world is mapped to a separate MuJoCo world. Defaults to not use_mujoco_cpu.
njmax (int) – Maximum number of constraints per 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.
nconmax (int | None) – Number of contact points per 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 “implicitfast”, 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.
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).
tolerance (float | None) – Solver tolerance for early termination of the iterative solver. Defaults to 1e-6 and will be increased to 1e-6 by the MuJoCo solver if a smaller value is provided.
ls_tolerance (float | None) – Solver tolerance for early termination of the line search. Defaults to 0.01.
include_sites (bool) – If
True(default), Newton shapes marked withShapeFlags.SITEare exported as MuJoCo sites. Sites are non-colliding reference points used for sensor attachment, debugging, or as frames of reference. IfFalse, sites are skipped during export. Defaults toTrue.
- close_mujoco_viewer()#
Close the MuJoCo viewer if it exists.
- 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 world, unless
use_mujoco_cpuisTrueor the solver was initialized withseparate_worldsset toFalse.The MuJoCo viewer is only meant as a debugging tool.
- Parameters:
- step(state_in, state_out, control, contacts, dt)#
- update_contacts(contacts)#
- update_eq_properties()#
Update equality constraint properties including solref in the MuJoCo model.
- 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, friction, armature, solimplimit, solref, passive stiffness and damping, and joint limit ranges 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.
- mjc_actuator_to_newton_axis: wp.array(dtype=wp.int32, ndim=2) | None#
Maps MuJoCo[world, actuator] -> Newton axis (DOF) index with actuator type encoded in sign.
Encoding: - Positive value: position actuator, newton_axis = value - Negative value (not -1): velocity actuator, newton_axis = -(value + 2) - Value of -1: unmapped actuator
Shape [nworld, nu], dtype int32.
- mjc_body_to_newton: wp.array(dtype=wp.int32, ndim=2) | None#
Mapping from MuJoCo [world, body] to Newton body index. Shape [nworld, nbody], dtype int32.
- mjc_dof_to_newton_dof: wp.array(dtype=wp.int32, ndim=2) | None#
Mapping from MuJoCo [world, dof] to Newton DOF index. Shape [nworld, nv], dtype int32.
- mjc_geom_to_newton_shape: wp.array(dtype=wp.int32, ndim=2) | None#
Mapping from MuJoCo [world, geom] to Newton shape index. Shape [nworld, ngeom], dtype int32.
- mjc_jnt_to_newton_dof: wp.array(dtype=wp.int32, ndim=2) | None#
Mapping from MuJoCo [world, joint] to Newton DOF index. Shape [nworld, njnt], dtype int32.
- mjc_jnt_to_newton_jnt: wp.array(dtype=wp.int32, ndim=2) | None#
Mapping from MuJoCo [world, joint] to Newton joint index. Shape [nworld, njnt], dtype int32.