Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
26 commits
Select commit Hold shift + click to select a range
678d66e
changes for attributefrequency.WORLD
adenzler-nvidia Dec 5, 2025
d8876d3
initial solverMuJoCo
adenzler-nvidia Dec 5, 2025
aecba1b
mjcf and USD import
adenzler-nvidia Dec 5, 2025
77fb71c
some early versions of tests
adenzler-nvidia Dec 5, 2025
c0a0a84
add custom attributes to the model
adenzler-nvidia Dec 5, 2025
3eefc67
add more tests, move to new class.
adenzler-nvidia Dec 5, 2025
d0950c4
better solverMuJoCo
adenzler-nvidia Dec 5, 2025
96fd15d
add more expandable options
adenzler-nvidia Dec 5, 2025
4949342
remove unnecessary name
adenzler-nvidia Dec 5, 2025
215861b
Merge branch 'main' into dev/adenzler/option-custom-attribute
adenzler-nvidia Dec 8, 2025
7de0ec8
merge
adenzler-nvidia Dec 11, 2025
ac634a2
Merge branch 'main' into dev/adenzler/option-custom-attribute
adenzler-nvidia Dec 17, 2025
1fbff89
add flag to avoid parsing options if wanted
adenzler-nvidia Dec 17, 2025
32e934b
make _update_solver_options private
adenzler-nvidia Dec 17, 2025
5ddc2d3
guard MJC import as well
adenzler-nvidia Dec 17, 2025
45005e2
coderabbit suggestions
adenzler-nvidia Dec 17, 2025
f17e568
change to invsqrt version
adenzler-nvidia Dec 17, 2025
1ec7f74
update tests
adenzler-nvidia Dec 17, 2025
1f68ab8
this keeps on giving
adenzler-nvidia Dec 17, 2025
32d68c1
this should be it
adenzler-nvidia Dec 17, 2025
ff87480
Merge branch 'main' into dev/adenzler/option-custom-attribute
adenzler-nvidia Dec 17, 2025
61ef331
Merge branch 'main' into dev/adenzler/option-custom-attribute
adenzler-nvidia Dec 18, 2025
63534cf
Merge branch 'main' into dev/adenzler/option-custom-attribute
adenzler-nvidia Jan 7, 2026
0ef28e0
Merge branch 'main' into dev/adenzler/option-custom-attribute
adenzler-nvidia Jan 12, 2026
1cbe491
documentation
adenzler-nvidia Jan 12, 2026
c3c61de
specify device
adenzler-nvidia Jan 12, 2026
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 6 additions & 0 deletions newton/_src/sim/builder.py
Original file line number Diff line number Diff line change
Expand Up @@ -1421,6 +1421,7 @@ def add_usd(
load_sites: bool = True,
load_visual_shapes: bool = True,
hide_collision_shapes: bool = False,
parse_mujoco_options: bool = True,
mesh_maxhullvert: int = MESH_MAXHULLVERT,
schema_resolvers: list[SchemaResolver] | None = None,
) -> dict[str, Any]:
Expand Down Expand Up @@ -1450,6 +1451,7 @@ def add_usd(
load_sites (bool): If True, sites (prims with MjcSiteAPI) are loaded as non-colliding reference points. If False, sites are ignored. Default is True.
load_visual_shapes (bool): If True, non-physics visual geometry is loaded. If False, visual-only shapes are ignored (sites are still controlled by ``load_sites``). Default is True.
hide_collision_shapes (bool): If True, collision shapes are hidden. Default is False.
parse_mujoco_options (bool): Whether MuJoCo solver options from the PhysicsScene should be parsed. If False, solver options are not loaded and custom attributes retain their default values. Default is True.
mesh_maxhullvert (int): Maximum vertices for convex hull approximation of meshes.
schema_resolvers (list[SchemaResolver]): Resolver instances in priority order. Default is no schema resolution.
Schema resolvers collect per-prim "solver-specific" attributes, see :ref:`schema_resolvers` for more information.
Expand Down Expand Up @@ -1521,6 +1523,7 @@ def add_usd(
load_sites,
load_visual_shapes,
hide_collision_shapes,
parse_mujoco_options,
mesh_maxhullvert,
schema_resolvers,
)
Expand All @@ -1538,6 +1541,7 @@ def add_mjcf(
parse_meshes: bool = True,
parse_sites: bool = True,
parse_visuals: bool = True,
parse_mujoco_options: bool = True,
up_axis: AxisType = Axis.Z,
ignore_names: Sequence[str] = (),
ignore_classes: Sequence[str] = (),
Expand Down Expand Up @@ -1570,6 +1574,7 @@ def add_mjcf(
parse_meshes (bool): Whether geometries of type `"mesh"` should be parsed. If False, geometries of type `"mesh"` are ignored.
parse_sites (bool): Whether sites (non-colliding reference points) should be parsed. If False, sites are ignored.
parse_visuals (bool): Whether visual geometries (non-collision shapes) should be loaded. If False, visual shapes are not loaded (different from `hide_visuals` which loads but hides them). Default is True.
parse_mujoco_options (bool): Whether solver options from the MJCF `<option>` tag should be parsed. If False, solver options are not loaded and custom attributes retain their default values. Default is True.
up_axis (AxisType): The up axis of the MuJoCo scene. The default is Z up.
ignore_names (Sequence[str]): A list of regular expressions. Bodies and joints with a name matching one of the regular expressions will be ignored.
ignore_classes (Sequence[str]): A list of regular expressions. Bodies and joints with a class matching one of the regular expressions will be ignored.
Expand Down Expand Up @@ -1602,6 +1607,7 @@ def add_mjcf(
parse_meshes,
parse_sites,
parse_visuals,
parse_mujoco_options,
up_axis,
ignore_names,
ignore_classes,
Expand Down
20 changes: 20 additions & 0 deletions newton/_src/solvers/mujoco/kernels.py
Original file line number Diff line number Diff line change
Expand Up @@ -969,6 +969,26 @@ def repeat_array_kernel(
dst[tid] = src[src_idx]


@wp.kernel
def update_solver_options_kernel(
newton_impratio: wp.array(dtype=float),
# outputs
opt_impratio_invsqrt: wp.array(dtype=float),
):
"""Update per-world solver options from Newton model.

Args:
newton_impratio: Per-world impratio values from Newton model (None if overridden)
opt_impratio_invsqrt: MuJoCo Warp opt.impratio_invsqrt array to update (shape: nworld)
"""
worldid = wp.tid()

# Only update if Newton array exists (None means overridden or not available)
if newton_impratio:
# MuJoCo stores impratio as inverse square root
opt_impratio_invsqrt[worldid] = 1.0 / wp.sqrt(newton_impratio[worldid])


@wp.kernel
def update_axis_properties_kernel(
mjc_actuator_to_newton_axis: wp.array2d(dtype=wp.int32),
Expand Down
126 changes: 119 additions & 7 deletions newton/_src/solvers/mujoco/solver_mujoco.py
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,7 @@
update_mocap_transforms_kernel,
update_model_properties_kernel,
update_shape_mappings_kernel,
update_solver_options_kernel,
)

if TYPE_CHECKING:
Expand Down Expand Up @@ -329,6 +330,18 @@ def register_custom_attributes(cls, builder: ModelBuilder) -> None:
mjcf_attribute_name="solref",
)
)
# Solver options (frequency WORLD for per-world values)
builder.add_custom_attribute(
ModelBuilder.CustomAttribute(
name="impratio",
frequency=ModelAttributeFrequency.WORLD,
assignment=ModelAttributeAssignment.MODEL,
dtype=wp.float32,
default=1.0,
namespace="mujoco",
usd_attribute_name="mjc:option:impratio",
)
)

# --- Pair attributes (from MJCF <pair> tag) ---
# Explicit contact pairs with custom properties. Only pairs from the template world are used.
Expand Down Expand Up @@ -536,7 +549,7 @@ def __init__(
solver: int | str = "cg",
integrator: int | str = "implicitfast",
cone: int | str = "pyramidal",
impratio: float = 1.0,
impratio: float | None = None,
use_mujoco_cpu: bool = False,
disable_contacts: bool = False,
default_actuator_gear: float | None = None,
Expand All @@ -550,6 +563,12 @@ def __init__(
include_sites: bool = True,
):
"""
Solver options (e.g., ``impratio``) follow this resolution priority:

1. **Constructor argument** - If provided, same value is used for all worlds.
2. **Newton model custom attribute** (``model.mujoco.<option>``) - Supports per-world values.
3. **MuJoCo default** - Used if neither of the above is set.

Args:
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.
Expand All @@ -562,7 +581,7 @@ def __init__(
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.
impratio (float | None): Frictional-to-normal constraint impedance ratio. Defaults to MuJoCo's default (1.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.
Expand Down Expand Up @@ -1191,7 +1210,7 @@ def _convert_to_mjc(
integrator: int | str = "implicitfast",
disableflags: int = 0,
disable_contacts: bool = False,
impratio: float = 1.0,
impratio: float | None = None,
tolerance: float = 1e-6,
ls_tolerance: float = 0.01,
cone: int | str = "pyramidal",
Expand All @@ -1208,12 +1227,41 @@ def _convert_to_mjc(
"""
Convert a Newton model and state to MuJoCo (Warp) model and data.

Solver options (e.g., ``impratio``) follow this resolution priority:

1. **Constructor argument** - If provided, same value is used for all worlds.
2. **Newton model custom attribute** (``model.mujoco.<option>``) - Supports per-world values.
3. **MuJoCo default** - Used if neither of the above is set.

Args:
Model (newton.Model): The Newton model to convert.
State (newton.State): The Newton state to convert.
model: The Newton model to convert.
state: The Newton state to convert (optional).
separate_worlds: If True, each world is a separate MuJoCo simulation.
iterations: Maximum solver iterations.
ls_iterations: Maximum line search iterations.
njmax: Maximum number of constraints per world.
nconmax: Maximum number of contacts.
solver: Constraint solver type ("cg" or "newton").
integrator: Integration method ("euler", "rk4", "implicit", "implicitfast").
disableflags: MuJoCo disable flags bitmask.
disable_contacts: If True, disable contact computation.
impratio: Impedance ratio for contacts. Defaults to MuJoCo default.
tolerance: Solver tolerance.
ls_tolerance: Line search tolerance.
cone: Friction cone type ("pyramidal" or "elliptic").
target_filename: Optional path to save generated MJCF file.
default_actuator_args: Default actuator parameters.
default_actuator_gear: Default actuator gear ratio.
actuator_gears: Per-actuator gear ratios by name.
actuated_axes: List of DOF indices to actuate.
skip_visual_only_geoms: If True, skip geoms that are visual-only.
include_sites: If True, include sites in the model.
mesh_maxhullvert: Maximum vertices for convex hull meshes.
ls_parallel: If True, enable parallel line search.

Returns:
tuple[MjWarpModel, MjWarpData, MjModel, MjData]: A tuple containing the model and data objects for ``mujoco_warp`` and MuJoCo.
tuple[MjWarpModel, MjWarpData, MjModel, MjData]: Model and data objects for
``mujoco_warp`` and MuJoCo.
"""

if not model.joint_count:
Expand Down Expand Up @@ -1296,6 +1344,16 @@ def fill_arr_from_dict(arr: nparray, d: dict[int, Any]):
else:
arr[tuple(keys.T)] = vals

# Solver option resolution priority (highest to lowest):
# 1. Constructor argument (e.g., impratio=5.0) - same value for all worlds
# 2. Newton model custom attribute (model.mujoco.<option>) - supports per-world values
# 3. MuJoCo default
impratio_overridden = impratio is not None
if impratio is None:
mujoco_attrs = getattr(model, "mujoco", None)
if mujoco_attrs and hasattr(mujoco_attrs, "impratio"):
impratio = float(mujoco_attrs.impratio.numpy()[0])

spec = mujoco.MjSpec()
spec.option.disableflags = disableflags
spec.option.gravity = np.array([*model.gravity.numpy()[0]])
Expand All @@ -1304,7 +1362,8 @@ def fill_arr_from_dict(arr: nparray, d: dict[int, Any]):
spec.option.iterations = iterations
spec.option.ls_iterations = ls_iterations
spec.option.cone = cone
spec.option.impratio = impratio
if impratio is not None:
spec.option.impratio = impratio
spec.option.tolerance = tolerance
spec.option.ls_tolerance = ls_tolerance
spec.option.jacobian = mujoco.mjtJacobian.mjJAC_AUTO
Expand Down Expand Up @@ -2237,6 +2296,9 @@ def add_geoms(newton_body_id: int):
# expand model fields that can be expanded:
self.expand_model_fields(self.mjw_model, nworld)

# update solver options from Newton model (only if not overridden by constructor)
self._update_solver_options(impratio_overridden=impratio_overridden)

# so far we have only defined the first world,
# now complete the data from the Newton model
self.notify_model_changed(SolverNotifyFlags.ALL)
Expand Down Expand Up @@ -2319,6 +2381,20 @@ def expand_model_fields(self, mj_model: MjWarpModel, nworld: int):
# "mat_rgba",
}

# Solver option fields to expand (nested in mj_model.opt)
opt_fields_to_expand = {
# "timestep",
"impratio_invsqrt",
# "tolerance",
# "ls_tolerance",
# "ccd_tolerance",
# "density",
# "viscosity",
# "gravity",
# "wind",
# "magnetic",
}

def tile(x: wp.array):
# Create new array with same shape but first dim multiplied by nworld
new_shape = list(x.shape)
Expand Down Expand Up @@ -2346,6 +2422,42 @@ def tile(x: wp.array):
array = getattr(mj_model, field)
setattr(mj_model, field, tile(array))

for field in opt_fields_to_expand:
if hasattr(mj_model.opt, field):
array = getattr(mj_model.opt, field)
setattr(mj_model.opt, field, tile(array))

def _update_solver_options(self, impratio_overridden: bool = False):
"""Update solver options from Newton model to MuJoCo Warp.

Copies per-world values from Newton custom attributes to the MuJoCo Warp model.
If a value was overridden by constructor, tile() already handled expansion so we skip it.

Args:
impratio_overridden: If True, impratio was set by constructor and tile() handled it.
"""
mujoco_attrs = getattr(self.model, "mujoco", None)
nworld = self.model.num_worlds

# Get Newton arrays - pass None if overridden or not available (kernel checks for None)
if not impratio_overridden and mujoco_attrs and hasattr(mujoco_attrs, "impratio"):
newton_impratio = mujoco_attrs.impratio
else:
newton_impratio = None

# Skip kernel if all options are None (add more checks here as options are added)
all_none = newton_impratio is None # and other_option is None and ...
if all_none:
return

wp.launch(
update_solver_options_kernel,
dim=nworld,
inputs=[newton_impratio],
outputs=[self.mjw_model.opt.impratio_invsqrt],
device=self.model.device,
)

def update_model_inertial_properties(self):
if self.model.body_count == 0:
return
Expand Down
15 changes: 15 additions & 0 deletions newton/_src/utils/import_mjcf.py
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ def parse_mjcf(
parse_meshes: bool = True,
parse_sites: bool = True,
parse_visuals: bool = True,
parse_options: bool = True,
up_axis: AxisType = Axis.Z,
ignore_names: Sequence[str] = (),
ignore_classes: Sequence[str] = (),
Expand Down Expand Up @@ -79,6 +80,7 @@ def parse_mjcf(
parse_meshes (bool): Whether geometries of type `"mesh"` should be parsed. If False, geometries of type `"mesh"` are ignored.
parse_sites (bool): Whether sites (non-colliding reference points) should be parsed. If False, sites are ignored.
parse_visuals (bool): Whether visual geometries (non-collision shapes) should be loaded. If False, visual shapes are not loaded (different from `hide_visuals` which loads but hides them). Default is True.
parse_options (bool): Whether solver options from the MJCF `<option>` tag should be parsed. If False, solver options are not loaded and custom attributes retain their default values. Default is True.
up_axis (AxisType): The up axis of the MuJoCo scene. The default is Z up.
ignore_names (Sequence[str]): A list of regular expressions. Bodies and joints with a name matching one of the regular expressions will be ignored.
ignore_classes (Sequence[str]): A list of regular expressions. Bodies and joints with a class matching one of the regular expressions will be ignored.
Expand Down Expand Up @@ -149,6 +151,19 @@ def parse_mjcf(
else:
mesh_dir = "."

# Parse MJCF option tag for ONCE and WORLD frequency custom attributes (solver options)
# WORLD frequency attributes use index 0 here; they get remapped during add_world()
if parse_options:
builder_custom_attr_option: list[ModelBuilder.CustomAttribute] = builder.get_custom_attributes_by_frequency(
[ModelAttributeFrequency.ONCE, ModelAttributeFrequency.WORLD]
)
option_elem = root.find("option")
if option_elem is not None and builder_custom_attr_option:
option_attrs = parse_custom_attributes(option_elem.attrib, builder_custom_attr_option, "mjcf")
for key, value in option_attrs.items():
if key in builder.custom_attributes:
builder.custom_attributes[key].values[0] = value

mesh_assets = {}
for asset in root.findall("asset"):
for mesh in asset.findall("mesh"):
Expand Down
19 changes: 17 additions & 2 deletions newton/_src/utils/import_usd.py
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@ def parse_usd(
load_sites: bool = True,
load_visual_shapes: bool = True,
hide_collision_shapes: bool = False,
parse_mujoco_options: bool = True,
mesh_maxhullvert: int = MESH_MAXHULLVERT,
schema_resolvers: list[SchemaResolver] | None = None,
) -> dict[str, Any]:
Expand Down Expand Up @@ -84,6 +85,7 @@ def parse_usd(
load_sites (bool): If True, sites (prims with MjcSiteAPI) are loaded as non-colliding reference points. If False, sites are ignored. Default is True.
load_visual_shapes (bool): If True, non-physics visual geometry is loaded. If False, visual-only shapes are ignored (sites are still controlled by ``load_sites``). Default is True.
hide_collision_shapes (bool): If True, collision shapes are hidden. Default is False.
parse_mujoco_options (bool): Whether MuJoCo solver options from the PhysicsScene should be parsed. If False, solver options are not loaded and custom attributes retain their default values. Default is True.
mesh_maxhullvert (int): Maximum vertices for convex hull approximation of meshes.
schema_resolvers (list[SchemaResolver]): Resolver instances in priority order. Default is no schema resolution.
Schema resolvers collect per-prim "solver-specific" attributes, see :ref:`schema_resolvers` for more information.
Expand Down Expand Up @@ -977,13 +979,26 @@ def define_joint_targets(dof, joint_desc):
)

if physics_scene_prim is not None:
# Extract custom attributes for model (ONCE) frequency from the PhysicsScene prim
# Extract custom attributes for model (ONCE and WORLD frequency) from the PhysicsScene prim
# WORLD frequency attributes use index 0 here; they get remapped during add_world()
builder_custom_attr_model: list[ModelBuilder.CustomAttribute] = [
attr for attr in builder.custom_attributes.values() if attr.frequency == ModelAttributeFrequency.ONCE
attr
for attr in builder.custom_attributes.values()
if attr.frequency in (ModelAttributeFrequency.ONCE, ModelAttributeFrequency.WORLD)
]

# Filter out MuJoCo attributes if parse_mujoco_options is False
if not parse_mujoco_options:
builder_custom_attr_model = [attr for attr in builder_custom_attr_model if attr.namespace != "mujoco"]

scene_custom_attrs = usd.get_custom_attribute_values(physics_scene_prim, builder_custom_attr_model)
scene_attributes.update(scene_custom_attrs)

# Set values on builder's custom attributes (similar to MJCF parsing)
for key, value in scene_custom_attrs.items():
if key in builder.custom_attributes:
builder.custom_attributes[key].values[0] = value

joint_descriptions = {}
# maps from joint prim path to joint index in builder
path_joint_map: dict[str, int] = {}
Expand Down
Loading
Loading