newton.solvers.MuJoCoSolver#
- class newton.solvers.MuJoCoSolver(model, *, mjw_model=None, mjw_data=None, separate_envs_to_worlds=None, nefc_per_env=100, ncon_per_env=None, iterations=20, ls_iterations=10, solver='cg', integrator='euler', cone='pyramidal', impratio=1.0, use_mujoco=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)[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.MuJoCoSolver(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 MuJoCoSolver, you can save the MuJoCo model that is created from the
newton.Model
in the constructor of the MuJoCoSolver:solver = newton.solvers.MuJoCoSolver(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 MuJoCoSolver 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 mujoco import mujoco.viewer import mujoco_warp solver = newton.solvers.MuJoCoSolver(model) mjm, mjd = solver.mj_model, solver.mj_data m, d = solver.mjw_model, solver.mjw_data viewer = mujoco.viewer.launch_passive(mjm, mjd) 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 if not solver.use_mujoco: mujoco_warp.get_data_into(mjd, mjm, d) viewer.sync()
- static color_collision_shapes(model, selected_shapes, visualize_graph=False)#
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.
- __init__(model, *, mjw_model=None, mjw_data=None, separate_envs_to_worlds=None, nefc_per_env=100, ncon_per_env=None, iterations=20, ls_iterations=10, solver='cg', integrator='euler', cone='pyramidal', impratio=1.0, use_mujoco=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)#
- 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.
nefc_per_env (int) – Number of constraints per environment (world).
ncon_per_env (int | None) – Number of contact points per environment (world). If None, the number of contact points is estimated from the model.
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 (bool) – If True, use the pure MuJoCo 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).
- convert_to_mjc(model, state=None, *, separate_envs_to_worlds=True, iterations=20, ls_iterations=10, nefc_per_env=100, 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, maxhullvert=MESH_MAXHULLVERT, ls_parallel=False)#
Convert a Newton model and state to MuJoCo (Warp) model and data.
- Parameters:
Model (newton.Model) – The Newton model to convert.
State (newton.State) – The Newton state to convert.
- 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)#
- step(state_in, state_out, control, contacts, dt)#
- update_geom_properties()#
Update geom properties including collision radius, friction, and contact parameters in the MuJoCo model.
- update_joint_properties()#
Update all joint properties including effort limits, velocity limits, friction, and armature in the MuJoCo model.