Skip to content

Commit d03b91d

Browse files
committed
Use newton-usd-schemas
1 parent a4ae345 commit d03b91d

File tree

6 files changed

+61
-3
lines changed

6 files changed

+61
-3
lines changed

mujoco_usd_converter/_impl/cli.py

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@
44
from pathlib import Path
55

66
import mujoco
7+
import newton_usd_schemas
78
import usdex.core
89
from pxr import Tf, Usd
910

@@ -47,6 +48,7 @@ def run() -> int:
4748
Tf.Status(f"USD Version: {Usd.GetVersion()}")
4849
Tf.Status(f"USDEX Version: {usdex.core.version()}")
4950
Tf.Status(f"MuJoCo Version: {mujoco.__version__}")
51+
Tf.Status(f"Newton USD Schemas Version: {newton_usd_schemas.__version__}")
5052

5153
try:
5254
converter = Converter(layer_structure=not args.no_layer_structure, scene=not args.no_physics_scene, comment=args.comment)

mujoco_usd_converter/_impl/convert.py

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,9 @@
55
from dataclasses import dataclass
66

77
import mujoco
8+
9+
# importing registers the Newton schema plugin with USD
10+
import newton_usd_schemas # noqa: F401
811
import usdex.core
912
from pxr import Sdf, Tf, Usd, UsdGeom, UsdPhysics
1013

mujoco_usd_converter/_impl/joint.py

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -67,18 +67,21 @@ def convert_joints(parent: Usd.Prim, body: mujoco.MjsBody, data: ConversionData)
6767

6868
data.references[Tokens.Physics][joint.name] = joint_prim.GetPrim()
6969

70-
apply_mjc_joint_api(joint_prim.GetPrim(), joint)
70+
convert_joint_attributes(joint_prim.GetPrim(), joint)
7171

7272

73-
def apply_mjc_joint_api(prim: Usd.Prim, joint: mujoco.MjsJoint):
73+
def convert_joint_attributes(prim: Usd.Prim, joint: mujoco.MjsJoint):
74+
prim.ApplyAPI(Usd.SchemaRegistry.GetSchemaTypeName("NewtonJointAPI"))
7475
prim.ApplyAPI(Usd.SchemaRegistry.GetSchemaTypeName("MjcPhysicsJointAPI"))
7576

77+
set_schema_attribute(prim, "newton:armature", joint.armature)
78+
set_schema_attribute(prim, "mjc:armature", joint.armature) # FUTURE: Remove once MuJoCo supports Newton schemas
79+
7680
limited_token = mj_limited_to_token(joint.actfrclimited)
7781
set_schema_attribute(prim, "mjc:actuatorfrclimited", limited_token)
7882
set_schema_attribute(prim, "mjc:actuatorfrcrange:min", joint.actfrcrange[0])
7983
set_schema_attribute(prim, "mjc:actuatorfrcrange:max", joint.actfrcrange[1])
8084
set_schema_attribute(prim, "mjc:actuatorgravcomp", bool(joint.actgravcomp))
81-
set_schema_attribute(prim, "mjc:armature", joint.armature)
8285
set_schema_attribute(prim, "mjc:damping", joint.damping)
8386
set_schema_attribute(prim, "mjc:frictionloss", joint.frictionloss)
8487
set_schema_attribute(prim, "mjc:group", joint.group)

pyproject.toml

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@ requires-python = ">=3.10,<3.13"
99
dependencies = [
1010
"mujoco==3.3.5",
1111
"usd-exchange>=2.1.0a3", # locked to USD 25.05
12+
"newton-usd-schemas>=0.1.0",
1213
"numpy-stl>=3.2",
1314
"tinyobjloader>=2.0.0rc13",
1415
]
@@ -39,6 +40,9 @@ path = "mujoco_usd_converter/_version.py"
3940
package = true
4041
python-preference = "only-managed"
4142

43+
[tool.uv.sources]
44+
newton-usd-schemas = { path = "../newton-usd-schemas", editable = true }
45+
4246
# Dev Tools
4347

4448
[tool.poe.tasks.test]

tests/testJoints.py

Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -342,6 +342,33 @@ def test_no_autolimits(self):
342342
self.assertFalse(unlimited_joint.GetLowerLimitAttr().HasAuthoredValue())
343343
self.assertFalse(unlimited_joint.GetUpperLimitAttr().HasAuthoredValue())
344344

345+
def test_newton_schema(self):
346+
model = pathlib.Path("./tests/data/joint_attributes.xml")
347+
asset: Sdf.AssetPath = mujoco_usd_converter.Converter().convert(model, self.tmpDir())
348+
stage: Usd.Stage = Usd.Stage.Open(asset.path)
349+
self.assertIsValidUsd(stage)
350+
351+
custom_joint: Usd.Prim = stage.GetPrimAtPath("/joint_attributes/Geometry/body1/custom_joint")
352+
self.assertTrue(custom_joint.IsValid())
353+
self.assertTrue(custom_joint.IsA(UsdPhysics.RevoluteJoint))
354+
self.assertTrue(custom_joint.HasAPI(Usd.SchemaRegistry.GetAPISchemaTypeName("NewtonJointAPI")))
355+
356+
# Check that all Newton properties are authored
357+
for property in custom_joint.GetPropertiesInNamespace("newton"):
358+
self.assertTrue(property.HasAuthoredValue(), f"Property {property.GetName()} is not authored")
359+
360+
# Check that all attributes are authored correctly
361+
self.assertTrue(custom_joint.GetAttribute("newton:armature").HasAuthoredValue())
362+
self.assertAlmostEqual(custom_joint.GetAttribute("newton:armature").Get(), 0.1)
363+
364+
# A joint with explicitly authored default values does not need to author any values in USD
365+
default_joint: Usd.Prim = stage.GetPrimAtPath("/joint_attributes/Geometry/body2/default_joint")
366+
self.assertTrue(default_joint.IsValid())
367+
self.assertTrue(default_joint.IsA(UsdPhysics.PrismaticJoint))
368+
self.assertTrue(default_joint.HasAPI(Usd.SchemaRegistry.GetAPISchemaTypeName("NewtonJointAPI")))
369+
self.assertFalse(default_joint.GetAttribute("newton:armature").HasAuthoredValue())
370+
self.assertAlmostEqual(default_joint.GetAttribute("newton:armature").Get(), 0.0)
371+
345372
def test_mjc_schema(self):
346373
# Test that all joint attributes are authored correctly
347374
model = pathlib.Path("./tests/data/joint_attributes.xml")

uv.lock

Lines changed: 19 additions & 0 deletions
Some generated files are not rendered by default. Learn more about customizing how changed files appear on GitHub.

0 commit comments

Comments
 (0)