newton.solvers.MuJoCoSolver#
- class newton.solvers.MuJoCoSolver(model, *, mjw_model=None, mjw_data=None, separate_envs_to_worlds=None, nefc_per_env=100, iterations=20, ls_iterations=10, solver='cg', integrator='euler', use_mujoco=False, disable_contacts=False, register_collision_groups=True, default_actuator_gear=None, actuator_gears=None, update_data_every=1, save_to_mjcf=None)#
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.MuJoCoSolver(model) # simulation loop for i in range(100): solver.step(model, state_in, state_out, control, contacts, dt)
Methods
__init__
(model, *[, mjw_model, mjw_data, ...])convert_to_mjc
(model[, state, ...])Convert a Newton model and state to MuJoCo (Warp) model and data.
integrate_bodies
(model, state_in, state_out, dt)Integrate the rigid bodies of the model.
integrate_particles
(model, state_in, ...)Integrate the particles of the model.
step
(model, state_in, state_out, control, ...)Simulate the model for a given time step using the given control input.
Attributes
Get the device used by the solver.
- __init__(model, *, mjw_model=None, mjw_data=None, separate_envs_to_worlds=None, nefc_per_env=100, iterations=20, ls_iterations=10, solver='cg', integrator='euler', use_mujoco=False, disable_contacts=False, register_collision_groups=True, default_actuator_gear=None, actuator_gears=None, update_data_every=1, save_to_mjcf=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.
nefc_per_env (int) – Number of constraints per environment (world).
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.
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_every (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.
- step(model, state_in, state_out, control, contacts, dt)#
Simulate the model for a given time step using the given control input.
- notify_model_changed(flags)#
Notify the solver that parts of the
Model
were modified.The flags argument is a bit-mask composed of the
NOTIFY_FLAG_*
constants defined innewton.core.types
. Each flag represents a category of model data that may have been updated after the solver was created. Passing the appropriate combination of flags enables a solver implementation to refresh its internal buffers without having to recreate the whole solver object. Valid flags are:Constant
Description
NOTIFY_FLAG_JOINT_PROPERTIES
Joint transforms or coordinates have changed.
NOTIFY_FLAG_JOINT_AXIS_PROPERTIES
Joint axis limits, targets, or modes have changed.
NOTIFY_FLAG_DOF_PROPERTIES
Joint DOF state or force buffers have changed.
NOTIFY_FLAG_BODY_PROPERTIES
Rigid-body pose or velocity buffers have changed.
NOTIFY_FLAG_BODY_INERTIAL_PROPERTIES
Rigid-body mass or inertia tensors have changed.
NOTIFY_FLAG_SHAPE_PROPERTIES
Shape transforms or geometry have changed.
- Parameters:
flags (int) – Bit-mask of model-update flags indicating which model properties changed.
- property device: Device#
Get the device used by the solver.
- Returns:
The device used by the solver.
- Return type:
wp.Device
- integrate_bodies(model, state_in, state_out, dt, angular_damping=0.0)#
Integrate the rigid bodies of the model.
- integrate_particles(model, state_in, state_out, dt)#
Integrate the particles of the model.
- convert_to_mjc(model, state=None, *, separate_envs_to_worlds=True, iterations=20, ls_iterations=10, nefc_per_env=100, solver='cg', integrator='euler', disableflags=0, impratio=1.0, tolerance=1e-8, ls_tolerance=0.01, timestep=0.01, cone=0, register_collision_groups=True, joint_limit_threshold=1e3, geom_solref=(0.02, 1.0), geom_solimp=(0.9, 0.95, 0.001, 0.5, 2.0), geom_friction=(1.0, 0.05, 0.05), 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=True)#
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]