newton.solvers.SolverMuJoCo#
- class newton.solvers.SolverMuJoCo(model, *, mjw_model=None, mjw_data=None, separate_worlds=None, njmax=None, nconmax=None, iterations=None, ls_iterations=None, ccd_iterations=None, sdf_iterations=None, sdf_initpoints=None, solver=None, integrator=None, cone=None, jacobian=None, impratio=None, tolerance=None, ls_tolerance=None, ccd_tolerance=None, density=None, viscosity=None, wind=None, magnetic=None, 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, 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.
shape_collision_radiusfrom Newton models is not used by MuJoCo. Instead, MuJoCo computes bounding sphere radii (geom_rbound) internally based on the geometry definition.
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()
- class CtrlSource(value)#
Bases:
IntEnumControl source for MuJoCo actuators.
Determines where an actuator gets its control input from:
JOINT_TARGET: Maps from Newton’sjoint_target_pos/joint_target_velarraysCTRL_DIRECT: Usescontrol.mujoco.ctrldirectly (for MuJoCo-native control)
- CTRL_DIRECT = 1#
- JOINT_TARGET = 0#
- class CtrlType(value)#
Bases:
IntEnumControl type for MuJoCo actuators.
For
JOINT_TARGETmode, determines which target array to read from:POSITION: Maps fromjoint_target_pos, syncs gains fromjoint_target_ke. ForPOSITION-only actuators, also syncs damping fromjoint_target_kd. ForPOSITION_VELOCITYmode, kd is handled by the separate velocity actuator.VELOCITY: Maps fromjoint_target_vel, syncs gains fromjoint_target_kdGENERAL: Used withCTRL_DIRECTmode for motor/general actuators
- GENERAL = 2#
- POSITION = 0#
- VELOCITY = 1#
- 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=None, ls_iterations=None, ccd_iterations=None, sdf_iterations=None, sdf_initpoints=None, solver=None, integrator=None, cone=None, jacobian=None, impratio=None, tolerance=None, ls_tolerance=None, ccd_tolerance=None, density=None, viscosity=None, wind=None, magnetic=None, 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, include_sites=True)#
Solver options (e.g.,
impratio) follow this resolution priority:Constructor argument - If provided, same value is used for all worlds.
Newton model custom attribute (
model.mujoco.<option>) - Supports per-world values.MuJoCo default - Used if neither of the above is set.
- 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 | None) – 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 | None) – Number of solver iterations. If None, uses model custom attribute or MuJoCo’s default (100).
ls_iterations (int | None) – Number of line search iterations for the solver. If None, uses model custom attribute or MuJoCo’s default (50).
ccd_iterations (int | None) – Maximum CCD iterations. If None, uses model custom attribute or MuJoCo’s default (50).
sdf_iterations (int | None) – Maximum SDF iterations. If None, uses model custom attribute or MuJoCo’s default (10).
sdf_initpoints (int | None) – Number of SDF initialization points. If None, uses model custom attribute or MuJoCo’s default (40).
solver (int | str) – Solver type. Can be “cg” or “newton”, or their corresponding MuJoCo integer constants. If None, uses model custom attribute or Newton’s default (“newton”).
integrator (int | str) – Integrator type. Can be “euler”, “rk4”, or “implicitfast”, or their corresponding MuJoCo integer constants. If None, uses model custom attribute or Newton’s default (“implicitfast”).
cone (int | str) – The type of contact friction cone. Can be “pyramidal”, “elliptic”, or their corresponding MuJoCo integer constants. If None, uses model custom attribute or Newton’s default (“pyramidal”).
jacobian (int | str | None) – Jacobian computation method. Can be “dense”, “sparse”, or “auto”, or their corresponding MuJoCo integer constants. If None, uses model custom attribute or MuJoCo’s default (“auto”).
impratio (float | None) – Frictional-to-normal constraint impedance ratio. If None, uses model custom attribute or MuJoCo’s default (1.0).
tolerance (float | None) – Solver tolerance for early termination. If None, uses model custom attribute or MuJoCo’s default (1e-8).
ls_tolerance (float | None) – Line search tolerance for early termination. If None, uses model custom attribute or MuJoCo’s default (0.01).
ccd_tolerance (float | None) – Continuous collision detection tolerance. If None, uses model custom attribute or MuJoCo’s default (1e-6).
density (float | None) – Medium density for lift and drag forces. If None, uses model custom attribute or MuJoCo’s default (0.0).
viscosity (float | None) – Medium viscosity for lift and drag forces. If None, uses model custom attribute or MuJoCo’s default (0.0).
wind (tuple | None) – Wind velocity vector (x, y, z) for lift and drag forces. If None, uses model custom attribute or MuJoCo’s default (0, 0, 0).
magnetic (tuple | None) – Global magnetic flux vector (x, y, z). If None, uses model custom attribute or MuJoCo’s default (0, -0.5, 0).
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).
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.
- enable_rne_postconstraint(state_out)#
Request computation of RNE forces if required for state fields.
- get_max_contact_count()#
Return the maximum number of rigid contacts that can be generated by MuJoCo.
- 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_actuator_properties()#
Update CTRL_DIRECT actuator properties (gainprm, biasprm) in the MuJoCo model.
Only updates actuators that use CTRL_DIRECT mode. JOINT_TARGET actuators are updated via update_joint_dof_properties() using joint_target_ke/kd.
- update_contacts(contacts, state=None)#
Update contacts from MuJoCo contacts when running with
use_mujoco_contacts.
- update_eq_properties()#
Update equality constraint properties in the MuJoCo model.
Updates:
eq_solref/eq_solimp from MuJoCo custom attributes (if set)
eq_data from Newton’s equality_constraint_anchor, equality_constraint_relpose, equality_constraint_polycoef, equality_constraint_torquescale
eq_active from Newton’s equality_constraint_enabled
Note
Note this update only affects the equality constraints explicitly defined in Newton, not the equality constraints defined for joints that are excluded from articulations (i.e. joints that have joint_articulation == -1, for example loop-closing joints). Equality constraints for these joints are defined after the regular equality constraints 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.
- update_pair_properties()#
Update MuJoCo contact pair properties from Newton custom attributes.
Updates the randomizable pair properties (solref, solreffriction, solimp, margin, gap, friction) for explicit contact pairs defined in the model.
- update_tendon_properties()#
Update fixed tendon properties in the MuJoCo model.
Updates tendon stiffness, damping, frictionloss, range, margin, solref, solimp, armature, and actfrcrange from Newton custom attributes.
- body_free_qd_start: wp.array(dtype=wp.int32) | None#
Per-body mapping to the free-joint qd_start index (or -1 if not free).
- mjc_actuator_ctrl_source: wp.array(dtype=wp.int32) | None#
Control source for each MuJoCo actuator.
Values: 0=JOINT_TARGET (uses joint_target_pos/vel), 1=CTRL_DIRECT (uses mujoco.ctrl) Shape [nu], dtype int32.
- mjc_actuator_to_newton_idx: wp.array(dtype=wp.int32) | None#
Mapping from MuJoCo actuator to Newton index.
For JOINT_TARGET: sign-encoded DOF index (>=0: position, -1: unmapped, <=-2: velocity with -(idx+2)) For CTRL_DIRECT: MJCF-order index into control.mujoco.ctrl array
Shape [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_eq_to_newton_eq: wp.array(dtype=wp.int32, ndim=2) | None#
Mapping from MuJoCo [world, eq] to Newton equality constraint index.
Corresponds to the equality constraints that are created in MuJoCo from Newton’s equality constraints. A value of -1 indicates that the MuJoCo equality constraint has been created from a Newton joint, see
mjc_eq_to_newton_jntfor the corresponding joint index.Shape [nworld, neq], dtype int32.
- mjc_eq_to_newton_jnt: wp.array(dtype=wp.int32, ndim=2) | None#
Mapping from MuJoCo [world, eq] to Newton joint index.
Corresponds to the equality constraints that are created in MuJoCo from Newton joints that have no associated articulation, i.e. where
newton.Model.joint_articulationis -1 for the joint which results in 2 equality constraints being created in MuJoCo. A value of -1 indicates that the MuJoCo equality constraint is not associated with a Newton joint but an explicitly created Newton equality constraint, seemjc_eq_to_newton_eqfor the corresponding equality constraint index.Shape [nworld, neq], 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.
- mjc_mocap_to_newton_jnt: wp.array(dtype=wp.int32, ndim=2) | None#
Mapping from MuJoCo [world, mocap] to Newton joint index. Shape [nworld, nmocap], dtype int32.