Repository: newton-physics/newton Branch: main Commit: 04e4be2554be Files: 730 Total size: 16.8 MB Directory structure: gitextract_nsnm_v9o/ ├── .claude/ │ └── skills/ │ └── newton-api-design/ │ └── SKILL.md ├── .coderabbit.yml ├── .gitattributes ├── .github/ │ ├── ISSUE_TEMPLATE/ │ │ ├── 1-bug-report.yml │ │ ├── 2-feature-request.yml │ │ ├── 3-documentation.yml │ │ └── config.yml │ ├── PULL_REQUEST_TEMPLATE.md │ ├── codecov.yml │ └── workflows/ │ ├── aws_gpu_benchmarks.yml │ ├── aws_gpu_tests.yml │ ├── ci.yml │ ├── docs-dev.yml │ ├── docs-release.yml │ ├── merge_queue_aws_gpu.yml │ ├── minimum_deps_tests.yml │ ├── mujoco_warp_tests.yml │ ├── pr.yml │ ├── pr_closed.yml │ ├── pr_license_check.yml │ ├── pr_target_aws_gpu_benchmarks.yml │ ├── pr_target_aws_gpu_tests.yml │ ├── push_aws_gpu.yml │ ├── release.yml │ ├── scheduled_nightly.yml │ └── warp_nightly_tests.yml ├── .gitignore ├── .licenserc-docs.yaml ├── .licenserc.yaml ├── .pre-commit-config.yaml ├── .python-version ├── AGENTS.md ├── CHANGELOG.md ├── CITATION.cff ├── CLAUDE.md ├── CODE_OF_CONDUCT.md ├── CONTRIBUTING.md ├── LICENSE.md ├── README.md ├── SECURITY.md ├── asv/ │ └── benchmarks/ │ ├── __init__.py │ ├── benchmark_ik.py │ ├── benchmark_mujoco.py │ ├── compilation/ │ │ ├── __init__.py │ │ └── bench_example_load.py │ ├── setup/ │ │ ├── __init__.py │ │ └── bench_model.py │ └── simulation/ │ ├── __init__.py │ ├── bench_anymal.py │ ├── bench_cable.py │ ├── bench_cloth.py │ ├── bench_contacts.py │ ├── bench_heightfield.py │ ├── bench_ik.py │ ├── bench_mujoco.py │ ├── bench_quadruped_xpbd.py │ ├── bench_selection.py │ ├── bench_sensor_tiled_camera.py │ └── bench_viewer.py ├── asv.conf.json ├── docs/ │ ├── Makefile │ ├── _ext/ │ │ ├── autodoc_filter.py │ │ └── autodoc_wpfunc.py │ ├── _static/ │ │ ├── custom.css │ │ ├── gh-pages-404.html │ │ └── switcher.json │ ├── _templates/ │ │ ├── autosummary/ │ │ │ └── class.rst │ │ ├── class.rst │ │ ├── genindex.html │ │ ├── py-modindex.html │ │ ├── search.html │ │ └── sidebar-nav-bs.html │ ├── api/ │ │ ├── newton.rst │ │ ├── newton_geometry.rst │ │ ├── newton_ik.rst │ │ ├── newton_math.rst │ │ ├── newton_selection.rst │ │ ├── newton_sensors.rst │ │ ├── newton_solvers.rst │ │ ├── newton_solvers_style3d.rst │ │ ├── newton_usd.rst │ │ ├── newton_utils.rst │ │ └── newton_viewer.rst │ ├── concepts/ │ │ ├── articulations.rst │ │ ├── collisions.rst │ │ ├── conventions.rst │ │ ├── custom_attributes.rst │ │ ├── extended_attributes.rst │ │ ├── mass_inertia.rst │ │ ├── sensors.rst │ │ ├── sites.rst │ │ ├── usd_parsing.rst │ │ └── worlds.rst │ ├── conf.py │ ├── faq.rst │ ├── generate_api.py │ ├── guide/ │ │ ├── development.rst │ │ ├── installation.rst │ │ ├── overview.rst │ │ ├── release.rst │ │ ├── tutorials.rst │ │ └── visualization.rst │ ├── images/ │ │ └── examples/ │ │ ├── resize.bat │ │ └── resize.sh │ ├── index.rst │ ├── integrations/ │ │ ├── index.rst │ │ ├── isaac-lab.rst │ │ └── mujoco.rst │ ├── make.bat │ ├── migration.rst │ ├── print_api.py │ ├── serve.py │ └── tutorials/ │ └── 00_introduction.ipynb ├── newton/ │ ├── __init__.py │ ├── _src/ │ │ ├── core/ │ │ │ ├── __init__.py │ │ │ └── types.py │ │ ├── geometry/ │ │ │ ├── __init__.py │ │ │ ├── broad_phase_common.py │ │ │ ├── broad_phase_nxn.py │ │ │ ├── broad_phase_sap.py │ │ │ ├── collision_convex.py │ │ │ ├── collision_core.py │ │ │ ├── collision_primitive.py │ │ │ ├── contact_data.py │ │ │ ├── contact_reduction.py │ │ │ ├── contact_reduction_global.py │ │ │ ├── contact_reduction_hydroelastic.py │ │ │ ├── differentiable_contacts.py │ │ │ ├── flags.py │ │ │ ├── hashtable.py │ │ │ ├── inertia.py │ │ │ ├── kernels.py │ │ │ ├── mpr.py │ │ │ ├── multicontact.py │ │ │ ├── narrow_phase.py │ │ │ ├── raycast.py │ │ │ ├── remesh.py │ │ │ ├── sdf_contact.py │ │ │ ├── sdf_hydroelastic.py │ │ │ ├── sdf_mc.py │ │ │ ├── sdf_texture.py │ │ │ ├── sdf_utils.py │ │ │ ├── simplex_solver.py │ │ │ ├── support_function.py │ │ │ ├── terrain_generator.py │ │ │ ├── types.py │ │ │ └── utils.py │ │ ├── math/ │ │ │ ├── __init__.py │ │ │ └── spatial.py │ │ ├── sensors/ │ │ │ ├── __init__.py │ │ │ ├── sensor_contact.py │ │ │ ├── sensor_frame_transform.py │ │ │ ├── sensor_imu.py │ │ │ ├── sensor_raycast.py │ │ │ ├── sensor_tiled_camera.py │ │ │ └── warp_raytrace/ │ │ │ ├── __init__.py │ │ │ ├── bvh.py │ │ │ ├── gaussians.py │ │ │ ├── lighting.py │ │ │ ├── ray_intersect.py │ │ │ ├── raytrace.py │ │ │ ├── render.py │ │ │ ├── render_context.py │ │ │ ├── textures.py │ │ │ ├── tiling.py │ │ │ ├── types.py │ │ │ └── utils.py │ │ ├── sim/ │ │ │ ├── __init__.py │ │ │ ├── articulation.py │ │ │ ├── builder.py │ │ │ ├── collide.py │ │ │ ├── contacts.py │ │ │ ├── control.py │ │ │ ├── enums.py │ │ │ ├── graph_coloring.py │ │ │ ├── ik/ │ │ │ │ ├── __init__.py │ │ │ │ ├── ik_common.py │ │ │ │ ├── ik_lbfgs_optimizer.py │ │ │ │ ├── ik_lm_optimizer.py │ │ │ │ ├── ik_objectives.py │ │ │ │ └── ik_solver.py │ │ │ ├── model.py │ │ │ └── state.py │ │ ├── solvers/ │ │ │ ├── __init__.py │ │ │ ├── featherstone/ │ │ │ │ ├── __init__.py │ │ │ │ ├── kernels.py │ │ │ │ └── solver_featherstone.py │ │ │ ├── flags.py │ │ │ ├── implicit_mpm/ │ │ │ │ ├── __init__.py │ │ │ │ ├── contact_solver_kernels.py │ │ │ │ ├── implicit_mpm_model.py │ │ │ │ ├── implicit_mpm_solver_kernels.py │ │ │ │ ├── rasterized_collisions.py │ │ │ │ ├── render_grains.py │ │ │ │ ├── rheology_solver_kernels.py │ │ │ │ ├── solve_rheology.py │ │ │ │ └── solver_implicit_mpm.py │ │ │ ├── kamino/ │ │ │ │ ├── README.md │ │ │ │ ├── __init__.py │ │ │ │ ├── _src/ │ │ │ │ │ ├── __init__.py │ │ │ │ │ ├── core/ │ │ │ │ │ │ ├── __init__.py │ │ │ │ │ │ ├── bodies.py │ │ │ │ │ │ ├── builder.py │ │ │ │ │ │ ├── control.py │ │ │ │ │ │ ├── conversions.py │ │ │ │ │ │ ├── data.py │ │ │ │ │ │ ├── geometry.py │ │ │ │ │ │ ├── gravity.py │ │ │ │ │ │ ├── inertia.py │ │ │ │ │ │ ├── joints.py │ │ │ │ │ │ ├── materials.py │ │ │ │ │ │ ├── math.py │ │ │ │ │ │ ├── model.py │ │ │ │ │ │ ├── shapes.py │ │ │ │ │ │ ├── size.py │ │ │ │ │ │ ├── state.py │ │ │ │ │ │ ├── time.py │ │ │ │ │ │ ├── types.py │ │ │ │ │ │ └── world.py │ │ │ │ │ ├── dynamics/ │ │ │ │ │ │ ├── __init__.py │ │ │ │ │ │ ├── delassus.py │ │ │ │ │ │ ├── dual.py │ │ │ │ │ │ └── wrenches.py │ │ │ │ │ ├── geometry/ │ │ │ │ │ │ ├── __init__.py │ │ │ │ │ │ ├── aggregation.py │ │ │ │ │ │ ├── contacts.py │ │ │ │ │ │ ├── detector.py │ │ │ │ │ │ ├── keying.py │ │ │ │ │ │ ├── primitive/ │ │ │ │ │ │ │ ├── __init__.py │ │ │ │ │ │ │ ├── broadphase.py │ │ │ │ │ │ │ ├── narrowphase.py │ │ │ │ │ │ │ └── pipeline.py │ │ │ │ │ │ └── unified.py │ │ │ │ │ ├── integrators/ │ │ │ │ │ │ ├── __init__.py │ │ │ │ │ │ ├── euler.py │ │ │ │ │ │ ├── integrator.py │ │ │ │ │ │ └── moreau.py │ │ │ │ │ ├── kinematics/ │ │ │ │ │ │ ├── __init__.py │ │ │ │ │ │ ├── constraints.py │ │ │ │ │ │ ├── jacobians.py │ │ │ │ │ │ ├── joints.py │ │ │ │ │ │ ├── limits.py │ │ │ │ │ │ └── resets.py │ │ │ │ │ ├── linalg/ │ │ │ │ │ │ ├── __init__.py │ │ │ │ │ │ ├── blas.py │ │ │ │ │ │ ├── conjugate.py │ │ │ │ │ │ ├── core.py │ │ │ │ │ │ ├── factorize/ │ │ │ │ │ │ │ ├── __init__.py │ │ │ │ │ │ │ ├── llt_blocked.py │ │ │ │ │ │ │ ├── llt_blocked_semi_sparse.py │ │ │ │ │ │ │ └── llt_sequential.py │ │ │ │ │ │ ├── linear.py │ │ │ │ │ │ ├── sparse_matrix.py │ │ │ │ │ │ ├── sparse_operator.py │ │ │ │ │ │ └── utils/ │ │ │ │ │ │ ├── __init__.py │ │ │ │ │ │ ├── matrix.py │ │ │ │ │ │ ├── rand.py │ │ │ │ │ │ └── range.py │ │ │ │ │ ├── models/ │ │ │ │ │ │ ├── __init__.py │ │ │ │ │ │ ├── assets/ │ │ │ │ │ │ │ ├── basics/ │ │ │ │ │ │ │ │ ├── box_on_plane.usda │ │ │ │ │ │ │ │ ├── box_pendulum.usda │ │ │ │ │ │ │ │ ├── boxes_fourbar.usda │ │ │ │ │ │ │ │ ├── boxes_hinged.usda │ │ │ │ │ │ │ │ ├── boxes_nunchaku.usda │ │ │ │ │ │ │ │ └── cartpole.usda │ │ │ │ │ │ │ └── testing/ │ │ │ │ │ │ │ ├── geoms/ │ │ │ │ │ │ │ │ ├── test_geom_box.usda │ │ │ │ │ │ │ │ ├── test_geom_capsule.usda │ │ │ │ │ │ │ │ ├── test_geom_cone.usda │ │ │ │ │ │ │ │ ├── test_geom_cylinder.usda │ │ │ │ │ │ │ │ ├── test_geom_ellipsoid.usda │ │ │ │ │ │ │ │ └── test_geom_sphere.usda │ │ │ │ │ │ │ └── joints/ │ │ │ │ │ │ │ ├── test_joint_cartesian_actuated.usda │ │ │ │ │ │ │ ├── test_joint_cartesian_actuated_unary.usda │ │ │ │ │ │ │ ├── test_joint_cartesian_passive.usda │ │ │ │ │ │ │ ├── test_joint_cartesian_passive_unary.usda │ │ │ │ │ │ │ ├── test_joint_cylindrical_actuated.usda │ │ │ │ │ │ │ ├── test_joint_cylindrical_actuated_unary.usda │ │ │ │ │ │ │ ├── test_joint_cylindrical_passive.usda │ │ │ │ │ │ │ ├── test_joint_cylindrical_passive_unary.usda │ │ │ │ │ │ │ ├── test_joint_d6_6dof_actuated.usda │ │ │ │ │ │ │ ├── test_joint_d6_6dof_passive.usda │ │ │ │ │ │ │ ├── test_joint_d6_cartesian_actuated.usda │ │ │ │ │ │ │ ├── test_joint_d6_cartesian_passive.usda │ │ │ │ │ │ │ ├── test_joint_d6_cylindrical_actuated.usda │ │ │ │ │ │ │ ├── test_joint_d6_cylindrical_passive.usda │ │ │ │ │ │ │ ├── test_joint_d6_prismatic_actuated.usda │ │ │ │ │ │ │ ├── test_joint_d6_prismatic_passive.usda │ │ │ │ │ │ │ ├── test_joint_d6_revolute_actuated.usda │ │ │ │ │ │ │ ├── test_joint_d6_revolute_passive.usda │ │ │ │ │ │ │ ├── test_joint_d6_spherical_actuated.usda │ │ │ │ │ │ │ ├── test_joint_d6_spherical_passive.usda │ │ │ │ │ │ │ ├── test_joint_d6_universal_actuated.usda │ │ │ │ │ │ │ ├── test_joint_d6_universal_passive.usda │ │ │ │ │ │ │ ├── test_joint_fixed.usda │ │ │ │ │ │ │ ├── test_joint_fixed_unary.usda │ │ │ │ │ │ │ ├── test_joint_prismatic_actuated.usda │ │ │ │ │ │ │ ├── test_joint_prismatic_actuated_unary.usda │ │ │ │ │ │ │ ├── test_joint_prismatic_passive.usda │ │ │ │ │ │ │ ├── test_joint_prismatic_passive_unary.usda │ │ │ │ │ │ │ ├── test_joint_revolute_actuated.usda │ │ │ │ │ │ │ ├── test_joint_revolute_actuated_unary.usda │ │ │ │ │ │ │ ├── test_joint_revolute_passive.usda │ │ │ │ │ │ │ ├── test_joint_revolute_passive_unary.usda │ │ │ │ │ │ │ ├── test_joint_spherical.usda │ │ │ │ │ │ │ ├── test_joint_spherical_unary.usda │ │ │ │ │ │ │ ├── test_joint_universal_actuated.usda │ │ │ │ │ │ │ ├── test_joint_universal_actuated_unary.usda │ │ │ │ │ │ │ ├── test_joint_universal_passive.usda │ │ │ │ │ │ │ └── test_joint_universal_passive_unary.usda │ │ │ │ │ │ └── builders/ │ │ │ │ │ │ ├── __init__.py │ │ │ │ │ │ ├── basics.py │ │ │ │ │ │ ├── basics_newton.py │ │ │ │ │ │ ├── testing.py │ │ │ │ │ │ └── utils.py │ │ │ │ │ ├── solver_kamino_impl.py │ │ │ │ │ ├── solvers/ │ │ │ │ │ │ ├── __init__.py │ │ │ │ │ │ ├── fk.py │ │ │ │ │ │ ├── metrics.py │ │ │ │ │ │ ├── padmm/ │ │ │ │ │ │ │ ├── __init__.py │ │ │ │ │ │ │ ├── kernels.py │ │ │ │ │ │ │ ├── math.py │ │ │ │ │ │ │ ├── solver.py │ │ │ │ │ │ │ └── types.py │ │ │ │ │ │ └── warmstart.py │ │ │ │ │ └── utils/ │ │ │ │ │ ├── __init__.py │ │ │ │ │ ├── benchmark/ │ │ │ │ │ │ ├── .gitignore │ │ │ │ │ │ ├── __init__.py │ │ │ │ │ │ ├── __main__.py │ │ │ │ │ │ ├── configs.py │ │ │ │ │ │ ├── metrics.py │ │ │ │ │ │ ├── problems.py │ │ │ │ │ │ ├── render.py │ │ │ │ │ │ └── runner.py │ │ │ │ │ ├── control/ │ │ │ │ │ │ ├── __init__.py │ │ │ │ │ │ ├── animation.py │ │ │ │ │ │ ├── pid.py │ │ │ │ │ │ └── rand.py │ │ │ │ │ ├── device.py │ │ │ │ │ ├── io/ │ │ │ │ │ │ ├── __init__.py │ │ │ │ │ │ └── usd.py │ │ │ │ │ ├── logger.py │ │ │ │ │ ├── profiles.py │ │ │ │ │ ├── sim/ │ │ │ │ │ │ ├── __init__.py │ │ │ │ │ │ ├── datalog.py │ │ │ │ │ │ ├── runner.py │ │ │ │ │ │ ├── simulator.py │ │ │ │ │ │ └── viewer.py │ │ │ │ │ ├── sparse.py │ │ │ │ │ └── viewer.py │ │ │ │ ├── config.py │ │ │ │ ├── examples/ │ │ │ │ │ ├── .gitignore │ │ │ │ │ ├── __init__.py │ │ │ │ │ ├── newton/ │ │ │ │ │ │ ├── example_anymal_d.py │ │ │ │ │ │ ├── example_dr_legs.py │ │ │ │ │ │ └── example_fourbar.py │ │ │ │ │ ├── reset/ │ │ │ │ │ │ └── example_reset_dr_legs.py │ │ │ │ │ ├── rl/ │ │ │ │ │ │ ├── __init__.py │ │ │ │ │ │ ├── camera_follow.py │ │ │ │ │ │ ├── example_rl_bipedal.py │ │ │ │ │ │ ├── example_rl_drlegs.py │ │ │ │ │ │ ├── joystick.py │ │ │ │ │ │ ├── observations.py │ │ │ │ │ │ ├── simulation.py │ │ │ │ │ │ ├── simulation_runner.py │ │ │ │ │ │ ├── test_multi_env_dr_legs.py │ │ │ │ │ │ └── utils.py │ │ │ │ │ └── sim/ │ │ │ │ │ ├── example_sim_basics_all_heterogeneous.py │ │ │ │ │ ├── example_sim_basics_box_on_plane.py │ │ │ │ │ ├── example_sim_basics_box_pendulum.py │ │ │ │ │ ├── example_sim_basics_boxes_fourbar.py │ │ │ │ │ ├── example_sim_basics_boxes_hinged.py │ │ │ │ │ ├── example_sim_basics_cartpole.py │ │ │ │ │ ├── example_sim_dr_legs.py │ │ │ │ │ ├── example_sim_dr_testmech.py │ │ │ │ │ ├── example_sim_test_all_geoms.py │ │ │ │ │ └── example_sim_test_all_joints.py │ │ │ │ ├── solver_kamino.py │ │ │ │ └── tests/ │ │ │ │ ├── .gitignore │ │ │ │ ├── README.md │ │ │ │ ├── __init__.py │ │ │ │ ├── __main__.py │ │ │ │ ├── test_core_builder.py │ │ │ │ ├── test_core_geometry.py │ │ │ │ ├── test_core_joints.py │ │ │ │ ├── test_core_materials.py │ │ │ │ ├── test_core_model.py │ │ │ │ ├── test_core_shapes.py │ │ │ │ ├── test_core_world.py │ │ │ │ ├── test_dynamics_delassus.py │ │ │ │ ├── test_dynamics_dual.py │ │ │ │ ├── test_dynamics_wrenches.py │ │ │ │ ├── test_geometry_aggregation.py │ │ │ │ ├── test_geometry_contacts.py │ │ │ │ ├── test_geometry_detector.py │ │ │ │ ├── test_geometry_keying.py │ │ │ │ ├── test_geometry_margin_gap.py │ │ │ │ ├── test_geometry_primitive.py │ │ │ │ ├── test_geometry_unified.py │ │ │ │ ├── test_kinematics_constraints.py │ │ │ │ ├── test_kinematics_jacobians.py │ │ │ │ ├── test_kinematics_joints.py │ │ │ │ ├── test_kinematics_limits.py │ │ │ │ ├── test_linalg_core.py │ │ │ │ ├── test_linalg_factorize_llt_blocked.py │ │ │ │ ├── test_linalg_factorize_llt_sequential.py │ │ │ │ ├── test_linalg_solve_cg.py │ │ │ │ ├── test_linalg_solver_llt_blocked.py │ │ │ │ ├── test_linalg_solver_llt_sequential.py │ │ │ │ ├── test_linalg_sparse.py │ │ │ │ ├── test_linalg_utils_matrix.py │ │ │ │ ├── test_linalg_utils_rand.py │ │ │ │ ├── test_solver_kamino.py │ │ │ │ ├── test_solvers_forward_kinematics.py │ │ │ │ ├── test_solvers_metrics.py │ │ │ │ ├── test_solvers_padmm.py │ │ │ │ ├── test_utils_control_animation.py │ │ │ │ ├── test_utils_control_pid.py │ │ │ │ ├── test_utils_control_rand.py │ │ │ │ ├── test_utils_io_usd.py │ │ │ │ ├── test_utils_logger.py │ │ │ │ ├── test_utils_profiles.py │ │ │ │ ├── test_utils_random.py │ │ │ │ ├── test_utils_sim_simulator.py │ │ │ │ └── utils/ │ │ │ │ ├── __init__.py │ │ │ │ ├── checks.py │ │ │ │ ├── diff_check.py │ │ │ │ ├── extract.py │ │ │ │ ├── make.py │ │ │ │ ├── print.py │ │ │ │ └── rand.py │ │ │ ├── mujoco/ │ │ │ │ ├── __init__.py │ │ │ │ ├── kernels.py │ │ │ │ └── solver_mujoco.py │ │ │ ├── semi_implicit/ │ │ │ │ ├── __init__.py │ │ │ │ ├── kernels_body.py │ │ │ │ ├── kernels_contact.py │ │ │ │ ├── kernels_muscle.py │ │ │ │ ├── kernels_particle.py │ │ │ │ └── solver_semi_implicit.py │ │ │ ├── solver.py │ │ │ ├── style3d/ │ │ │ │ ├── __init__.py │ │ │ │ ├── builder.py │ │ │ │ ├── cloth.py │ │ │ │ ├── collision/ │ │ │ │ │ ├── __init__.py │ │ │ │ │ ├── bvh/ │ │ │ │ │ │ ├── __init__.py │ │ │ │ │ │ ├── bvh.py │ │ │ │ │ │ └── kernels.py │ │ │ │ │ ├── collision.py │ │ │ │ │ ├── collision_legacy.py │ │ │ │ │ └── kernels.py │ │ │ │ ├── kernels.py │ │ │ │ ├── linear_solver.py │ │ │ │ └── solver_style3d.py │ │ │ ├── vbd/ │ │ │ │ ├── __init__.py │ │ │ │ ├── particle_vbd_kernels.py │ │ │ │ ├── rigid_vbd_kernels.py │ │ │ │ ├── solver_vbd.py │ │ │ │ └── tri_mesh_collision.py │ │ │ └── xpbd/ │ │ │ ├── __init__.py │ │ │ ├── kernels.py │ │ │ └── solver_xpbd.py │ │ ├── usd/ │ │ │ ├── __init__.py │ │ │ ├── schema_resolver.py │ │ │ ├── schemas.py │ │ │ └── utils.py │ │ ├── utils/ │ │ │ ├── __init__.py │ │ │ ├── benchmark.py │ │ │ ├── cable.py │ │ │ ├── download_assets.py │ │ │ ├── heightfield.py │ │ │ ├── import_mjcf.py │ │ │ ├── import_urdf.py │ │ │ ├── import_usd.py │ │ │ ├── import_utils.py │ │ │ ├── mesh.py │ │ │ ├── render.py │ │ │ ├── selection.py │ │ │ ├── texture.py │ │ │ └── topology.py │ │ └── viewer/ │ │ ├── __init__.py │ │ ├── camera.py │ │ ├── gl/ │ │ │ ├── gui.py │ │ │ ├── icon.py │ │ │ ├── opengl.py │ │ │ └── shaders.py │ │ ├── kernels.py │ │ ├── picking.py │ │ ├── viewer.py │ │ ├── viewer_file.py │ │ ├── viewer_gl.py │ │ ├── viewer_null.py │ │ ├── viewer_rerun.py │ │ ├── viewer_usd.py │ │ ├── viewer_viser.py │ │ ├── viser/ │ │ │ └── static/ │ │ │ ├── assets/ │ │ │ │ ├── Sorter-Df0J3ZWJ.wasm │ │ │ │ ├── SplatSortWorker-DiSpcAPr.js │ │ │ │ ├── WebsocketServerWorker-C6PJJ7Dx.js │ │ │ │ ├── __vite-browser-external-BIHI7g3E.js │ │ │ │ ├── index-BVvA0mmR.css │ │ │ │ └── index-H4DT9vxj.js │ │ │ ├── index.html │ │ │ ├── manifest.json │ │ │ └── robots.txt │ │ └── wind.py │ ├── _version.py │ ├── examples/ │ │ ├── __init__.py │ │ ├── __main__.py │ │ ├── assets/ │ │ │ ├── ant.usda │ │ │ ├── anymal_walking_policy.pt │ │ │ ├── axis_cube.usda │ │ │ ├── bear.usd │ │ │ ├── boxes_fourbar.usda │ │ │ ├── bunny.usd │ │ │ ├── cartpole.urdf │ │ │ ├── cartpole.usda │ │ │ ├── cartpole_single_pendulum.usda │ │ │ ├── crazyflie.usd │ │ │ ├── curvedSurface.usd │ │ │ ├── humanoid.usda │ │ │ ├── nv_ant.xml │ │ │ ├── nv_humanoid.xml │ │ │ ├── quadruped.urdf │ │ │ ├── rj45_plug.usd │ │ │ ├── sensor_contact_scene.usda │ │ │ ├── tabletop.xml │ │ │ └── unisex_shirt.usd │ │ ├── basic/ │ │ │ ├── example_basic_conveyor.py │ │ │ ├── example_basic_heightfield.py │ │ │ ├── example_basic_joints.py │ │ │ ├── example_basic_pendulum.py │ │ │ ├── example_basic_plotting.py │ │ │ ├── example_basic_shapes.py │ │ │ ├── example_basic_urdf.py │ │ │ ├── example_basic_viewer.py │ │ │ ├── example_recording.py │ │ │ └── example_replay_viewer.py │ │ ├── cable/ │ │ │ ├── example_cable_bundle_hysteresis.py │ │ │ ├── example_cable_pile.py │ │ │ ├── example_cable_twist.py │ │ │ └── example_cable_y_junction.py │ │ ├── cloth/ │ │ │ ├── example_cloth_bending.py │ │ │ ├── example_cloth_franka.py │ │ │ ├── example_cloth_h1.py │ │ │ ├── example_cloth_hanging.py │ │ │ ├── example_cloth_poker_cards.py │ │ │ ├── example_cloth_rollers.py │ │ │ ├── example_cloth_style3d.py │ │ │ └── example_cloth_twist.py │ │ ├── contacts/ │ │ │ ├── example_brick_stacking.py │ │ │ ├── example_contacts_rj45_plug.py │ │ │ ├── example_nut_bolt_hydro.py │ │ │ ├── example_nut_bolt_sdf.py │ │ │ └── example_pyramid.py │ │ ├── diffsim/ │ │ │ ├── example_diffsim_ball.py │ │ │ ├── example_diffsim_bear.py │ │ │ ├── example_diffsim_cloth.py │ │ │ ├── example_diffsim_drone.py │ │ │ ├── example_diffsim_soft_body.py │ │ │ └── example_diffsim_spring_cage.py │ │ ├── ik/ │ │ │ ├── example_ik_cube_stacking.py │ │ │ ├── example_ik_custom.py │ │ │ ├── example_ik_franka.py │ │ │ └── example_ik_h1.py │ │ ├── mpm/ │ │ │ ├── example_mpm_anymal.py │ │ │ ├── example_mpm_beam_twist.py │ │ │ ├── example_mpm_grain_rendering.py │ │ │ ├── example_mpm_granular.py │ │ │ ├── example_mpm_multi_material.py │ │ │ ├── example_mpm_snow_ball.py │ │ │ ├── example_mpm_twoway_coupling.py │ │ │ └── example_mpm_viscous.py │ │ ├── multiphysics/ │ │ │ ├── example_softbody_dropping_to_cloth.py │ │ │ └── example_softbody_gift.py │ │ ├── robot/ │ │ │ ├── example_robot_allegro_hand.py │ │ │ ├── example_robot_anymal_c_walk.py │ │ │ ├── example_robot_anymal_d.py │ │ │ ├── example_robot_cartpole.py │ │ │ ├── example_robot_g1.py │ │ │ ├── example_robot_h1.py │ │ │ ├── example_robot_panda_hydro.py │ │ │ ├── example_robot_policy.py │ │ │ └── example_robot_ur10.py │ │ ├── selection/ │ │ │ ├── example_selection_articulations.py │ │ │ ├── example_selection_cartpole.py │ │ │ ├── example_selection_materials.py │ │ │ └── example_selection_multiple.py │ │ ├── sensors/ │ │ │ ├── example_sensor_contact.py │ │ │ ├── example_sensor_imu.py │ │ │ └── example_sensor_tiled_camera.py │ │ └── softbody/ │ │ ├── example_softbody_franka.py │ │ └── example_softbody_hanging.py │ ├── geometry.py │ ├── ik.py │ ├── licenses/ │ │ ├── CC-BY-4.0.txt │ │ ├── unittest-parallel-LICENSE.txt │ │ └── viser_and_inter-font-family.txt │ ├── math.py │ ├── py.typed │ ├── selection.py │ ├── sensors.py │ ├── solvers.py │ ├── tests/ │ │ ├── __init__.py │ │ ├── __main__.py │ │ ├── assets/ │ │ │ ├── actuator_test.usda │ │ │ ├── ant.usda │ │ │ ├── ant_mixed.usda │ │ │ ├── ant_multi.usda │ │ │ ├── cartpole_mjc.usda │ │ │ ├── constraints.xml │ │ │ ├── cube_cylinder.usda │ │ │ ├── four_link_chain_articulation.usda │ │ │ ├── humanoid.urdf │ │ │ ├── humanoid.usda │ │ │ ├── mjcf_exclude_hyphen_test.xml │ │ │ ├── mjcf_exclude_test.xml │ │ │ ├── pendulum_revolute_vs_d6.usda │ │ │ ├── revolute_articulation.usda │ │ │ ├── simple_articulation_with_mesh.usda │ │ │ ├── tetmesh_custom_attrs.usda │ │ │ ├── tetmesh_multi.usda │ │ │ ├── tetmesh_simple.usda │ │ │ └── tetmesh_with_material.usda │ │ ├── golden_data/ │ │ │ └── test_sensor_tiled_camera/ │ │ │ ├── color.npy │ │ │ └── depth.npy │ │ ├── test_actuators.py │ │ ├── test_anymal_reset.py │ │ ├── test_api.py │ │ ├── test_body_force.py │ │ ├── test_body_velocity.py │ │ ├── test_broad_phase.py │ │ ├── test_cable.py │ │ ├── test_cloth.py │ │ ├── test_collision_cloth.py │ │ ├── test_collision_pipeline.py │ │ ├── test_collision_primitives.py │ │ ├── test_coloring.py │ │ ├── test_cone_orientation.py │ │ ├── test_contact_reduction.py │ │ ├── test_contact_reduction_global.py │ │ ├── test_control_force.py │ │ ├── test_custom_attributes.py │ │ ├── test_differentiable_contacts.py │ │ ├── test_download_assets.py │ │ ├── test_environment_group_collision.py │ │ ├── test_equality_constraints.py │ │ ├── test_example_browser.py │ │ ├── test_examples.py │ │ ├── test_fixed_tendon.py │ │ ├── test_gjk.py │ │ ├── test_hashtable.py │ │ ├── test_heightfield.py │ │ ├── test_hydroelastic.py │ │ ├── test_ik.py │ │ ├── test_ik_fk_kernels.py │ │ ├── test_ik_lbfgs.py │ │ ├── test_implicit_mpm.py │ │ ├── test_implicit_mpm_flow_rule.py │ │ ├── test_import_mjcf.py │ │ ├── test_import_urdf.py │ │ ├── test_import_usd.py │ │ ├── test_inertia.py │ │ ├── test_inertia_validation.py │ │ ├── test_jacobian_mass_matrix.py │ │ ├── test_joint_controllers.py │ │ ├── test_joint_drive.py │ │ ├── test_joint_limits.py │ │ ├── test_kinematic_links.py │ │ ├── test_kinematics.py │ │ ├── test_match_labels.py │ │ ├── test_menagerie_mujoco.py │ │ ├── test_menagerie_usd_mujoco.py │ │ ├── test_mesh_aabb.py │ │ ├── test_model.py │ │ ├── test_mujoco_general_actuators.py │ │ ├── test_mujoco_solver.py │ │ ├── test_narrow_phase.py │ │ ├── test_obb.py │ │ ├── test_parent_force.py │ │ ├── test_pendulum_revolute_vs_d6.py │ │ ├── test_physics_validation.py │ │ ├── test_raycast.py │ │ ├── test_recorder.py │ │ ├── test_remesh.py │ │ ├── test_rigid_contact.py │ │ ├── test_robot_composer.py │ │ ├── test_runtime_gravity.py │ │ ├── test_schema_resolver.py │ │ ├── test_sdf_compute.py │ │ ├── test_sdf_primitive.py │ │ ├── test_sdf_texture.py │ │ ├── test_selection.py │ │ ├── test_sensor_contact.py │ │ ├── test_sensor_frame_transform.py │ │ ├── test_sensor_imu.py │ │ ├── test_sensor_raycast.py │ │ ├── test_sensor_tiled_camera.py │ │ ├── test_sensor_tiled_camera_forward_depth.py │ │ ├── test_sensor_tiled_camera_particles_multiworld.py │ │ ├── test_shape_colors.py │ │ ├── test_shapes_no_bounce.py │ │ ├── test_sites.py │ │ ├── test_sites_mjcf_import.py │ │ ├── test_sites_mujoco_export.py │ │ ├── test_sites_usd_import.py │ │ ├── test_softbody.py │ │ ├── test_solver_vbd.py │ │ ├── test_solver_xpbd.py │ │ ├── test_spatial_tendon.py │ │ ├── test_terrain_generator.py │ │ ├── test_tolerance_clamping.py │ │ ├── test_up_axis.py │ │ ├── test_viewer_geometry_batching.py │ │ ├── test_viewer_log_shapes.py │ │ ├── test_viewer_particle_flags.py │ │ ├── test_viewer_picking.py │ │ ├── test_viewer_rerun_hidden.py │ │ ├── test_viewer_rerun_init_args.py │ │ ├── test_viewer_usd.py │ │ ├── test_viewer_world_offsets.py │ │ ├── test_warp_config_cli.py │ │ ├── thirdparty/ │ │ │ ├── __init__.py │ │ │ └── unittest_parallel.py │ │ └── unittest_utils.py │ ├── usd.py │ ├── utils.py │ └── viewer.py ├── pyproject.toml └── scripts/ ├── check_warp_array_syntax.py └── ci/ ├── dispatch_workflow_and_wait.py └── update_docs_switcher.py ================================================ FILE CONTENTS ================================================ ================================================ FILE: .claude/skills/newton-api-design/SKILL.md ================================================ --- name: newton-api-design description: Use when designing, adding, or reviewing public API for the Newton physics engine — class names, method signatures, type hints, docstrings, or parameter conventions. Also use when unsure if new API conforms to project conventions. --- # Newton API Design Conventions Detailed patterns that supplement AGENTS.md. Read AGENTS.md first for the basics (prefix-first naming, PEP 604, Google-style docstrings, SI units, Sphinx cross-refs). ## Builder Method Signature Template All `ModelBuilder.add_shape_*` methods follow this parameter order: ```python def add_shape_cone( self, body: int, xform: Transform | None = None, # shape-specific params here (radius, height, etc.) radius: float = 0.5, height: float = 1.0, cfg: ShapeConfig | None = None, as_site: bool = False, label: str | None = None, custom_attributes: dict[str, Any] | None = None, ) -> int: """Adds a cone collision shape to a body. Args: body: Index of the parent body. Use -1 for static shapes. xform: Transform in parent body's local frame. If ``None``, identity transform is used. radius: Cone base radius [m]. height: Cone height [m]. cfg: Shape configuration. If ``None``, uses :attr:`default_shape_cfg`. as_site: If ``True``, creates a site instead of a collision shape. label: Optional label for identifying the shape. custom_attributes: Dictionary of custom attribute names to values. Returns: Index of the newly added shape. """ ``` **Key conventions:** - `xform` (not `tf`, `transform`, or `pose`) — always `Transform | None = None` - `cfg` (not `config`, `shape_config`) — always `ShapeConfig | None = None` - `body`, `label`, `custom_attributes` — standard params on all builder methods - Defaults are `None`, not constructed objects like `wp.transform()` ## Nested Classes Use `IntEnum` (not `Enum` with strings) for enumerations: ```python class Model: class AttributeAssignment(IntEnum): MODEL = 0 STATE = 1 ``` When an `IntEnum` includes a `NONE` member, define it first at `0`: ```python class GeoType(IntEnum): NONE = 0 PLANE = 1 HFIELD = 2 ``` This keeps the sentinel value stable and leaves room to append future real members at the end instead of inserting them before a trailing `NONE`. Dataclass field docstrings go on the line immediately below the field: ```python @dataclass class ShapeConfig: density: float = 1000.0 """The density of the shape material.""" ke: float = 2.5e3 """The contact elastic stiffness.""" ``` ## Array Documentation Format Document shape, dtype, and units in attribute docstrings: ```python """Rigid body velocities [m/s, rad/s], shape (body_count,), dtype :class:`spatial_vector`.""" """Joint forces [N or N·m], shape (joint_dof_count,), dtype float.""" """Contact points [m], shape [count, 3], float.""" ``` For compound arrays, list per-component units: ```python """[0] k_mu [Pa], [1] k_lambda [Pa], ...""" ``` For **public API** attributes and method signatures, use bare `wp.array | None` and document the concrete dtype in the docstring (e.g., `dtype :class:\`vec3\``). Warp kernel parameters require concrete dtypes inline (`wp.array(dtype=wp.vec3)`) per AGENTS.md. ## Quick Checklist When reviewing new API, verify: - [ ] Parameters use project vocabulary (`xform`, `cfg`, `body`, `label`) - [ ] Defaults are `None`, not constructed objects - [ ] Nested enumerations use `IntEnum` with int values - [ ] Enumerations with `NONE` define `NONE = 0` first - [ ] Dataclass fields have docstrings on the line below - [ ] Array docs include shape, dtype, and units - [ ] Builder methods include `as_site`, `label`, `custom_attributes` ================================================ FILE: .coderabbit.yml ================================================ # yaml-language-server: $schema=https://coderabbit.ai/integrations/schema.v2.json language: "en-US" early_access: false reviews: profile: "chill" request_changes_workflow: false high_level_summary: true poem: false review_status: true collapse_walkthrough: true auto_review: enabled: true drafts: true tools: github-checks: timeout_ms: 900000 path_instructions: - path: "**" instructions: | Check that any user-facing change includes a corresponding entry in CHANGELOG.md under the [Unreleased] section. Entries should use imperative present tense ("Add X", not "Added X") and be placed under the correct category (Added, Changed, Deprecated, Removed, or Fixed). For Deprecated, Changed, and Removed entries, verify the entry includes migration guidance telling users what replaces the old behavior. chat: auto_reply: true issue_enrichment: auto_enrich: enabled: false ================================================ FILE: .gitattributes ================================================ *.jpg !text !filter !merge !diff CHANGELOG.md merge=union ================================================ FILE: .github/ISSUE_TEMPLATE/1-bug-report.yml ================================================ name: Bug Report description: Create a report to help us improve Newton. title: "[BUG] " labels: ["bug"] body: - type: markdown attributes: value: | Thanks for taking the time to fill out this bug report! - type: textarea attributes: label: Bug Description description: >- Describe the bug. What happened, and what did you expect to happen? validations: required: true - type: textarea attributes: label: Reproduction Script description: >- If possible, provide a minimal script or code snippet that reproduces the issue. render: python validations: required: false - type: textarea attributes: label: System Information description: >- Newton version, Warp version, Python version, OS, and GPU (if relevant). placeholder: | - Newton: 0.x.x - Warp: 1.x.x - Python: 3.x - OS: Ubuntu 22.04 / Windows 11 / macOS 14 - GPU: NVIDIA RTX ... validations: required: false ================================================ FILE: .github/ISSUE_TEMPLATE/2-feature-request.yml ================================================ name: Feature Request description: Suggest an idea for Newton. title: "[REQ] " labels: ["feature request"] body: - type: textarea attributes: label: Description description: >- Describe the feature you'd like added or changed. validations: required: true - type: textarea attributes: label: Motivation / Use Case description: >- Why would this be useful? What problem does it solve? validations: required: true - type: textarea attributes: label: Alternatives Considered description: >- Have you considered any alternative approaches or workarounds? validations: required: false ================================================ FILE: .github/ISSUE_TEMPLATE/3-documentation.yml ================================================ name: Documentation description: Report an error or suggest improvements for the documentation. title: "[DOCS] " labels: ["docs"] body: - type: dropdown attributes: label: Category description: What kind of documentation issue is this? options: - Error in existing documentation - Missing documentation - Improvement suggestion validations: required: true - type: textarea attributes: label: Description description: >- Describe the issue. Include links to the relevant documentation pages if applicable. validations: required: true ================================================ FILE: .github/ISSUE_TEMPLATE/config.yml ================================================ blank_issues_enabled: true contact_links: - name: Question url: https://github.com/newton-physics/newton/discussions about: Ask questions about Newton in GitHub Discussions. ================================================ FILE: .github/PULL_REQUEST_TEMPLATE.md ================================================ ## Description ## Checklist - [ ] New or existing tests cover these changes - [ ] The documentation is up to date with these changes - [ ] `CHANGELOG.md` has been updated (if user-facing change) ## Test plan ## Bug fix **Steps to reproduce:** **Minimal reproduction:** ```python import newton # Code that demonstrates the bug ``` ## New feature / API change ```python import newton # Code that demonstrates the new capability ``` ================================================ FILE: .github/codecov.yml ================================================ coverage: status: project: off patch: off comment: layout: "diff, flags, files" fixes: - "/var/snap/amazon-ssm-agent/[0-9]+/::" ================================================ FILE: .github/workflows/aws_gpu_benchmarks.yml ================================================ name: GPU Benchmarks on AWS EC2 (Reusable) # This is a reusable workflow that uses machulav/ec2-github-runner to run GPU benchmarks. # Called by: # - pr_target_aws_gpu.yml (for pull requests) # Workflow configuration variables env: AWS_REGION: us-east-2 AWS_INSTANCE_TYPE: g7e.2xlarge AWS_VOLUME_SIZE: 92 AWS_VOLUME_TYPE: gp3 AWS_SECURITY_GROUP_IDS: sg-07807c44e7f2a368a AWS_ROLE_ARN: arn:aws:iam::968945269301:role/newton-physics-newton-ec2-github-runner-role AWS_ROLE_DURATION: 7200 HOME: /actions-runner on: workflow_call: inputs: ref: description: 'Git ref to checkout' required: true type: string default: '' base_ref: description: 'Base ref to compare against (for ASV)' required: true type: string default: '' secrets: GH_PERSONAL_ACCESS_TOKEN: required: true jobs: start-runner: name: Start self-hosted EC2 runner if: github.repository == 'newton-physics/newton' runs-on: ubuntu-latest permissions: id-token: write contents: read outputs: label: ${{ steps.start-ec2-runner.outputs.label }} ec2-instance-id: ${{ steps.start-ec2-runner.outputs.ec2-instance-id }} steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Configure AWS credentials uses: aws-actions/configure-aws-credentials@8df5847569e6427dd6c4fb1cf565c83acfa8afa7 # v6.0.0 with: aws-region: ${{ env.AWS_REGION }} role-to-assume: ${{ env.AWS_ROLE_ARN }} role-duration-seconds: ${{ env.AWS_ROLE_DURATION }} - name: Get the latest AWS Deep Learning Base GPU AMI run: | echo "Finding the latest AWS Deep Learning Base GPU AMI..." LATEST_AMI_ID=$(aws ec2 describe-images --region ${{ env.AWS_REGION }} \ --owners amazon \ --filters 'Name=name,Values=Deep Learning Base AMI with Single CUDA (Ubuntu 22.04) ????????' 'Name=state,Values=available' \ --query 'reverse(sort_by(Images, &CreationDate))[:1].ImageId' \ --output text) if [[ -z "$LATEST_AMI_ID" ]]; then echo "❌ No AMI ID found. Exiting." exit 1 fi echo "Latest AMI ID found: $LATEST_AMI_ID" echo "LATEST_AMI_ID=$LATEST_AMI_ID" >> "$GITHUB_ENV" - name: Start EC2 runner id: start-ec2-runner uses: machulav/ec2-github-runner@a00f575a87f3a96ec6de9413d16eeb828a3cc0a8 # v2.5.2 with: mode: start github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN }} ec2-instance-type: ${{ env.AWS_INSTANCE_TYPE }} ec2-volume-size: ${{ env.AWS_VOLUME_SIZE }} ec2-volume-type: ${{ env.AWS_VOLUME_TYPE }} availability-zones-config: > [ {"imageId": "${{ env.LATEST_AMI_ID }}", "subnetId": "subnet-051b9d2e71acf8047", "securityGroupId": "${{ env.AWS_SECURITY_GROUP_IDS }}"}, {"imageId": "${{ env.LATEST_AMI_ID }}", "subnetId": "subnet-0c98bd06abe8ee5eb", "securityGroupId": "${{ env.AWS_SECURITY_GROUP_IDS }}"} ] pre-runner-script: | if [ -d /opt/dlami/nvme ]; then mkdir -p /opt/dlami/nvme/actions-runner/_work mkdir -p /opt/dlami/nvme/actions-runner/.local mkdir -p /opt/dlami/nvme/actions-runner/.cache ln -s /opt/dlami/nvme/actions-runner/_work /actions-runner/_work ln -s /opt/dlami/nvme/actions-runner/.local /actions-runner/.local ln -s /opt/dlami/nvme/actions-runner/.cache /actions-runner/.cache fi aws-resource-tags: > [ {"Key": "Name", "Value": "ec2-github-runner"}, {"Key": "created-by", "Value": "github-actions-newton-role"}, {"Key": "GitHub-Repository", "Value": "${{ github.repository }}"} ] gpu-benchmarks: name: Run GPU Benchmarks on AWS EC2 needs: start-runner # required to start the main job when the runner is ready runs-on: ${{ needs.start-runner.outputs.label }} # run the job on the newly created runner permissions: contents: read steps: - name: Checkout repository uses: actions/checkout@8e8c483db84b4bee98b60c0593521ed34d9990e8 # v6.0.1 with: ref: ${{ inputs.ref }} fetch-depth: 0 - name: Install system dependencies run: | sudo apt-get update sudo apt-get install -y libxrandr-dev libxinerama-dev libxcursor-dev libxi-dev \ libgl1-mesa-dev libglu1-mesa-dev # Clean up apt cache immediately after install sudo apt-get clean - name: Install uv uses: astral-sh/setup-uv@37802adc94f370d6bfd71619e3f0bf239e1f3b78 # v7.6.0 with: version: "0.11.0" - name: Set up Python run: uv python install - name: Check disk space run: df -h - name: Set up ASV environment run: uvx asv machine --yes - name: Run Benchmarks run: | uvx --with virtualenv asv continuous \ --launch-method spawn \ --interleave-rounds \ --append-samples \ --no-only-changed \ -e -b Fast \ ${{ inputs.base_ref }} \ ${{ inputs.ref }} continue-on-error: true id: benchmark - name: Show comparison on failure if: steps.benchmark.outcome == 'failure' run: | uvx asv compare --split ${{ inputs.base_ref }} ${{ inputs.ref }} exit 2 - name: Check disk space (post-benchmark) if: always() run: df -h - name: Re-run instructions if: failure() run: | # Create error annotations (appear at top of job summary) echo "::error::DO NOT use 'Re-run failed jobs' - the EC2 runner no longer exists and your job will be queued forever." echo "::error::USE 'Re-run all jobs' instead to start a fresh EC2 runner." # Write to job summary (appears in Summary tab) cat >> "$GITHUB_STEP_SUMMARY" << 'EOF' ## ⚠️ How to Re-run This Workflow This workflow uses **ephemeral EC2 runners** that are terminated after each run. | | Option | Result | |---|--------|--------| | ❌ | **Re-run failed jobs** | Runner no longer exists → job queued forever | | ✅ | **Re-run all jobs** | Starts new EC2 runner → benchmarks re-run | EOF # Also print to log for completeness cat << 'EOF' ================================================================================ ⚠️ IMPORTANT: HOW TO RE-RUN THIS WORKFLOW ================================================================================ This workflow uses ephemeral EC2 runners that are terminated after each run. ❌ DO NOT select "Re-run failed jobs" → The runner no longer exists and your job will be queued forever. ✅ DO select "Re-run all jobs" → This will start a new EC2 runner and re-run the benchmarks. ================================================================================ EOF stop-runner: name: Stop self-hosted EC2 runner runs-on: ubuntu-latest permissions: id-token: write contents: read needs: - start-runner - gpu-benchmarks if: always() && github.repository == 'newton-physics/newton' steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Configure AWS credentials uses: aws-actions/configure-aws-credentials@8df5847569e6427dd6c4fb1cf565c83acfa8afa7 # v6.0.0 with: aws-region: ${{ env.AWS_REGION }} role-to-assume: ${{ env.AWS_ROLE_ARN }} role-duration-seconds: ${{ env.AWS_ROLE_DURATION }} - name: Stop EC2 runner uses: machulav/ec2-github-runner@a00f575a87f3a96ec6de9413d16eeb828a3cc0a8 # v2.5.2 with: mode: stop github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN }} label: ${{ needs.start-runner.outputs.label }} ec2-instance-id: ${{ needs.start-runner.outputs.ec2-instance-id }} ================================================ FILE: .github/workflows/aws_gpu_tests.yml ================================================ name: GPU Unit Tests on AWS EC2 (Reusable) # This is a reusable workflow that uses machulav/ec2-github-runner to run GPU tests. # Called by: # - pr_target_aws_gpu_tests.yml (for pull requests) # - merge_queue_aws_gpu.yml (for merge groups) # - push_aws_gpu.yml (for pushes to main/release branches) # - scheduled_nightly.yml (for nightly multi-GPU tests) # Workflow configuration variables env: AWS_REGION: us-east-2 AWS_INSTANCE_TYPE: ${{ inputs.instance-type || 'g7e.2xlarge' }} AWS_VOLUME_SIZE: ${{ inputs.volume-size || '92' }} AWS_VOLUME_TYPE: gp3 AWS_SECURITY_GROUP_IDS: sg-07807c44e7f2a368a AWS_ROLE_ARN: arn:aws:iam::968945269301:role/newton-physics-newton-ec2-github-runner-role AWS_ROLE_DURATION: 7200 HOME: /actions-runner on: workflow_call: inputs: ref: description: 'Git ref to checkout' required: false type: string default: '' instance-type: description: 'EC2 instance type' required: false type: string default: 'g7e.2xlarge' volume-size: description: 'EBS volume size in GB' required: false type: string default: '92' secrets: GH_PERSONAL_ACCESS_TOKEN: required: true CODECOV_TOKEN: required: true workflow_dispatch: inputs: instance-type: description: 'EC2 instance type' required: false type: string default: 'g7e.2xlarge' jobs: start-runner: name: Start self-hosted EC2 runner if: github.repository == 'newton-physics/newton' runs-on: ubuntu-latest permissions: id-token: write contents: read outputs: label: ${{ steps.start-ec2-runner.outputs.label }} ec2-instance-id: ${{ steps.start-ec2-runner.outputs.ec2-instance-id }} steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Configure AWS credentials uses: aws-actions/configure-aws-credentials@8df5847569e6427dd6c4fb1cf565c83acfa8afa7 # v6.0.0 with: aws-region: ${{ env.AWS_REGION }} role-to-assume: ${{ env.AWS_ROLE_ARN }} role-duration-seconds: ${{ env.AWS_ROLE_DURATION }} - name: Get the latest AWS Deep Learning Base GPU AMI run: | echo "Finding the latest AWS Deep Learning Base GPU AMI..." LATEST_AMI_ID=$(aws ec2 describe-images --region ${{ env.AWS_REGION }} \ --owners amazon \ --filters 'Name=name,Values=Deep Learning Base AMI with Single CUDA (Ubuntu 22.04) ????????' 'Name=state,Values=available' \ --query 'reverse(sort_by(Images, &CreationDate))[:1].ImageId' \ --output text) if [[ -z "$LATEST_AMI_ID" ]]; then echo "❌ No AMI ID found. Exiting." exit 1 fi echo "Latest AMI ID found: $LATEST_AMI_ID" echo "LATEST_AMI_ID=$LATEST_AMI_ID" >> "$GITHUB_ENV" - name: Start EC2 runner id: start-ec2-runner uses: machulav/ec2-github-runner@a00f575a87f3a96ec6de9413d16eeb828a3cc0a8 # v2.5.2 with: mode: start github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN }} ec2-instance-type: ${{ env.AWS_INSTANCE_TYPE }} ec2-volume-size: ${{ env.AWS_VOLUME_SIZE }} ec2-volume-type: ${{ env.AWS_VOLUME_TYPE }} availability-zones-config: > [ {"imageId": "${{ env.LATEST_AMI_ID }}", "subnetId": "subnet-051b9d2e71acf8047", "securityGroupId": "${{ env.AWS_SECURITY_GROUP_IDS }}"}, {"imageId": "${{ env.LATEST_AMI_ID }}", "subnetId": "subnet-0c98bd06abe8ee5eb", "securityGroupId": "${{ env.AWS_SECURITY_GROUP_IDS }}"} ] pre-runner-script: | if [ -d /opt/dlami/nvme ]; then mkdir -p /opt/dlami/nvme/actions-runner/_work mkdir -p /opt/dlami/nvme/actions-runner/.local mkdir -p /opt/dlami/nvme/actions-runner/.cache ln -s /opt/dlami/nvme/actions-runner/_work /actions-runner/_work ln -s /opt/dlami/nvme/actions-runner/.local /actions-runner/.local ln -s /opt/dlami/nvme/actions-runner/.cache /actions-runner/.cache fi aws-resource-tags: > [ {"Key": "Name", "Value": "ec2-github-runner"}, {"Key": "created-by", "Value": "github-actions-newton-role"}, {"Key": "GitHub-Repository", "Value": "${{ github.repository }}"} ] gpu-unit-tests: name: Run GPU Unit Tests on AWS EC2 needs: start-runner # required to start the main job when the runner is ready runs-on: ${{ needs.start-runner.outputs.label }} # run the job on the newly created runner permissions: contents: read env: PYTHONFAULTHANDLER: "1" # Dump tracebacks on fatal signals (SIGSEGV, SIGABRT, etc.) steps: - name: Checkout repository uses: actions/checkout@8e8c483db84b4bee98b60c0593521ed34d9990e8 # v6.0.1 with: ref: ${{ inputs.ref || github.sha }} - name: Install uv uses: astral-sh/setup-uv@37802adc94f370d6bfd71619e3f0bf239e1f3b78 # v7.6.0 with: version: "0.11.0" - name: Set up Python run: uv python install - name: Restore Warp kernel cache if: github.event_name != 'merge_group' uses: actions/cache@668228422ae6a00e4ad889ee87cd7109ec5666a7 # v5.0.4 with: path: /actions-runner/.cache/warp key: warp-kernels-gpu-${{ hashFiles('uv.lock', 'newton/**/*.py') }} restore-keys: | warp-kernels-gpu- - name: Check disk space run: df -h - name: Run Tests run: uv run --extra dev --extra torch-cu13 -m newton.tests --no-cache-clear --junit-report-xml rspec.xml --coverage --coverage-xml coverage.xml - name: Check disk space (post-test) if: always() run: df -h - name: Test Summary if: ${{ !cancelled() }} uses: test-summary/action@31493c76ec9e7aa675f1585d3ed6f1da69269a86 # v2.4 with: paths: "rspec.xml" show: "fail" - name: Upload coverage reports to Codecov if: ${{ !cancelled() }} uses: codecov/codecov-action@1af58845a975a7985b0beb0cbe6fbbb71a41dbad # v5.5.3 with: disable_search: true env_vars: AWS_INSTANCE_TYPE files: ./coverage.xml flags: unittests token: ${{ secrets.CODECOV_TOKEN }} - name: Re-run instructions if: failure() run: | # Create error annotations (appear at top of job summary) echo "::error::DO NOT use 'Re-run failed jobs' - the EC2 runner no longer exists and your job will be queued forever." echo "::error::USE 'Re-run all jobs' instead to start a fresh EC2 runner." # Write to job summary (appears in Summary tab) cat >> "$GITHUB_STEP_SUMMARY" << 'EOF' ## ⚠️ How to Re-run This Workflow This workflow uses **ephemeral EC2 runners** that are terminated after each run. | | Option | Result | |---|--------|--------| | ❌ | **Re-run failed jobs** | Runner no longer exists → job queued forever | | ✅ | **Re-run all jobs** | Starts new EC2 runner → tests re-run | EOF # Also print to log for completeness cat << 'EOF' ================================================================================ ⚠️ IMPORTANT: HOW TO RE-RUN THIS WORKFLOW ================================================================================ This workflow uses ephemeral EC2 runners that are terminated after each run. ❌ DO NOT select "Re-run failed jobs" → The runner no longer exists and your job will be queued forever. ✅ DO select "Re-run all jobs" → This will start a new EC2 runner and re-run the tests. ================================================================================ EOF stop-runner: name: Stop self-hosted EC2 runner runs-on: ubuntu-latest permissions: id-token: write contents: read needs: - start-runner - gpu-unit-tests if: always() && needs.start-runner.result != 'skipped' && github.repository == 'newton-physics/newton' steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Configure AWS credentials uses: aws-actions/configure-aws-credentials@8df5847569e6427dd6c4fb1cf565c83acfa8afa7 # v6.0.0 with: aws-region: ${{ env.AWS_REGION }} role-to-assume: ${{ env.AWS_ROLE_ARN }} role-duration-seconds: ${{ env.AWS_ROLE_DURATION }} - name: Stop EC2 runner uses: machulav/ec2-github-runner@a00f575a87f3a96ec6de9413d16eeb828a3cc0a8 # v2.5.2 with: mode: stop github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN }} label: ${{ needs.start-runner.outputs.label }} ec2-instance-id: ${{ needs.start-runner.outputs.ec2-instance-id }} ================================================ FILE: .github/workflows/ci.yml ================================================ name: CI permissions: contents: read env: PYTHONFAULTHANDLER: "1" # Dump tracebacks on fatal signals (SIGSEGV, SIGABRT, etc.) on: workflow_call: workflow_dispatch: push: tags: - v* branches: - main - release-* jobs: minimal-import-test: if: github.event_name != 'push' || github.repository == 'newton-physics/newton' runs-on: ubuntu-latest steps: - name: Harden Runner uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: block allowed-endpoints: > download.pytorch.org:443 files.pythonhosted.org:443 github.com:443 pypi.nvidia.com:443 pypi.org:443 raw.githubusercontent.com:443 release-assets.githubusercontent.com:443 releases.astral.sh:443 - name: Checkout repository uses: actions/checkout@8e8c483db84b4bee98b60c0593521ed34d9990e8 # v6.0.1 - name: Install uv uses: astral-sh/setup-uv@37802adc94f370d6bfd71619e3f0bf239e1f3b78 # v7.6.0 with: version: "0.11.0" - name: Test minimal import (Python 3.10) run: uv run --python 3.10 python -c "import newton; print(f'Newton {newton.__version__} imported successfully')" - name: Test minimal import (Python 3.11) run: uv run --python 3.11 python -c "import newton; print(f'Newton {newton.__version__} imported successfully')" - name: Test minimal import (Python 3.12) run: uv run --python 3.12 python -c "import newton; print(f'Newton {newton.__version__} imported successfully')" - name: Test minimal import (Python 3.13) run: uv run --python 3.13 python -c "import newton; print(f'Newton {newton.__version__} imported successfully')" - name: Test minimal import (Python 3.14) run: uv run --python 3.14 python -c "import newton; print(f'Newton {newton.__version__} imported successfully')" dependency-install-test: needs: minimal-import-test strategy: fail-fast: false matrix: os: [ ubuntu-latest, ubuntu-24.04-arm, windows-latest, macos-latest, ] runs-on: ${{ matrix.os }} steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Checkout repository uses: actions/checkout@8e8c483db84b4bee98b60c0593521ed34d9990e8 # v6.0.1 - name: Install uv uses: astral-sh/setup-uv@37802adc94f370d6bfd71619e3f0bf239e1f3b78 # v7.6.0 with: version: "0.11.0" - name: Test dependency resolution (Python 3.10) run: uv sync --dry-run --python 3.10 --extra dev - name: Test dependency resolution (Python 3.11) run: uv sync --dry-run --python 3.11 --extra dev - name: Test dependency resolution (Python 3.12) run: uv sync --dry-run --python 3.12 --extra dev - name: Test dependency resolution (Python 3.13) run: uv sync --dry-run --python 3.13 --extra dev newton-unittests: needs: dependency-install-test strategy: fail-fast: false matrix: os: [ ubuntu-latest, ubuntu-24.04-arm, windows-latest, macos-latest, ] runs-on: ${{ matrix.os }} env: OS: ${{ matrix.os }} steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Checkout repository uses: actions/checkout@8e8c483db84b4bee98b60c0593521ed34d9990e8 # v6.0.1 - name: Install system dependencies (Ubuntu ARM) if: matrix.os == 'ubuntu-24.04-arm' run: | sudo apt-get update sudo apt-get install -y libx11-dev libxrandr-dev libxinerama-dev libxcursor-dev libxi-dev libgl1-mesa-dev - name: Install uv uses: astral-sh/setup-uv@37802adc94f370d6bfd71619e3f0bf239e1f3b78 # v7.6.0 with: version: "0.11.0" - name: Set up Python uses: actions/setup-python@a309ff8b426b58ec0e2a45f0f869d46889d02405 # v6.2.0 with: python-version-file: ".python-version" - name: Restore Warp kernel cache if: github.event_name != 'merge_group' uses: actions/cache@668228422ae6a00e4ad889ee87cd7109ec5666a7 # v5.0.4 with: path: | ~/.cache/warp ~/Library/Caches/warp ~\AppData\Local\NVIDIA\warp\Cache key: warp-kernels-${{ runner.os }}-${{ runner.arch }}-${{ hashFiles('uv.lock', 'newton/**/*.py') }} restore-keys: | warp-kernels-${{ runner.os }}-${{ runner.arch }}- - name: Run Tests run: uv run --extra dev -m newton.tests --no-cache-clear --junit-report-xml rspec.xml --coverage --coverage-xml coverage.xml - name: Test Summary uses: test-summary/action@31493c76ec9e7aa675f1585d3ed6f1da69269a86 # v2.4 with: paths: "rspec.xml" show: "fail" if: always() - name: Upload test results to Codecov if: ${{ !cancelled() }} uses: codecov/codecov-action@1af58845a975a7985b0beb0cbe6fbbb71a41dbad # v5.5.3 with: files: ./rspec.xml report_type: test_results token: ${{ secrets.CODECOV_TOKEN }} - name: Upload coverage reports to Codecov uses: codecov/codecov-action@1af58845a975a7985b0beb0cbe6fbbb71a41dbad # v5.5.3 with: disable_search: true env_vars: OS files: ./coverage.xml flags: unittests token: ${{ secrets.CODECOV_TOKEN }} ================================================ FILE: .github/workflows/docs-dev.yml ================================================ name: Deploy dev documentation on: push: branches: - main workflow_dispatch: # Ensure only one deployment runs at a time concurrency: group: docs-deploy cancel-in-progress: false jobs: build-and-deploy: runs-on: ubuntu-latest permissions: contents: write steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Checkout repository uses: actions/checkout@8e8c483db84b4bee98b60c0593521ed34d9990e8 # v6.0.1 with: fetch-depth: 0 # Need full history for gh-pages branch - name: Install uv uses: astral-sh/setup-uv@37802adc94f370d6bfd71619e3f0bf239e1f3b78 # v7.6.0 with: version: "0.11.0" - name: Set up Python uses: actions/setup-python@a309ff8b426b58ec0e2a45f0f869d46889d02405 # v6.2.0 with: python-version-file: ".python-version" - name: Install pandoc uses: pandoc/actions/setup@86321b6dd4675f5014c611e05088e10d4939e09e # v1.1.1 - name: Build Sphinx documentation run: uv run --extra docs --extra sim sphinx-build -j auto -b html docs docs/_build/html env: NEWTON_REQUIRE_PANDOC: "1" - name: Deploy to gh-pages /latest/ run: | set -e # Exit on any error git config user.email "actions@github.com" git config user.name "GitHub Actions" # Save built docs and 404 template outside the repo before switching branches mv docs/_build/html /tmp/docs-latest cp docs/_static/gh-pages-404.html /tmp/gh-pages-404.html # Switch to gh-pages branch (check existence first to avoid masking other fetch errors) if git ls-remote --exit-code --heads origin gh-pages > /dev/null 2>&1; then git fetch origin gh-pages:gh-pages git checkout gh-pages else echo "Creating new gh-pages branch" git checkout --orphan gh-pages git rm -rf . || true fi # Remove old /latest/ and replace with new build rm -rf latest mv /tmp/docs-latest latest # Deploy custom 404 page for redirecting old non-versioned URLs cp /tmp/gh-pages-404.html 404.html # Ensure .nojekyll exists touch .nojekyll # Check gh-pages size (warn if approaching GitHub Pages 1GB limit) SIZE_KB=$(du -sk --exclude=.git . | cut -f1) SIZE_MB=$((SIZE_KB / 1024)) echo "Current gh-pages size: ${SIZE_MB}MB" if [ "$SIZE_MB" -gt 800 ]; then echo "::warning::gh-pages branch is ${SIZE_MB}MB, approaching GitHub Pages 1GB limit. Consider pruning old versions." fi # Stage only the files we want deployed (avoid committing build artifacts # like .venv/ that persist after switching branches) git add latest 404.html .nojekyll git diff --cached --quiet || git commit -m "Update dev docs from main@${GITHUB_SHA::8}" git push origin gh-pages ================================================ FILE: .github/workflows/docs-release.yml ================================================ name: Deploy release documentation on: push: tags: - 'v*' workflow_dispatch: inputs: version: description: 'Version to build (e.g., 1.0.0)' required: true type: string # Ensure only one deployment runs at a time concurrency: group: docs-deploy cancel-in-progress: false jobs: build-and-deploy: runs-on: ubuntu-latest permissions: contents: write steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Checkout repository uses: actions/checkout@8e8c483db84b4bee98b60c0593521ed34d9990e8 # v6.0.1 with: fetch-depth: 0 # Need full history for gh-pages branch - name: Set version from tag or input id: version env: EVENT_NAME: ${{ github.event_name }} INPUT_VERSION: ${{ inputs.version }} run: | if [ "$EVENT_NAME" = "push" ]; then VERSION="${GITHUB_REF#refs/tags/v}" else VERSION="$INPUT_VERSION" fi echo "VERSION=$VERSION" >> $GITHUB_OUTPUT echo "Version: $VERSION" # Only deploy docs for stable releases (strict semver X.Y.Z) # Pre-release tags (e.g., 1.0.0-rc.1, 1.0.0-beta) are skipped entirely if [[ "$VERSION" =~ ^[0-9]+\.[0-9]+\.[0-9]+$ ]]; then echo "SHOULD_DEPLOY=true" >> $GITHUB_OUTPUT echo "Stable release detected: will deploy docs" else echo "SHOULD_DEPLOY=false" >> $GITHUB_OUTPUT echo "Pre-release detected: skipping documentation deployment" fi - name: Install uv if: steps.version.outputs.SHOULD_DEPLOY == 'true' uses: astral-sh/setup-uv@37802adc94f370d6bfd71619e3f0bf239e1f3b78 # v7.6.0 with: version: "0.11.0" - name: Set up Python if: steps.version.outputs.SHOULD_DEPLOY == 'true' uses: actions/setup-python@a309ff8b426b58ec0e2a45f0f869d46889d02405 # v6.2.0 with: python-version-file: ".python-version" - name: Install pandoc if: steps.version.outputs.SHOULD_DEPLOY == 'true' uses: pandoc/actions/setup@86321b6dd4675f5014c611e05088e10d4939e09e # v1.1.1 - name: Build Sphinx documentation if: steps.version.outputs.SHOULD_DEPLOY == 'true' run: uv run --extra docs --extra sim sphinx-build -j auto -b html docs docs/_build/html env: NEWTON_REQUIRE_PANDOC: "1" - name: Deploy to gh-pages if: steps.version.outputs.SHOULD_DEPLOY == 'true' env: VERSION: ${{ steps.version.outputs.VERSION }} run: | set -e # Exit on any error git config user.email "actions@github.com" git config user.name "GitHub Actions" # Save built docs and 404 template outside the repo before switching branches mv docs/_build/html /tmp/docs-release cp docs/_static/gh-pages-404.html /tmp/gh-pages-404.html # Switch to gh-pages branch (check existence first to avoid masking other fetch errors) if git ls-remote --exit-code --heads origin gh-pages > /dev/null 2>&1; then git fetch origin gh-pages:gh-pages git checkout gh-pages else echo "Creating new gh-pages branch" git checkout --orphan gh-pages git rm -rf . || true fi # Deploy version directory (remove old if rebuilding) rm -rf "$VERSION" mv /tmp/docs-release "$VERSION" # Update stable/ directory (copy, not symlink - symlinks unreliable on GH Pages) rm -rf stable cp -r "$VERSION" stable # Update switcher.json (script is in the main branch, not gh-pages) # Use origin/main because there's no local main branch on tag-triggered runs git show origin/main:scripts/ci/update_docs_switcher.py > /tmp/update_docs_switcher.py uv run --no-project /tmp/update_docs_switcher.py "$VERSION" rm -f switcher.json.bak # Ensure root index.html redirect exists { echo '' echo '' echo '' echo ' ' echo ' Redirecting to Newton Documentation' echo ' ' echo ' ' echo '' echo '' echo '

Redirecting to Newton Documentation...

' echo '' echo '' } > index.html # Deploy custom 404 page for redirecting old non-versioned URLs cp /tmp/gh-pages-404.html 404.html # Ensure .nojekyll exists touch .nojekyll # Check gh-pages size (warn if approaching GitHub Pages 1GB limit) SIZE_KB=$(du -sk --exclude=.git . | cut -f1) SIZE_MB=$((SIZE_KB / 1024)) echo "Current gh-pages size: ${SIZE_MB}MB" if [ "$SIZE_MB" -gt 800 ]; then echo "::warning::gh-pages branch is ${SIZE_MB}MB, approaching GitHub Pages 1GB limit. Consider pruning old versions." fi # Stage only the files we want deployed (avoid committing build artifacts # like .venv/ that persist after switching branches) git add "$VERSION" stable switcher.json index.html 404.html .nojekyll git diff --cached --quiet || git commit -m "Release v$VERSION documentation" git push origin gh-pages ================================================ FILE: .github/workflows/merge_queue_aws_gpu.yml ================================================ name: Merge Queue - AWS GPU on: merge_group: jobs: run-tests: name: Run GPU Tests if: github.repository == 'newton-physics/newton' uses: ./.github/workflows/aws_gpu_tests.yml with: ref: ${{ github.sha }} secrets: inherit permissions: id-token: write # Required for AWS OIDC authentication in start-runner/stop-runner contents: read # Required for checkout in all jobs ================================================ FILE: .github/workflows/minimum_deps_tests.yml ================================================ name: Minimum Dependency Version Tests on AWS EC2 (Reusable) # Standalone workflow that tests Newton with the lowest compatible versions # of direct PyPI dependencies (as specified by version floors in pyproject.toml). # Dispatched by scheduled_nightly.yml via the workflow_dispatch API. env: AWS_REGION: us-east-2 AWS_INSTANCE_TYPE: g7e.2xlarge AWS_VOLUME_SIZE: 92 AWS_VOLUME_TYPE: gp3 AWS_SECURITY_GROUP_IDS: sg-07807c44e7f2a368a AWS_ROLE_ARN: arn:aws:iam::968945269301:role/newton-physics-newton-ec2-github-runner-role AWS_ROLE_DURATION: 3600 HOME: /actions-runner on: workflow_call: secrets: GH_PERSONAL_ACCESS_TOKEN: required: true CODECOV_TOKEN: required: true workflow_dispatch: jobs: start-runner: name: Start self-hosted EC2 runner if: github.repository == 'newton-physics/newton' runs-on: ubuntu-latest permissions: id-token: write contents: read outputs: label: ${{ steps.start-ec2-runner.outputs.label }} ec2-instance-id: ${{ steps.start-ec2-runner.outputs.ec2-instance-id }} steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Configure AWS credentials uses: aws-actions/configure-aws-credentials@8df5847569e6427dd6c4fb1cf565c83acfa8afa7 # v6.0.0 with: aws-region: ${{ env.AWS_REGION }} role-to-assume: ${{ env.AWS_ROLE_ARN }} role-duration-seconds: ${{ env.AWS_ROLE_DURATION }} - name: Get the latest AWS Deep Learning Base GPU AMI run: | echo "Finding the latest AWS Deep Learning Base GPU AMI..." LATEST_AMI_ID=$(aws ec2 describe-images --region ${{ env.AWS_REGION }} \ --owners amazon \ --filters 'Name=name,Values=Deep Learning Base AMI with Single CUDA (Ubuntu 22.04) ????????' 'Name=state,Values=available' \ --query 'reverse(sort_by(Images, &CreationDate))[:1].ImageId' \ --output text) if [[ -z "$LATEST_AMI_ID" ]]; then echo "❌ No AMI ID found. Exiting." exit 1 fi echo "Latest AMI ID found: $LATEST_AMI_ID" echo "LATEST_AMI_ID=$LATEST_AMI_ID" >> "$GITHUB_ENV" - name: Start EC2 runner id: start-ec2-runner uses: machulav/ec2-github-runner@a00f575a87f3a96ec6de9413d16eeb828a3cc0a8 # v2.5.2 with: mode: start github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN }} ec2-instance-type: ${{ env.AWS_INSTANCE_TYPE }} ec2-volume-size: ${{ env.AWS_VOLUME_SIZE }} ec2-volume-type: ${{ env.AWS_VOLUME_TYPE }} availability-zones-config: > [ {"imageId": "${{ env.LATEST_AMI_ID }}", "subnetId": "subnet-051b9d2e71acf8047", "securityGroupId": "${{ env.AWS_SECURITY_GROUP_IDS }}"}, {"imageId": "${{ env.LATEST_AMI_ID }}", "subnetId": "subnet-0c98bd06abe8ee5eb", "securityGroupId": "${{ env.AWS_SECURITY_GROUP_IDS }}"} ] pre-runner-script: | if [ -d /opt/dlami/nvme ]; then mkdir -p /opt/dlami/nvme/actions-runner/_work mkdir -p /opt/dlami/nvme/actions-runner/.local mkdir -p /opt/dlami/nvme/actions-runner/.cache ln -s /opt/dlami/nvme/actions-runner/_work /actions-runner/_work ln -s /opt/dlami/nvme/actions-runner/.local /actions-runner/.local ln -s /opt/dlami/nvme/actions-runner/.cache /actions-runner/.cache fi aws-resource-tags: > [ {"Key": "Name", "Value": "ec2-github-runner"}, {"Key": "created-by", "Value": "github-actions-newton-role"}, {"Key": "GitHub-Repository", "Value": "${{ github.repository }}"} ] minimum-deps-tests: name: Run Tests with Minimum Dependency Versions needs: start-runner if: ${{ !cancelled() && needs.start-runner.result == 'success' }} runs-on: ${{ needs.start-runner.outputs.label }} timeout-minutes: 60 permissions: contents: read env: PYTHONFAULTHANDLER: "1" steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Checkout repository uses: actions/checkout@8e8c483db84b4bee98b60c0593521ed34d9990e8 # v6.0.1 - name: Install uv uses: astral-sh/setup-uv@37802adc94f370d6bfd71619e3f0bf239e1f3b78 # v7.6.0 with: version: "0.11.0" - name: Set up Python run: uv python install - name: Resolve minimum dependency versions run: | uv lock --resolution lowest-direct echo "Resolved dependency versions:" uv tree --depth 1 - name: Run Tests run: uv run --extra dev -m newton.tests --junit-report-xml rspec.xml - name: Test Summary if: ${{ !cancelled() }} uses: test-summary/action@31493c76ec9e7aa675f1585d3ed6f1da69269a86 # v2.4 with: paths: "rspec.xml" show: "fail" - name: Upload test results to Codecov if: ${{ !cancelled() }} continue-on-error: true uses: codecov/codecov-action@1af58845a975a7985b0beb0cbe6fbbb71a41dbad # v5.5.3 with: disable_search: true files: ./rspec.xml flags: minimum-deps-nightly report_type: test_results token: ${{ secrets.CODECOV_TOKEN }} - name: Re-run instructions if: failure() run: | echo "::error::DO NOT use 'Re-run failed jobs' - the EC2 runner no longer exists and your job will be queued forever." echo "::error::USE 'Re-run all jobs' instead to start a fresh EC2 runner." cat >> "$GITHUB_STEP_SUMMARY" << 'EOF' ## ⚠️ How to Re-run This Workflow This workflow uses **ephemeral EC2 runners** that are terminated after each run. | | Option | Result | |---|--------|--------| | ❌ | **Re-run failed jobs** | Runner no longer exists → job queued forever | | ✅ | **Re-run all jobs** | Starts new EC2 runner → tests re-run | EOF stop-runner: name: Stop self-hosted EC2 runner runs-on: ubuntu-latest permissions: id-token: write contents: read needs: - start-runner - minimum-deps-tests if: always() && needs.start-runner.result != 'skipped' && github.repository == 'newton-physics/newton' steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Configure AWS credentials uses: aws-actions/configure-aws-credentials@8df5847569e6427dd6c4fb1cf565c83acfa8afa7 # v6.0.0 with: aws-region: ${{ env.AWS_REGION }} role-to-assume: ${{ env.AWS_ROLE_ARN }} role-duration-seconds: ${{ env.AWS_ROLE_DURATION }} - name: Stop EC2 runner uses: machulav/ec2-github-runner@a00f575a87f3a96ec6de9413d16eeb828a3cc0a8 # v2.5.2 with: mode: stop github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN }} label: ${{ needs.start-runner.outputs.label }} ec2-instance-id: ${{ needs.start-runner.outputs.ec2-instance-id }} ================================================ FILE: .github/workflows/mujoco_warp_tests.yml ================================================ name: MuJoCo Warp Tests on AWS EC2 (Reusable) # Standalone workflow that tests Newton with the latest mujoco-warp from source. # Not currently dispatched by scheduled_nightly.yml; kept available for manual dispatch/reuse. env: AWS_REGION: us-east-2 AWS_INSTANCE_TYPE: g7e.2xlarge AWS_VOLUME_SIZE: 92 AWS_VOLUME_TYPE: gp3 AWS_SECURITY_GROUP_IDS: sg-07807c44e7f2a368a AWS_ROLE_ARN: arn:aws:iam::968945269301:role/newton-physics-newton-ec2-github-runner-role AWS_ROLE_DURATION: 3600 HOME: /actions-runner on: workflow_call: secrets: GH_PERSONAL_ACCESS_TOKEN: required: true CODECOV_TOKEN: required: true workflow_dispatch: jobs: start-runner: name: Start self-hosted EC2 runner if: github.repository == 'newton-physics/newton' runs-on: ubuntu-latest permissions: id-token: write contents: read outputs: label: ${{ steps.start-ec2-runner.outputs.label }} ec2-instance-id: ${{ steps.start-ec2-runner.outputs.ec2-instance-id }} steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Configure AWS credentials uses: aws-actions/configure-aws-credentials@8df5847569e6427dd6c4fb1cf565c83acfa8afa7 # v6.0.0 with: aws-region: ${{ env.AWS_REGION }} role-to-assume: ${{ env.AWS_ROLE_ARN }} role-duration-seconds: ${{ env.AWS_ROLE_DURATION }} - name: Get the latest AWS Deep Learning Base GPU AMI run: | echo "Finding the latest AWS Deep Learning Base GPU AMI..." LATEST_AMI_ID=$(aws ec2 describe-images --region ${{ env.AWS_REGION }} \ --owners amazon \ --filters 'Name=name,Values=Deep Learning Base AMI with Single CUDA (Ubuntu 22.04) ????????' 'Name=state,Values=available' \ --query 'reverse(sort_by(Images, &CreationDate))[:1].ImageId' \ --output text) if [[ -z "$LATEST_AMI_ID" ]]; then echo "❌ No AMI ID found. Exiting." exit 1 fi echo "Latest AMI ID found: $LATEST_AMI_ID" echo "LATEST_AMI_ID=$LATEST_AMI_ID" >> "$GITHUB_ENV" - name: Start EC2 runner id: start-ec2-runner uses: machulav/ec2-github-runner@a00f575a87f3a96ec6de9413d16eeb828a3cc0a8 # v2.5.2 with: mode: start github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN }} ec2-instance-type: ${{ env.AWS_INSTANCE_TYPE }} ec2-volume-size: ${{ env.AWS_VOLUME_SIZE }} ec2-volume-type: ${{ env.AWS_VOLUME_TYPE }} availability-zones-config: > [ {"imageId": "${{ env.LATEST_AMI_ID }}", "subnetId": "subnet-051b9d2e71acf8047", "securityGroupId": "${{ env.AWS_SECURITY_GROUP_IDS }}"}, {"imageId": "${{ env.LATEST_AMI_ID }}", "subnetId": "subnet-0c98bd06abe8ee5eb", "securityGroupId": "${{ env.AWS_SECURITY_GROUP_IDS }}"} ] pre-runner-script: | if [ -d /opt/dlami/nvme ]; then mkdir -p /opt/dlami/nvme/actions-runner/_work mkdir -p /opt/dlami/nvme/actions-runner/.local mkdir -p /opt/dlami/nvme/actions-runner/.cache ln -s /opt/dlami/nvme/actions-runner/_work /actions-runner/_work ln -s /opt/dlami/nvme/actions-runner/.local /actions-runner/.local ln -s /opt/dlami/nvme/actions-runner/.cache /actions-runner/.cache fi aws-resource-tags: > [ {"Key": "Name", "Value": "ec2-github-runner"}, {"Key": "created-by", "Value": "github-actions-newton-role"}, {"Key": "GitHub-Repository", "Value": "${{ github.repository }}"} ] mujoco-warp-tests: name: Run Tests with MuJoCo Warp from Source needs: start-runner if: ${{ !cancelled() && needs.start-runner.result == 'success' }} runs-on: ${{ needs.start-runner.outputs.label }} timeout-minutes: 60 permissions: contents: read env: PYTHONFAULTHANDLER: "1" steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Checkout repository uses: actions/checkout@8e8c483db84b4bee98b60c0593521ed34d9990e8 # v6.0.1 - name: Install uv uses: astral-sh/setup-uv@37802adc94f370d6bfd71619e3f0bf239e1f3b78 # v7.6.0 with: version: "0.11.0" - name: Set up Python run: uv python install - name: Install Newton and override mujoco-warp with source build run: | uv sync --extra dev --extra torch-cu13 uv pip install --reinstall-package mujoco-warp "mujoco-warp @ git+https://github.com/google-deepmind/mujoco_warp.git" - name: Print mujoco-warp version info run: uv run --no-sync python -c "import mujoco_warp; print('mujoco_warp version:', getattr(mujoco_warp, '__version__', 'unknown'))" - name: Check disk space run: df -h - name: Run Tests run: uv run --no-sync -m newton.tests --junit-report-xml rspec.xml - name: Check disk space (post-test) if: always() run: df -h - name: Test Summary if: ${{ !cancelled() }} uses: test-summary/action@31493c76ec9e7aa675f1585d3ed6f1da69269a86 # v2.4 with: paths: "rspec.xml" show: "fail" - name: Upload test results to Codecov if: ${{ !cancelled() }} continue-on-error: true uses: codecov/codecov-action@1af58845a975a7985b0beb0cbe6fbbb71a41dbad # v5.5.3 with: disable_search: true files: ./rspec.xml flags: mujoco-warp-nightly report_type: test_results token: ${{ secrets.CODECOV_TOKEN }} - name: Re-run instructions if: failure() run: | echo "::error::DO NOT use 'Re-run failed jobs' - the EC2 runner no longer exists and your job will be queued forever." echo "::error::USE 'Re-run all jobs' instead to start a fresh EC2 runner." cat >> "$GITHUB_STEP_SUMMARY" << 'EOF' ## ⚠️ How to Re-run This Workflow This workflow uses **ephemeral EC2 runners** that are terminated after each run. | | Option | Result | |---|--------|--------| | ❌ | **Re-run failed jobs** | Runner no longer exists → job queued forever | | ✅ | **Re-run all jobs** | Starts new EC2 runner → tests re-run | EOF stop-runner: name: Stop self-hosted EC2 runner runs-on: ubuntu-latest permissions: id-token: write contents: read needs: - start-runner - mujoco-warp-tests if: always() && needs.start-runner.result != 'skipped' && github.repository == 'newton-physics/newton' steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Configure AWS credentials uses: aws-actions/configure-aws-credentials@8df5847569e6427dd6c4fb1cf565c83acfa8afa7 # v6.0.0 with: aws-region: ${{ env.AWS_REGION }} role-to-assume: ${{ env.AWS_ROLE_ARN }} role-duration-seconds: ${{ env.AWS_ROLE_DURATION }} - name: Stop EC2 runner uses: machulav/ec2-github-runner@a00f575a87f3a96ec6de9413d16eeb828a3cc0a8 # v2.5.2 with: mode: stop github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN }} label: ${{ needs.start-runner.outputs.label }} ec2-instance-id: ${{ needs.start-runner.outputs.ec2-instance-id }} ================================================ FILE: .github/workflows/pr.yml ================================================ name: Pull Request permissions: contents: read on: merge_group: pull_request: branches: - main - "release-*" concurrency: group: ${{ github.workflow }}-on-${{ github.event_name }}-from-${{ github.ref_name }} cancel-in-progress: true jobs: check-lockfile: runs-on: ubuntu-latest steps: - name: Harden Runner uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: block allowed-endpoints: > download.pytorch.org:443 files.pythonhosted.org:443 github.com:443 pypi.nvidia.com:443 pypi.org:443 raw.githubusercontent.com:443 release-assets.githubusercontent.com:443 releases.astral.sh:443 - name: Checkout repository uses: actions/checkout@8e8c483db84b4bee98b60c0593521ed34d9990e8 # v6.0.1 - name: Install uv uses: astral-sh/setup-uv@37802adc94f370d6bfd71619e3f0bf239e1f3b78 # v7.6.0 with: version: "0.11.0" - name: Set up Python uses: actions/setup-python@a309ff8b426b58ec0e2a45f0f869d46889d02405 # v6.2.0 with: python-version-file: ".python-version" - name: Check uv lockfile run: uv lock --check run-newton-tests: uses: ./.github/workflows/ci.yml secrets: inherit pull-request-docs: runs-on: ubuntu-latest steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Checkout repository uses: actions/checkout@8e8c483db84b4bee98b60c0593521ed34d9990e8 # v6.0.1 - name: Install uv uses: astral-sh/setup-uv@37802adc94f370d6bfd71619e3f0bf239e1f3b78 # v7.6.0 with: version: "0.11.0" - name: "Set up Python" uses: actions/setup-python@a309ff8b426b58ec0e2a45f0f869d46889d02405 # v6.2.0 with: python-version-file: ".python-version" - name: Install pandoc uses: pandoc/actions/setup@86321b6dd4675f5014c611e05088e10d4939e09e # v1.1.1 - name: Build Sphinx documentation run: uv run --extra docs --extra sim sphinx-build -j auto -W -b html docs docs/_build/html env: NEWTON_REQUIRE_PANDOC: "1" - name: Verify API docs are up-to-date run: | git diff --exit-code docs/api/ || { echo "::error::API docs are stale. Run 'python docs/generate_api.py' and commit the changes." exit 1 } - name: Run Sphinx doctests run: uv run --extra docs --extra sim sphinx-build -j auto -W -b doctest docs docs/_build/doctest ================================================ FILE: .github/workflows/pr_closed.yml ================================================ name: Cancel workflows on PR close on: pull_request_target: types: [closed] jobs: cancel-pr-workflows: name: Cancel in-progress PR workflows runs-on: ubuntu-latest permissions: actions: write timeout-minutes: 3 steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Cancel in-progress runs for this PR env: GH_TOKEN: ${{ github.token }} GH_REPO: ${{ github.repository }} HEAD_BRANCH: ${{ github.event.pull_request.head.ref }} PR_NUMBER: ${{ github.event.pull_request.number }} CURRENT_RUN: ${{ github.run_id }} run: | echo "PR #$PR_NUMBER closed, cancelling workflows for branch: $HEAD_BRANCH" # Cancel all in-progress and queued runs on this PR's head branch (except this one) for status in in_progress queued; do gh run list --branch "$HEAD_BRANCH" --status "$status" --json databaseId --jq '.[].databaseId' \ | while read -r run_id; do if [ "$run_id" != "$CURRENT_RUN" ]; then echo "Cancelling run $run_id" if ! gh run cancel "$run_id"; then echo "Warning: failed to cancel run $run_id" >&2 fi fi done done ================================================ FILE: .github/workflows/pr_license_check.yml ================================================ name: License Check permissions: contents: read pull-requests: read on: merge_group: pull_request: branches: - main - "release-*" # Cancels in-progress runs of this workflow for the same pull request, # but allows parallel runs for pushes to the main branch. concurrency: group: ${{ github.workflow }}-${{ github.head_ref }} cancel-in-progress: true jobs: check-licenses: runs-on: ubuntu-latest steps: - name: Harden Runner uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: block allowed-endpoints: > api.github.com:443 github.com:443 proxy.golang.org:443 - name: Checkout repository uses: actions/checkout@8e8c483db84b4bee98b60c0593521ed34d9990e8 # v6.0.1 - name: Check code license headers (Apache-2.0) uses: apache/skywalking-eyes/header@61275cc80d0798a405cb070f7d3a8aaf7cf2c2c1 # v0.8.0 - name: Check docs license headers (CC-BY-4.0) uses: apache/skywalking-eyes/header@61275cc80d0798a405cb070f7d3a8aaf7cf2c2c1 # v0.8.0 with: config: .licenserc-docs.yaml - name: Check notebook license headers (CC-BY-4.0) run: | status=0 for nb in $(find docs -name '*.ipynb' -not -path '*/.*' -not -path '*/_build/*'); do if ! grep -q 'SPDX-License-Identifier: CC-BY-4.0' "$nb"; then echo "ERROR: $nb missing CC-BY-4.0 SPDX header" status=1 fi done exit $status ================================================ FILE: .github/workflows/pr_target_aws_gpu_benchmarks.yml ================================================ name: Pull Request - AWS GPU Benchmarks on: pull_request_target: concurrency: group: ${{ github.workflow }}-pr-${{ github.event.pull_request.number }} cancel-in-progress: true jobs: check-author-membership: name: Check Author Membership runs-on: ubuntu-latest permissions: {} outputs: membership_status: ${{ steps.check_org.outputs.membership_status }} steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Check user's organization membership id: check_org run: | ASSOCIATION="${{ github.event.pull_request.author_association }}" echo "Author's association with the repository: ${ASSOCIATION}" if [[ "${ASSOCIATION}" == "MEMBER" || "${ASSOCIATION}" == "OWNER" || "${ASSOCIATION}" == "COLLABORATOR" ]]; then echo "Author is a recognized member, owner, or collaborator." echo "membership_status=CONFIRMED_MEMBER" >> "$GITHUB_OUTPUT" else # Set the output for other jobs to use echo "membership_status=NOT_MEMBER" >> "$GITHUB_OUTPUT" # Print a message explaining the status and its impact on workflows. echo "--------------------------------------------------------------------------------" >&2 echo "Thank you for your contribution!" >&2 echo "This is the expected status for community contributors. Certain automated" >&2 echo "workflows are reserved for verified organization members." >&2 echo "" >&2 echo "--------------------------------------------------------------------------------" >&2 echo "❓ Are you a member of the 'newton-physics' organization and believe this is an error?" >&2 echo "" >&2 echo "This can happen if your organization membership is set to 'Private'. To fix this," >&2 echo "please make your membership 'Public' to enable all workflow triggers:" >&2 echo "" >&2 echo "1. Go to the organization's People page: https://github.com/orgs/newton-physics/people" >&2 echo "2. Find your username in the list." >&2 echo "3. Click the dropdown next to your name and change your visibility from 'Private' to 'Public'." >&2 echo "" >&2 echo "After updating your visibility, push a new commit to this PR to re-run the check." >&2 echo "--------------------------------------------------------------------------------" >&2 # Surface warnings as visible annotations (yellow banners in job view) echo "::warning::This PR requires manual approval before GPU benchmarks can run (author is not a recognized org member)." echo "::warning::If you are a newton-physics org member with private membership, make it public at https://github.com/orgs/newton-physics/people" # Write to job summary (appears in Summary tab) cat >> "$GITHUB_STEP_SUMMARY" << 'EOF' ## ⚠️ Manual Approval Required This PR was authored by an external contributor. GPU benchmarks require manual approval from a maintainer before they can run. ### Are you a newton-physics org member? If your membership is set to **Private**, the workflow cannot detect it. To fix: 1. Go to [newton-physics People](https://github.com/orgs/newton-physics/people) 2. Find your username and change visibility from **Private** to **Public** 3. Push a new commit to re-trigger the check EOF fi require-approval: name: Require Manual Approval for External PRs runs-on: ubuntu-latest permissions: deployments: write # Required for creating deployment record when using environment needs: check-author-membership if: needs.check-author-membership.outputs.membership_status != 'CONFIRMED_MEMBER' environment: name: external-pr-approval url: ${{ github.event.pull_request.html_url }} steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Approval granted run: echo "Manual approval granted for external PR" run-gpu-benchmarks: name: Run GPU Benchmarks needs: - check-author-membership - require-approval if: github.repository == 'newton-physics/newton' && (!cancelled()) uses: ./.github/workflows/aws_gpu_benchmarks.yml with: ref: ${{ github.event.pull_request.head.sha }} base_ref: ${{ github.event.pull_request.base.sha }} secrets: inherit permissions: id-token: write # Required for AWS OIDC authentication in start-runner/stop-runner contents: read # Required for checkout in all jobs ================================================ FILE: .github/workflows/pr_target_aws_gpu_tests.yml ================================================ name: Pull Request - AWS GPU Tests on: pull_request_target: concurrency: group: ${{ github.workflow }}-pr-${{ github.event.pull_request.number }} cancel-in-progress: true jobs: check-author-membership: name: Check Author Membership runs-on: ubuntu-latest permissions: {} outputs: membership_status: ${{ steps.check_org.outputs.membership_status }} steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Check user's organization membership id: check_org run: | ASSOCIATION="${{ github.event.pull_request.author_association }}" echo "Author's association with the repository: ${ASSOCIATION}" if [[ "${ASSOCIATION}" == "MEMBER" || "${ASSOCIATION}" == "OWNER" || "${ASSOCIATION}" == "COLLABORATOR" ]]; then echo "Author is a recognized member, owner, or collaborator." echo "membership_status=CONFIRMED_MEMBER" >> "$GITHUB_OUTPUT" else # Set the output for other jobs to use echo "membership_status=NOT_MEMBER" >> "$GITHUB_OUTPUT" # Print a message explaining the status and its impact on workflows. echo "--------------------------------------------------------------------------------" >&2 echo "Thank you for your contribution!" >&2 echo "This is the expected status for community contributors. Certain automated" >&2 echo "workflows are reserved for verified organization members." >&2 echo "" >&2 echo "--------------------------------------------------------------------------------" >&2 echo "❓ Are you a member of the 'newton-physics' organization and believe this is an error?" >&2 echo "" >&2 echo "This can happen if your organization membership is set to 'Private'. To fix this," >&2 echo "please make your membership 'Public' to enable all workflow triggers:" >&2 echo "" >&2 echo "1. Go to the organization's People page: https://github.com/orgs/newton-physics/people" >&2 echo "2. Find your username in the list." >&2 echo "3. Click the dropdown next to your name and change your visibility from 'Private' to 'Public'." >&2 echo "" >&2 echo "After updating your visibility, push a new commit to this PR to re-run the check." >&2 echo "--------------------------------------------------------------------------------" >&2 # Surface warnings as visible annotations (yellow banners in job view) echo "::warning::This PR requires manual approval before GPU tests can run (author is not a recognized org member)." echo "::warning::If you are a newton-physics org member with private membership, make it public at https://github.com/orgs/newton-physics/people" # Write to job summary (appears in Summary tab) cat >> "$GITHUB_STEP_SUMMARY" << 'EOF' ## ⚠️ Manual Approval Required This PR was authored by an external contributor. GPU tests require manual approval from a maintainer before they can run. ### Are you a newton-physics org member? If your membership is set to **Private**, the workflow cannot detect it. To fix: 1. Go to [newton-physics People](https://github.com/orgs/newton-physics/people) 2. Find your username and change visibility from **Private** to **Public** 3. Push a new commit to re-trigger the check EOF fi require-approval: name: Require Manual Approval for External PRs runs-on: ubuntu-latest permissions: deployments: write # Required for creating deployment record when using environment needs: check-author-membership if: needs.check-author-membership.outputs.membership_status != 'CONFIRMED_MEMBER' environment: name: external-pr-approval url: ${{ github.event.pull_request.html_url }} steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Approval granted run: echo "Manual approval granted for external PR" run-gpu-tests: name: Run GPU Tests needs: - check-author-membership - require-approval if: github.repository == 'newton-physics/newton' && (!cancelled()) uses: ./.github/workflows/aws_gpu_tests.yml with: ref: ${{ github.event.pull_request.head.sha }} secrets: inherit permissions: id-token: write # Required for AWS OIDC authentication in start-runner/stop-runner contents: read # Required for checkout in all jobs ================================================ FILE: .github/workflows/push_aws_gpu.yml ================================================ name: Push - AWS GPU # This workflow triggers GPU tests for pushes to main/release branches. # It replaces the old push_aws_gpu_tests.yml workflow. # Uses reusable workflows: # - aws_gpu_tests.yml on: push: paths-ignore: - "docs/**" - "**.md" jobs: run-tests: if: github.repository == 'newton-physics/newton' uses: ./.github/workflows/aws_gpu_tests.yml secrets: inherit permissions: id-token: write # Required for AWS OIDC authentication in start-runner/stop-runner contents: read # Required for checkout in all jobs ================================================ FILE: .github/workflows/release.yml ================================================ name: Release # This workflow runs when a tag is pushed. # The publish-to-pypi job requires manual approval via the 'pypi' environment protection rules # configured in Settings > Environments > pypi. on: push: tags: - '*' jobs: build: name: Build distribution runs-on: ubuntu-latest permissions: contents: read actions: write steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - uses: actions/checkout@8e8c483db84b4bee98b60c0593521ed34d9990e8 # v6.0.1 with: persist-credentials: false - name: Install uv uses: astral-sh/setup-uv@37802adc94f370d6bfd71619e3f0bf239e1f3b78 # v7.6.0 with: version: "0.11.0" - name: Set up Python run: uv python install - name: Build a binary wheel run: uv build --wheel - name: Store the distribution packages uses: actions/upload-artifact@b7c566a772e6b6bfb58ed0dc250532a479d7789f # v6.0.0 with: name: python-package-distributions path: dist/ publish-to-pypi: name: Publish Python distribution to PyPI if: github.repository == 'newton-physics/newton' needs: - build runs-on: ubuntu-latest environment: name: pypi url: https://pypi.org/p/newton permissions: id-token: write steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Download wheel and source tarball uses: actions/download-artifact@37930b1c2abaa49bbe596cd826c3c89aef350131 # v7.0.0 with: name: python-package-distributions path: dist/ - name: Publish distribution to PyPI uses: pypa/gh-action-pypi-publish@ed0c53931b1dc9bd32cbe73a98c7f6766f8a527e # v1.13.0 create-github-release: name: Create GitHub Release if: github.repository == 'newton-physics/newton' needs: - build runs-on: ubuntu-latest permissions: contents: write steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - uses: actions/checkout@8e8c483db84b4bee98b60c0593521ed34d9990e8 # v6.0.1 - name: Download wheel and source tarball uses: actions/download-artifact@37930b1c2abaa49bbe596cd826c3c89aef350131 # v7.0.0 with: name: python-package-distributions path: dist/ - name: Create GitHub Release run: | gh release create ${{ github.ref_name }} \ --draft \ --title "Release ${{ github.ref_name }}" \ dist/* env: GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} ================================================ FILE: .github/workflows/scheduled_nightly.yml ================================================ name: Scheduled Nightly Tests # Orchestrator that dispatches all nightly test suites sequentially. # Each sub-workflow is triggered via the workflow_dispatch REST API and # polled to completion before the next is started, ensuring only one # EC2 instance is active at a time. Per-workflow history is preserved # as separate workflow runs. One group's failure does not block # subsequent groups. on: schedule: - cron: '0 9 * * *' # Daily at 9 AM UTC (1 AM PST / 2 AM PDT) workflow_dispatch: jobs: check-warp-update: name: Check for new warp-lang nightly build if: github.repository == 'newton-physics/newton' runs-on: ubuntu-latest permissions: contents: read outputs: warp-updated: ${{ steps.check-update.outputs.warp-updated }} steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Checkout repository uses: actions/checkout@8e8c483db84b4bee98b60c0593521ed34d9990e8 # v6.0.1 - name: Install uv uses: astral-sh/setup-uv@37802adc94f370d6bfd71619e3f0bf239e1f3b78 # v7.6.0 with: version: "0.11.0" - name: Update warp-lang in lock file run: uv lock -P warp-lang --prerelease allow - name: Check if warp-lang version changed id: check-update run: | if git diff --quiet uv.lock; then echo "No new warp-lang nightly build detected" echo "warp-updated=false" >> "$GITHUB_OUTPUT" else echo "New warp-lang nightly build detected!" echo "warp-updated=true" >> "$GITHUB_OUTPUT" echo "Current warp-lang dependency tree:" uv tree --package warp-lang fi run-nightly-tests: name: Run nightly test suites needs: [check-warp-update] if: ${{ !cancelled() && github.repository == 'newton-physics/newton' }} runs-on: ubuntu-latest timeout-minutes: 180 # Budget for sequential dispatch+poll of all sub-workflows (typical total ~90 min) permissions: actions: write contents: read outputs: gpu-tests-conclusion: ${{ steps.gpu-tests.outputs.conclusion }} gpu-tests-url: ${{ steps.gpu-tests.outputs.run-url }} minimum-deps-tests-conclusion: ${{ steps.minimum-deps-tests.outputs.conclusion }} minimum-deps-tests-url: ${{ steps.minimum-deps-tests.outputs.run-url }} warp-nightly-tests-conclusion: ${{ steps.warp-nightly-tests.outputs.conclusion }} warp-nightly-tests-url: ${{ steps.warp-nightly-tests.outputs.run-url }} env: GH_TOKEN: ${{ github.token }} REPO: ${{ github.repository }} REF: ${{ github.ref }} steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Checkout repository uses: actions/checkout@8e8c483db84b4bee98b60c0593521ed34d9990e8 # v6.0.1 - name: Install uv uses: astral-sh/setup-uv@37802adc94f370d6bfd71619e3f0bf239e1f3b78 # v7.6.0 with: version: "0.11.0" - name: Set up Python run: uv python install - name: Dispatch and wait for GPU tests id: gpu-tests run: uv run --no-project scripts/ci/dispatch_workflow_and_wait.py aws_gpu_tests.yml -f "inputs[instance-type]=g7e.12xlarge" - name: Dispatch and wait for Minimum Deps tests id: minimum-deps-tests run: uv run --no-project scripts/ci/dispatch_workflow_and_wait.py minimum_deps_tests.yml - name: Dispatch and wait for Warp Nightly tests id: warp-nightly-tests if: needs.check-warp-update.result == 'success' && needs.check-warp-update.outputs.warp-updated == 'true' run: uv run --no-project scripts/ci/dispatch_workflow_and_wait.py warp_nightly_tests.yml notify-on-failure: name: Notify on failure needs: [run-nightly-tests] if: | !cancelled() && ((needs.run-nightly-tests.outputs.gpu-tests-conclusion != '' && needs.run-nightly-tests.outputs.gpu-tests-conclusion != 'success') || (needs.run-nightly-tests.outputs.minimum-deps-tests-conclusion != '' && needs.run-nightly-tests.outputs.minimum-deps-tests-conclusion != 'success') || (needs.run-nightly-tests.outputs.warp-nightly-tests-conclusion != '' && needs.run-nightly-tests.outputs.warp-nightly-tests-conclusion != 'success')) runs-on: ubuntu-latest permissions: issues: write contents: read steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: File or update GitHub issue uses: actions/github-script@ed597411d8f924073f98dfc5c65a23a2325f34cd # v8.0.0 with: script: | const suites = [ { name: 'Multi-GPU tests', workflow: 'aws_gpu_tests.yml', conclusion: '${{ needs.run-nightly-tests.outputs.gpu-tests-conclusion }}', url: '${{ needs.run-nightly-tests.outputs.gpu-tests-url }}' }, { name: 'Minimum deps tests', workflow: 'minimum_deps_tests.yml', conclusion: '${{ needs.run-nightly-tests.outputs.minimum-deps-tests-conclusion }}', url: '${{ needs.run-nightly-tests.outputs.minimum-deps-tests-url }}' }, { name: 'Warp nightly tests', workflow: 'warp_nightly_tests.yml', conclusion: '${{ needs.run-nightly-tests.outputs.warp-nightly-tests-conclusion }}', url: '${{ needs.run-nightly-tests.outputs.warp-nightly-tests-url }}' } ]; // Fetch recent run history to show pass/fail trend in the issue table // (default branch only, excludes cancelled runs) async function getHistory(workflowFile) { try { const { data } = await github.rest.actions.listWorkflowRuns({ owner: context.repo.owner, repo: context.repo.repo, workflow_id: workflowFile, branch: context.payload.repository?.default_branch || 'main', per_page: 10, status: 'completed', exclude_pull_requests: true }); const runs = data.workflow_runs .filter(r => r.conclusion !== 'cancelled') .slice(0, 5); return runs.map(r => r.conclusion === 'success' ? '✅' : '❌').join(''); } catch (error) { core.warning(`Failed to fetch history for ${workflowFile}: ${error.message}`); return ''; } } const failed = []; const rows = []; for (const suite of suites) { const history = await getHistory(suite.workflow); const recentCol = history || '—'; if (!suite.conclusion) { rows.push(`| ${suite.name} | ${recentCol} | ⏭️ Skipped | |`); } else if (suite.conclusion === 'success') { rows.push(`| ${suite.name} | ${recentCol} | ✅ Passed | [View logs](${suite.url}) |`); } else { rows.push(`| ${suite.name} | ${recentCol} | ❌ Failed | [View logs](${suite.url}) |`); failed.push(suite.name); } } const labels = ['stability', 'testing']; const orchestratorUrl = `${context.serverUrl}/${context.repo.owner}/${context.repo.repo}/actions/runs/${context.runId}`; const failedList = failed.join(', '); const table = [ '| Test Suite | Recent | Status | Logs |', '|---|---|---|---|', ...rows ].join('\n'); // Search for an existing open nightly failure issue to update // instead of creating duplicates const { data: candidates } = await github.rest.issues.listForRepo({ owner: context.repo.owner, repo: context.repo.repo, labels: labels.join(','), state: 'open', per_page: 100 }); const existing = candidates.find(i => i.title.startsWith('Nightly failure')); try { // If an existing issue is found, add a comment; otherwise // create a new one with today's date if (existing) { await github.rest.issues.createComment({ owner: context.repo.owner, repo: context.repo.repo, issue_number: existing.number, body: [ `@newton-physics/newton-ci-notify Nightly tests are still failing.`, ``, table, ``, `**Orchestrator run:** [View](${orchestratorUrl})` ].join('\n') }); } else { const date = new Date().toISOString().slice(0, 10); await github.rest.issues.create({ owner: context.repo.owner, repo: context.repo.repo, title: `Nightly failure (${date}): ${failedList}`, body: [ `@newton-physics/newton-ci-notify`, ``, `The scheduled nightly workflow failed.`, ``, table, ``, `**Orchestrator run:** [View](${orchestratorUrl})` ].join('\n'), labels: labels }); } } catch (error) { core.error(`Failed to create/update notification issue: ${error.message}`); core.error(`Test suites that failed: ${failedList}`); throw error; } ================================================ FILE: .github/workflows/warp_nightly_tests.yml ================================================ name: Warp Nightly Build Tests on AWS EC2 (Reusable) # Standalone workflow that tests Newton with the latest nightly warp-lang builds. # Called by scheduled_nightly.yml (only when a new warp-lang nightly is detected). env: AWS_REGION: us-east-2 AWS_INSTANCE_TYPE: g7e.2xlarge AWS_VOLUME_SIZE: 92 AWS_VOLUME_TYPE: gp3 AWS_SECURITY_GROUP_IDS: sg-07807c44e7f2a368a AWS_ROLE_ARN: arn:aws:iam::968945269301:role/newton-physics-newton-ec2-github-runner-role AWS_ROLE_DURATION: 3600 HOME: /actions-runner on: workflow_call: secrets: GH_PERSONAL_ACCESS_TOKEN: required: true CODECOV_TOKEN: required: true workflow_dispatch: jobs: start-runner: name: Start self-hosted EC2 runner if: github.repository == 'newton-physics/newton' runs-on: ubuntu-latest permissions: id-token: write contents: read outputs: label: ${{ steps.start-ec2-runner.outputs.label }} ec2-instance-id: ${{ steps.start-ec2-runner.outputs.ec2-instance-id }} steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Configure AWS credentials uses: aws-actions/configure-aws-credentials@8df5847569e6427dd6c4fb1cf565c83acfa8afa7 # v6.0.0 with: aws-region: ${{ env.AWS_REGION }} role-to-assume: ${{ env.AWS_ROLE_ARN }} role-duration-seconds: ${{ env.AWS_ROLE_DURATION }} - name: Get the latest AWS Deep Learning Base GPU AMI run: | echo "Finding the latest AWS Deep Learning Base GPU AMI..." LATEST_AMI_ID=$(aws ec2 describe-images --region ${{ env.AWS_REGION }} \ --owners amazon \ --filters 'Name=name,Values=Deep Learning Base AMI with Single CUDA (Ubuntu 22.04) ????????' 'Name=state,Values=available' \ --query 'reverse(sort_by(Images, &CreationDate))[:1].ImageId' \ --output text) if [[ -z "$LATEST_AMI_ID" ]]; then echo "❌ No AMI ID found. Exiting." exit 1 fi echo "Latest AMI ID found: $LATEST_AMI_ID" echo "LATEST_AMI_ID=$LATEST_AMI_ID" >> "$GITHUB_ENV" - name: Start EC2 runner id: start-ec2-runner uses: machulav/ec2-github-runner@a00f575a87f3a96ec6de9413d16eeb828a3cc0a8 # v2.5.2 with: mode: start github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN }} ec2-instance-type: ${{ env.AWS_INSTANCE_TYPE }} ec2-volume-size: ${{ env.AWS_VOLUME_SIZE }} ec2-volume-type: ${{ env.AWS_VOLUME_TYPE }} availability-zones-config: > [ {"imageId": "${{ env.LATEST_AMI_ID }}", "subnetId": "subnet-051b9d2e71acf8047", "securityGroupId": "${{ env.AWS_SECURITY_GROUP_IDS }}"}, {"imageId": "${{ env.LATEST_AMI_ID }}", "subnetId": "subnet-0c98bd06abe8ee5eb", "securityGroupId": "${{ env.AWS_SECURITY_GROUP_IDS }}"} ] pre-runner-script: | if [ -d /opt/dlami/nvme ]; then mkdir -p /opt/dlami/nvme/actions-runner/_work mkdir -p /opt/dlami/nvme/actions-runner/.local mkdir -p /opt/dlami/nvme/actions-runner/.cache ln -s /opt/dlami/nvme/actions-runner/_work /actions-runner/_work ln -s /opt/dlami/nvme/actions-runner/.local /actions-runner/.local ln -s /opt/dlami/nvme/actions-runner/.cache /actions-runner/.cache fi aws-resource-tags: > [ {"Key": "Name", "Value": "ec2-github-runner"}, {"Key": "created-by", "Value": "github-actions-newton-role"}, {"Key": "GitHub-Repository", "Value": "${{ github.repository }}"} ] warp-nightly-tests: name: Run Tests with Warp Nightly Build needs: start-runner if: ${{ !cancelled() && needs.start-runner.result == 'success' }} runs-on: ${{ needs.start-runner.outputs.label }} timeout-minutes: 60 permissions: contents: read env: PYTHONFAULTHANDLER: "1" steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Checkout repository uses: actions/checkout@8e8c483db84b4bee98b60c0593521ed34d9990e8 # v6.0.1 - name: Install uv uses: astral-sh/setup-uv@37802adc94f370d6bfd71619e3f0bf239e1f3b78 # v7.6.0 with: version: "0.11.0" - name: Set up Python run: uv python install - name: Update lock file with latest warp-lang nightly build run: uv lock -P warp-lang --prerelease allow - name: Check disk space run: df -h - name: Run Tests run: uv run --extra dev --extra torch-cu13 -m newton.tests --junit-report-xml rspec.xml - name: Check disk space (post-test) if: always() run: df -h - name: Test Summary if: ${{ !cancelled() }} uses: test-summary/action@31493c76ec9e7aa675f1585d3ed6f1da69269a86 # v2.4 with: paths: "rspec.xml" show: "fail" - name: Upload test results to Codecov if: ${{ !cancelled() }} continue-on-error: true uses: codecov/codecov-action@1af58845a975a7985b0beb0cbe6fbbb71a41dbad # v5.5.3 with: disable_search: true files: ./rspec.xml flags: warp-nightly report_type: test_results token: ${{ secrets.CODECOV_TOKEN }} - name: Re-run instructions if: failure() run: | echo "::error::DO NOT use 'Re-run failed jobs' - the EC2 runner no longer exists and your job will be queued forever." echo "::error::USE 'Re-run all jobs' instead to start a fresh EC2 runner." cat >> "$GITHUB_STEP_SUMMARY" << 'EOF' ## ⚠️ How to Re-run This Workflow This workflow uses **ephemeral EC2 runners** that are terminated after each run. | | Option | Result | |---|--------|--------| | ❌ | **Re-run failed jobs** | Runner no longer exists → job queued forever | | ✅ | **Re-run all jobs** | Starts new EC2 runner → tests re-run | EOF stop-runner: name: Stop self-hosted EC2 runner runs-on: ubuntu-latest permissions: id-token: write contents: read needs: - start-runner - warp-nightly-tests if: always() && needs.start-runner.result != 'skipped' && github.repository == 'newton-physics/newton' steps: - name: Harden the runner (Audit all outbound calls) uses: step-security/harden-runner@fa2e9d605c4eeb9fcad4c99c224cee0c6c7f3594 # v2.16.0 with: egress-policy: audit - name: Configure AWS credentials uses: aws-actions/configure-aws-credentials@8df5847569e6427dd6c4fb1cf565c83acfa8afa7 # v6.0.0 with: aws-region: ${{ env.AWS_REGION }} role-to-assume: ${{ env.AWS_ROLE_ARN }} role-duration-seconds: ${{ env.AWS_ROLE_DURATION }} - name: Stop EC2 runner uses: machulav/ec2-github-runner@a00f575a87f3a96ec6de9413d16eeb828a3cc0a8 # v2.5.2 with: mode: stop github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN }} label: ${{ needs.start-runner.outputs.label }} ec2-instance-id: ${{ needs.start-runner.outputs.ec2-instance-id }} ================================================ FILE: .gitignore ================================================ # Python-generated files __pycache__/ *.py[oc] build/ dist/ wheels/ *.egg-info # Virtual Environments .venv # Tool cache .cache/ .thumbs/ # Coverage reports .coverage .coverage.* coverage.xml htmlcov/ # Test Reports rspec.xml # Type Checking .mypy_cache/ # IDEs & Editors .vscode .history/ .idea # Claude Code .claude/settings.local.json .claude/worktrees/ .mcp.json # Claude Code sandbox artifacts (empty placeholder files created in repo root) .bash_profile .bashrc .profile .zprofile .zshrc .gitconfig .gitmodules .ripgreprc /HEAD /config /hooks /objects /refs # Documentation docs/_build/ docs/api/_generated/ # Airspeed Velocity asv/env asv/results asv/html # Log files, settings MUJOCO_LOG.TXT imgui.ini newton/tests/outputs/ # Viser recordings docs/_static/recordings/ *.viser # Viser static files docs/_static/viser/ # Notebook checkpoints **/*.ipynb_checkpoints/ ================================================ FILE: .licenserc-docs.yaml ================================================ header: license: spdx-id: CC-BY-4.0 copyright-owner: The Newton Developers content: | SPDX-FileCopyrightText: Copyright (c) 2026 The Newton Developers SPDX-License-Identifier: CC-BY-4.0 # Pattern is matched against lowercased text where "(c)" is normalized # to the word "copyright", so "Copyright (c)" becomes "copyright copyright". pattern: | spdx-filecopyrighttext: copyright copyright \d{4} the newton developers spdx-license-identifier: cc-by-4\.0 paths: - "**/*.rst" paths-ignore: - "docs/api/_generated/**" - "docs/_templates/**" language: reStructuredText: extensions: - ".rst" comment_style_id: DoubleDot comment: on-failure ================================================ FILE: .licenserc.yaml ================================================ header: license: spdx-id: Apache-2.0 copyright-owner: The Newton Developers content: | # SPDX-FileCopyrightText: Copyright (c) 2026 The Newton Developers # SPDX-License-Identifier: Apache-2.0 # Pattern is matched against lowercased text where "(c)" is normalized # to the word "copyright", so "Copyright (c)" becomes "copyright copyright". pattern: | spdx-filecopyrighttext: copyright copyright \d{4} the newton developers spdx-license-identifier: apache-2\.0 paths: - "**/*.py" paths-ignore: - "newton/_version.py" - "asv/benchmarks/**/__init__.py" - "newton/tests/thirdparty/__init__.py" comment: on-failure ================================================ FILE: .pre-commit-config.yaml ================================================ ci: autofix_commit_msg: | [pre-commit.ci] auto code formatting autofix_prs: false autoupdate_branch: "" autoupdate_commit_msg: "[pre-commit.ci] pre-commit autoupdate" autoupdate_schedule: quarterly # pre-commit.ci has no network access, but uv-lock needs to resolve # dependencies from remote indexes (PyPI, nvidia, pytorch). # Lockfile freshness is checked by a separate CI workflow instead. skip: - uv-lock submodules: false # See https://pre-commit.com for more information # See https://pre-commit.com/hooks.html for more hooks repos: - repo: https://github.com/astral-sh/ruff-pre-commit # Ruff version. rev: v0.14.10 hooks: # Run the linter. - id: ruff args: [--fix] # Apply fixes to resolve lint violations. # Run the formatter. - id: ruff-format - repo: https://github.com/astral-sh/uv-pre-commit # uv version. rev: 0.9.21 hooks: # Update the uv lockfile - id: uv-lock - repo: https://github.com/crate-ci/typos rev: v1.42.0 hooks: - id: typos args: [] exclude: \.(js|css)$ - repo: local hooks: - id: check-warp-array-syntax name: check warp array syntax entry: python scripts/check_warp_array_syntax.py language: system types: [python] exclude: ^(scripts/check_warp_array_syntax\.py|newton/_src/solvers/kamino/) ================================================ FILE: .python-version ================================================ 3.12 ================================================ FILE: AGENTS.md ================================================ # Newton Development Guidelines - `newton/_src/` is internal. Examples and docs must not import from `newton._src`. Expose user-facing symbols via public modules (`newton/geometry.py`, `newton/solvers.py`, etc.). - Breaking changes require a deprecation first. Do not remove or rename public API symbols without deprecating them in a prior release. - Prefix-first naming for autocomplete: `ActuatorPD` (not `PDActuator`), `add_shape_sphere()` (not `add_sphere_shape()`). - Prefer nested classes for self-contained helper types/enums. - PEP 604 unions (`x | None`, not `Optional[x]`). - Annotate Warp arrays with bracket syntax (`wp.array[wp.vec3]`, `wp.array2d[float]`, `wp.array[Any]`), not the parenthesized form (`wp.array(dtype=...)`). Use `wp.array[X]` for 1-D arrays, not `wp.array1d[X]`. - Follow Google-style docstrings. Types in annotations, not docstrings. `Args:` use `name: description`. - Sphinx cross-refs (`:class:`, `:meth:`) with shortest possible targets. Prefer public API paths; never use `newton._src`. - SI units for physical quantities in public API docstrings: `"""Particle positions [m], shape [particle_count, 3]."""`. Joint-dependent: `[m or rad]`. Spatial vectors: `[N, N·m]`. Compound arrays: per-component. Skip non-physical fields. - Run `docs/generate_api.py` when adding public API symbols. - Avoid new required dependencies. Strongly prefer not adding optional ones — use Warp, NumPy, or stdlib. - Create a feature branch before committing — never commit directly to `main`. Use `/feature-desc`. - Imperative mood in commit messages ("Fix X", not "Fixed X"), ~50 char subject, body wraps at 72 chars explaining _what_ and _why_. - Verify regression tests fail without the fix before committing. - Pin GitHub Actions by SHA: `action@ # vX.Y.Z`. Check `.github/workflows/` for allowlisted hashes. - In SPDX copyright lines, use the year the file was first created. Do not create date ranges or update the year when modifying a file. Run `uvx pre-commit run -a` to lint/format before committing. Use `uv` for all commands; fall back to `venv`/`conda` if unavailable. ```bash # Examples uv sync --extra examples uv run -m newton.examples basic_pendulum ``` ## Tests Always use `unittest`, not pytest. ```bash uv run --extra dev -m newton.tests uv run --extra dev -m newton.tests -k test_viewer_log_shapes # specific test uv run --extra dev -m newton.tests -k test_basic.example_basic_shapes # example test uv run --extra dev --extra torch-cu12 -m newton.tests # with PyTorch ``` ### Testing guidelines - Never call `wp.synchronize()` or `wp.synchronize_device()` right before `.numpy()` on a Warp array. This is redundant as `.numpy()` performs a synchronous device-to-host copy that completes all outstanding work. ```bash # Benchmarks uvx --with virtualenv asv run --launch-method spawn main^! ``` ## PR Instructions - If opening a pull request on GitHub, use the template in `.github/PULL_REQUEST_TEMPLATE.md`. - If a change modifies user-facing behavior, append an entry at the end of the correct category (`Added`, `Changed`, `Deprecated`, `Removed`, `Fixed`) in `CHANGELOG.md`'s `[Unreleased]` section. Use imperative present tense ("Add X") and avoid internal implementation details. - For `Deprecated`, `Changed`, and `Removed` entries, include migration guidance: "Deprecate `Model.geo_meshes` in favor of `Model.shapes`". ## Examples - Follow the `Example` class format. - Implement `test_final()` — runs after the example completes to verify simulation state is valid. - Optionally implement `test_post_step()` — runs after every `step()` for per-step validation. - Register in `README.md` with `python -m newton.examples ` command and a 320x320 jpg screenshot. ================================================ FILE: CHANGELOG.md ================================================ # Changelog ## [Unreleased] ### Added - Add repeatable `--warp-config KEY=VALUE` CLI option for overriding `warp.config` attributes when running examples - Add 3D texture-based SDF, replacing NanoVDB volumes in the mesh-mesh collision pipeline for improved performance and CPU compatibility. - Add `--benchmark [SECONDS]` flag to examples for headless FPS measurement with warmup - Interactive example browser in the GL viewer with tree-view navigation and switch/reset support - Add `TetMesh` class and USD loading API for tetrahedral mesh geometry - Support kinematic bodies in VBD solver - Add brick stacking example - Add box pyramid example and ASV benchmark for dense convex-on-convex contacts - Add plotting example showing how to access and visualize per-step simulation diagnostics - Add `exposure` property to GL renderer - Add `snap_to` argument to `ViewerGL.log_gizmo()` to snap gizmos to a target world transform when the user releases them - Expose `gizmo_is_using` attribute to detect whether a gizmo is actively being dragged - Add per-axis gizmo filtering via `translate`/`rotate` parameters on `log_gizmo` - Add conceptual overview and MuJoCo Warp integration primer to collision documentation - Add configurable velocity basis for implicit MPM (`velocity_basis`, default `"Q1"`) with GIMP quadrature option (`integration_scheme="gimp"`) - Add plastic viscosity, dilatancy, hardening and softening rate as per-particle MPM material properties (`mpm:viscosity`, `mpm:dilatancy`, `mpm:hardening_rate`, `mpm:softening_rate`) - Add MPM beam twist, snow ball, and viscous coiling examples - Add support for textures in `SensorTiledCamera` via `Config.enable_textures` - Add `enable_ambient_lighting` and `enable_particles` options to `SensorTiledCamera.Config` - Add `SensorTiledCamera.utils.convert_ray_depth_to_forward_depth()` to convert ray-distance depth to forward (planar) depth - Add `newton.geometry.compute_offset_mesh()` for extracting offset surface meshes from any collision shape, and a viewer toggle to visualize gap + margin wireframes in the GL viewer - Add differentiable rigid contacts (experimental) with respect to body poses via `CollisionPipeline` when `requires_grad=True` - Add per-shape display colors via `ModelBuilder.shape_color`, `Model.shape_color`, and `color=` on `ModelBuilder.add_shape_*`; mesh shapes fall back to `Mesh.color` when available and viewers honor runtime `Model.shape_color` updates - Add `ModelBuilder.inertia_tolerance` to configure the eigenvalue positivity and triangle inequality threshold used during inertia correction in `finalize()` - Pin `newton-assets` and `mujoco_menagerie` downloads to specific commit SHAs for reproducible builds (`NEWTON_ASSETS_REF`, `MENAGERIE_REF`) - Add `ref` parameter to `download_asset()` to allow overriding the pinned revision - Add `total_force_friction` and `force_matrix_friction` to `SensorContact` for tangential (friction) force decomposition - Add `compute_normals` and `compute_uvs` optional arguments to `Mesh.create_heightfield()` and `Mesh.create_terrain()` - Add RJ45 plug-socket insertion example with SDF contacts, latch joint, and interactive gizmo ### Changed - Unify heightfield and mesh collision pipeline paths; the separate `heightfield_midphase_kernel` and `shape_pairs_heightfield` buffer are removed in favor of the shared mesh midphase - Replace per-shape `Model.shape_heightfield_data` / `Model.heightfield_elevation_data` with compact `Model.shape_heightfield_index` / `Model.heightfield_data` / `Model.heightfield_elevations`, matching the SDF indirection pattern - Standardize `rigid_contact_normal` to point from shape 0 toward shape 1 (A-to-B), matching the documented convention. Consumers that previously negated the normal on read (XPBD, VBD, MuJoCo, Kamino) no longer need to. - Replace `Model.sdf_data` / `sdf_volume` / `sdf_coarse_volume` with texture-based equivalents (`texture_sdf_data`, `texture_sdf_coarse_textures`, `texture_sdf_subgrid_textures`) - Render inertia boxes as wireframe lines instead of solid boxes in the GL viewer to avoid occluding objects - Make contact reduction normal binning configurable (polyhedron, scan directions, voxel budget) via constants in ``contact_reduction.py`` - Upgrade GL viewer lighting from Blinn-Phong to Cook-Torrance PBR with GGX distribution, Schlick-GGX geometry, Fresnel-weighted ambient, and ACES filmic tone mapping - Change implicit MPM residual computation to consider both infinity and l2 norm - Change implicit MPM hardening law from exponential to hyperbolic sine (`sinh(-h * log(Jp))`), no longer scales elastic modulus - Change implicit MPM collider velocity mode names: `"forward"` / `"backward"` replace `"instantaneous"` / `"finite_difference"` - Simplify `SensorContact` force output: add `total_force` (aggregate per sensing object) and `force_matrix` (per-counterpart breakdown, `None` when no counterparts) - Add `sensing_obj_idx` (`list[int]`), `counterpart_indices` (`list[list[int]]`), `sensing_obj_type`, and `counterpart_type` attributes. Rename `include_total` to `measure_total` - Replace verbose Apache 2.0 boilerplate with two-line SPDX-only license headers across all source and documentation files - Add `custom_attributes` argument to `ModelBuilder.add_shape_convex_hull()` - Improve wrench preservation in hydroelastic contacts with contact reduction. - Show Newton deprecation warnings during example runs started via `python -m newton.examples ...` or `python -m newton.examples..`; pass `-W ignore::DeprecationWarning` if you need the previous quiet behavior. - Reorder `ModelBuilder.add_shape_gaussian()` parameters so `xform` precedes `gaussian`, in line with other `add_shape_*` methods. Callers using positional arguments should switch to keyword form (`gaussian=..., xform=...`); passing a `Gaussian` as the second positional argument still works but emits a `DeprecationWarning` - Rename `ModelBuilder.add_shape_ellipsoid()` parameters `a`, `b`, `c` to `rx`, `ry`, `rz`. Old names are still accepted as keyword arguments but emit a `DeprecationWarning` - Rename `collide_plane_cylinder()` parameter `cylinder_center` to `cylinder_pos` for consistency with other collide functions - Add optional `state` parameter to `SolverBase.update_contacts()` to align the base-class signature with Kamino and MuJoCo solvers - Use `Literal` types for `SolverImplicitMPM.Config` string fields with fixed option sets (`solver`, `warmstart_mode`, `collider_velocity_mode`, `grid_type`, `transfer_scheme`, `integration_scheme`) - Migrate `wp.array(dtype=X)` type annotations to `wp.array[X]` bracket syntax (Warp 1.12+). ### Deprecated - Deprecate `ModelBuilder.default_body_armature`, the `armature` argument on `ModelBuilder.add_link()` / `ModelBuilder.add_body()`, and USD-authored body armature via `newton:armature` in favor of adding any isotropic artificial inertia directly to `inertia` - Deprecate `SensorContact.net_force` in favor of `SensorContact.total_force` and `SensorContact.force_matrix` - Deprecate `SensorContact(include_total=...)` in favor of `SensorContact(measure_total=...)` - Deprecate `SensorContact.sensing_objs` in favor of `SensorContact.sensing_obj_idx` - Deprecate `SensorContact.counterparts` and `SensorContact.reading_indices` in favor of `SensorContact.counterpart_indices` - Deprecate `SensorContact.shape` (use `total_force.shape` and `force_matrix.shape` instead) - Deprecate `SensorTiledCamera.render_context`; prefer `SensorTiledCamera.utils` and `SensorTiledCamera.render_config`. - Deprecate `SensorTiledCamera.RenderContext`; use `SensorTiledCamera.RenderConfig` for config types and `SensorTiledCamera.render_config` / `SensorTiledCamera.utils` for runtime access. - Deprecate `SensorTiledCamera.Config`; prefer `SensorTiledCamera.RenderConfig` and `SensorTiledCamera.utils`. - Deprecate `Viewer.update_shape_colors()` in favor of writing directly to `Model.shape_color` - Deprecate `ModelBuilder.add_shape_ellipsoid()` parameters `a`, `b`, `c` in favor of `rx`, `ry`, `rz` - Deprecate passing a `Gaussian` as the second positional argument to `ModelBuilder.add_shape_gaussian()`; use the `gaussian=` keyword argument instead - Deprecate `SensorTiledCamera.utils.assign_random_colors_per_world()` and `assign_random_colors_per_shape()` in favor of per-shape colors via `ModelBuilder.add_shape_*(color=...)` ### Removed - Remove `Heightfield.finalize()` and stop storing raw pointers for heightfields in `Model.shape_source_ptr`; heightfield collision data is accessed via `Model.shape_heightfield_index` / `Model.heightfield_data` / `Model.heightfield_elevations` - Remove `robot_humanoid` example in favor of `basic_plotting` which uses the same humanoid model with diagnostics visualization ### Fixed - Fix inertia validation spuriously inflating small but physically valid eigenvalues for lightweight components (< ~50 g) by using a relative threshold instead of an absolute 1e-6 cutoff - Restore keyboard camera movement while hovering gizmos so keyboard controls remain active when the pointer is over gizmos - Resolve USD asset references recursively in `resolve_usd_from_url` so nested stages are fully downloaded - Unify CPU and GPU inertia validation to produce identical results for zero-mass bodies with `bound_mass`, singular inertia, non-symmetric tensors, and triangle-inequality boundary cases - Fix `UnboundLocalError` crash in detailed inertia validation when eigenvalue decomposition encounters NaN/Inf input - Handle NaN/Inf mass and inertia deterministically in both validation paths (zero out mass and inertia) - Update `ModelBuilder` internal state after fast-path (GPU kernel) inertia validation so it matches the returned `Model` - Fix MJCF mesh scale resolution to use the mesh asset's own class rather than the geom's default class, avoiding incorrect vertex scaling for models like Robotiq 2F-85 V4 - Fix articulated bodies drifting laterally on the ground in XPBD solver by solving rigid contacts before joints - Fix viewer crash with `imgui_bundle>=1.92.6` when editing colors by normalizing `color_edit3` input/output in `_edit_color3` - Fix `hide_collision_shapes=True` not hiding collision meshes that have bound PBR materials - Filter inactive particles in viewer so only particles with `ParticleFlags.ACTIVE` are rendered - Fix concurrent asset download races on Windows by using content-addressed cache directories - Show prismatic joints in the GL viewer when "Show Joints" is enabled - Fix body `gravcomp` not being written to the MuJoCo spec, causing it to be absent from XML saved via `save_to_mjcf` - Fix `compute_world_offsets` grid ordering to match terrain grid row-major order so replicated world indices align with terrain block indices - Fix `eq_solimp` not being written to the MuJoCo spec for equality constraints, causing it to be absent from XML saved via `save_to_mjcf` - Fix WELD equality constraint quaternion written in xyzw format instead of MuJoCo's wxyz format in the spec, causing incorrect orientation in XML saved via `save_to_mjcf` - Fix `update_contacts` not populating `rigid_contact_point0`/`rigid_contact_point1` when using `use_mujoco_contacts=True` - Fix VSync toggle having no effect in `ViewerGL` on Windows 8+ due to a pyglet bug where `DwmFlush()` is never called when `_always_dwm` is True - Fix loop joint coordinate mapping in the MuJoCo solver so joints after a loop joint read/write at correct qpos/qvel offsets - Fix viewer crash when contact buffer overflows by clamping contact count to buffer size - Decompose loop joint constraints by DOF type (WELD for fixed, CONNECT-pair for revolute, single CONNECT for ball) instead of always emitting 2x CONNECT - Fix inertia box wireframe rotation for isotropic and axisymmetric bodies in viewer - Implicit MPM solver now uses `mass=0` for kinematic particles instead of `ACTIVE` flag - Suppress macOS OpenGL warning about unloadable textures by binding a 1x1 white fallback texture when no albedo or environment texture is set - Fix MuJoCo solver freeze when immovable bodies (kinematic, static, or fixed-root) generate contacts with degenerate invweight - Fix forward-kinematics child-origin linear velocity for articulated translated joints - Fix `ModelBuilder.approximate_meshes()` to handle the duplication of per-shape custom attributes that results from convex decomposition - Fix `get_tetmesh()` winding order for left-handed USD meshes - Fix contact force conversion in `SolverMuJoCo` to include friction (tangential) components - Fix URDF inertial parameters parsing in parse_urdf so inertia tensor is correctly calculated as R@I@R.T - Fix Poisson surface reconstruction segfault under parallel test execution by defaulting to single-threaded Open3D Poisson (`n_threads=1`) - Fix overly conservative broadphase AABB for mesh shapes by using the pre-computed local AABB with a rotated-box transform instead of a bounding-sphere fallback, eliminating false contacts between distant meshes - Fix heightfield bounding-sphere radius underestimating Z extent for asymmetric height ranges (e.g. `min_z=0, max_z=10`) - Fix VBD self-contact barrier C2 discontinuity at `d = tau` caused by a factor-of-two error in the log-barrier coefficient - Fix fast inertia validation treating near-symmetric tensors within `np.allclose()` default tolerances as corrections, aligning CPU and GPU validation warnings ## [1.0.0] - 2026-03-10 Initial public release. ================================================ FILE: CITATION.cff ================================================ cff-version: 1.2.0 message: "If you use Newton, please cite it using this metadata." title: "Newton: GPU-accelerated physics simulation for robotics and simulation research" type: software authors: - name: "The Newton Contributors" url: "https://github.com/newton-physics/newton" license: Apache-2.0 date-released: "2025-04-22" ================================================ FILE: CLAUDE.md ================================================ @AGENTS.md ================================================ FILE: CODE_OF_CONDUCT.md ================================================ By participating in this community, you agree to abide by the Linux Foundation [Code of Conduct](https://lfprojects.org/policies/code-of-conduct/). ================================================ FILE: CONTRIBUTING.md ================================================ # Overview Newton is a project of the Linux Foundation and aims to be governed in a transparent, accessible way for the benefit of the community. All participation in this project is open and not bound to corporate affiliation. Participants are all bound to the Linux Foundation [Code of Conduct](https://lfprojects.org/policies/code-of-conduct/). # General Guidelines and Legal Please refer to [the contribution guidelines](https://github.com/newton-physics/newton-governance/blob/main/CONTRIBUTING.md) in the `newton-governance` repository for general information, project membership, and legal requirements for making contributions to Newton. # Contributing to Newton Newton welcomes contributions from the community. In order to avoid any surprises and to increase the chance of contributions being merged, we encourage contributors to communicate their plans proactively by opening a GitHub Issue or starting a Discussion in the corresponding repository. Please also refer to the [development guide](https://newton-physics.github.io/newton/latest/guide/development.html). There are several ways to participate in the Newton community: ## Questions, Discussions, Suggestions * Help answer questions or contribute to technical discussion in [GitHub Discussions](https://github.com/newton-physics/newton/discussions) and Issues. * If you have a question, suggestion or discussion topic, start a new [GitHub Discussion](https://github.com/newton-physics/newton/discussions) if there is no existing topic. * Once somebody shares a satisfying answer to the question, click "Mark as answer". * [GitHub Issues](https://github.com/newton-physics/newton/issues) should only be used for bugs and features. Specifically, issues that result in a code or documentation change. We may convert issues to discussions if these conditions are not met. ## Reporting a Bug * Check in the [GitHub Issues](https://github.com/newton-physics/newton/issues) if a report for the bug already exists. * If the bug has not been reported yet, open a new Issue. * Use a short, descriptive title and write a clear description of the bug. * Document the Git hash or release version where the bug is present, and the hardware and environment by including the output of `nvidia-smi`. * Add executable code samples or test cases with instructions for reproducing the bug. ## Documentation Issues * Create a new issue if there is no existing report, or * directly submit a fix following the "Fixing a Bug" workflow below. ## Fixing a Bug * Ensure that the bug report issue has no assignee yet. If the issue is assigned and there is no linked PR, you're welcome to ask about the current status by commenting on the issue. * Write a fix and regression unit test for the bug following the [style guide](https://newton-physics.github.io/newton/latest/guide/development.html#style-guide). * Open a new pull request for the fix and test. * Write a description of the bug and the fix. * Mention related issues in the description: E.g. if the patch fixes Issue \#33, write Fixes \#33. * Have a signed CLA on file (see [Legal Requirements](https://github.com/newton-physics/newton-governance/blob/main/CONTRIBUTING.md#legal-requirements)). * Have the pull request approved by a [Project Member](https://github.com/newton-physics/newton-governance/blob/main/CONTRIBUTING.md#project-members) and merged into the codebase. ## Improving Performance * Write an optimization that improves an existing or new benchmark following the [style guide](https://newton-physics.github.io/newton/latest/guide/development.html#style-guide). * Open a new pull request with the optimization, and the benchmark, if applicable. * Write a description of the performance optimization. * Mention related issues in the description: E.g. if the optimization addresses Issue \#42, write Addresses \#42. * Have a signed CLA on file (see [Legal Requirements](https://github.com/newton-physics/newton-governance/blob/main/CONTRIBUTING.md#legal-requirements)). * Have the pull request approved by a [Project Member](https://github.com/newton-physics/newton-governance/blob/main/CONTRIBUTING.md#project-members) and merged into the codebase. ## Adding a Feature or Solver * Discuss your proposal ideally before starting with implementation. Open a GitHub Issue or Discussion to: * propose and motivate the new feature or solver; * detail technical specifications; * and list changes or additions to the Newton API. * Wait for feedback from [Project Members](https://github.com/newton-physics/newton-governance/blob/main/CONTRIBUTING.md#project-members) before proceeding. * Implement the feature or solver following the [style guide](https://newton-physics.github.io/newton/latest/guide/development.html#style-guide). * Add comprehensive testing and benchmarking for the new feature or solver. * Ensure all existing tests pass and that existing benchmarks do not regress. * Update or add documentation for the new feature or solver. * Have a signed CLA on file (see [Legal Requirements](https://github.com/newton-physics/newton-governance/blob/main/CONTRIBUTING.md#legal-requirements)). * Have the pull request approved by a [Project Member](https://github.com/newton-physics/newton-governance/blob/main/CONTRIBUTING.md#project-members) and merged into the codebase. ## Adding Simulation Assets * Before proposing to add any assets to the Newton project, make sure that the assets are properly licensed for use and distribution. If you are unsure about the license, open a new discussion. * The Newton project hosts possibly large simulation assets such as models, textures, datasets, or pre-trained policies in the [newton-assets](https://github.com/newton-physics/newton-assets) repository to keep the main newton repository small. * Therefore, along with a pull request in the main newton repository that relies on new assets, open a corresponding pull request in the [newton-assets](https://github.com/newton-physics/newton-assets) repository. * Follow the instructions in the [README](https://github.com/newton-physics/newton-assets) of the newton-assets repository. * Have a signed CLA on file (see [Legal Requirements](https://github.com/newton-physics/newton-governance/blob/main/CONTRIBUTING.md#legal-requirements)). * Have the pull request approved by a [Project Member](https://github.com/newton-physics/newton-governance/blob/main/CONTRIBUTING.md#project-members) and merged into the asset repository. ================================================ FILE: LICENSE.md ================================================ Apache License Version 2.0, January 2004 http://www.apache.org/licenses/ TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION 1. Definitions. "License" shall mean the terms and conditions for use, reproduction, and distribution as defined by Sections 1 through 9 of this document. "Licensor" shall mean the copyright owner or entity authorized by the copyright owner that is granting the License. "Legal Entity" shall mean the union of the acting entity and all other entities that control, are controlled by, or are under common control with that entity. For the purposes of this definition, "control" means (i) the power, direct or indirect, to cause the direction or management of such entity, whether by contract or otherwise, or (ii) ownership of fifty percent (50%) or more of the outstanding shares, or (iii) beneficial ownership of such entity. "You" (or "Your") shall mean an individual or Legal Entity exercising permissions granted by this License. "Source" form shall mean the preferred form for making modifications, including but not limited to software source code, documentation source, and configuration files. "Object" form shall mean any form resulting from mechanical transformation or translation of a Source form, including but not limited to compiled object code, generated documentation, and conversions to other media types. "Work" shall mean the work of authorship, whether in Source or Object form, made available under the License, as indicated by a copyright notice that is included in or attached to the work (an example is provided in the Appendix below). "Derivative Works" shall mean any work, whether in Source or Object form, that is based on (or derived from) the Work and for which the editorial revisions, annotations, elaborations, or other modifications represent, as a whole, an original work of authorship. For the purposes of this License, Derivative Works shall not include works that remain separable from, or merely link (or bind by name) to the interfaces of, the Work and Derivative Works thereof. "Contribution" shall mean any work of authorship, including the original version of the Work and any modifications or additions to that Work or Derivative Works thereof, that is intentionally submitted to Licensor for inclusion in the Work by the copyright owner or by an individual or Legal Entity authorized to submit on behalf of the copyright owner. For the purposes of this definition, "submitted" means any form of electronic, verbal, or written communication sent to the Licensor or its representatives, including but not limited to communication on electronic mailing lists, source code control systems, and issue tracking systems that are managed by, or on behalf of, the Licensor for the purpose of discussing and improving the Work, but excluding communication that is conspicuously marked or otherwise designated in writing by the copyright owner as "Not a Contribution." "Contributor" shall mean Licensor and any individual or Legal Entity on behalf of whom a Contribution has been received by Licensor and subsequently incorporated within the Work. 2. Grant of Copyright License. Subject to the terms and conditions of this License, each Contributor hereby grants to You a perpetual, worldwide, non-exclusive, no-charge, royalty-free, irrevocable copyright license to reproduce, prepare Derivative Works of, publicly display, publicly perform, sublicense, and distribute the Work and such Derivative Works in Source or Object form. 3. Grant of Patent License. Subject to the terms and conditions of this License, each Contributor hereby grants to You a perpetual, worldwide, non-exclusive, no-charge, royalty-free, irrevocable (except as stated in this section) patent license to make, have made, use, offer to sell, sell, import, and otherwise transfer the Work, where such license applies only to those patent claims licensable by such Contributor that are necessarily infringed by their Contribution(s) alone or by combination of their Contribution(s) with the Work to which such Contribution(s) was submitted. If You institute patent litigation against any entity (including a cross-claim or counterclaim in a lawsuit) alleging that the Work or a Contribution incorporated within the Work constitutes direct or contributory patent infringement, then any patent licenses granted to You under this License for that Work shall terminate as of the date such litigation is filed. 4. Redistribution. You may reproduce and distribute copies of the Work or Derivative Works thereof in any medium, with or without modifications, and in Source or Object form, provided that You meet the following conditions: (a) You must give any other recipients of the Work or Derivative Works a copy of this License; and (b) You must cause any modified files to carry prominent notices stating that You changed the files; and (c) You must retain, in the Source form of any Derivative Works that You distribute, all copyright, patent, trademark, and attribution notices from the Source form of the Work, excluding those notices that do not pertain to any part of the Derivative Works; and (d) If the Work includes a "NOTICE" text file as part of its distribution, then any Derivative Works that You distribute must include a readable copy of the attribution notices contained within such NOTICE file, excluding those notices that do not pertain to any part of the Derivative Works, in at least one of the following places: within a NOTICE text file distributed as part of the Derivative Works; within the Source form or documentation, if provided along with the Derivative Works; or, within a display generated by the Derivative Works, if and wherever such third-party notices normally appear. The contents of the NOTICE file are for informational purposes only and do not modify the License. You may add Your own attribution notices within Derivative Works that You distribute, alongside or as an addendum to the NOTICE text from the Work, provided that such additional attribution notices cannot be construed as modifying the License. You may add Your own copyright statement to Your modifications and may provide additional or different license terms and conditions for use, reproduction, or distribution of Your modifications, or for any such Derivative Works as a whole, provided Your use, reproduction, and distribution of the Work otherwise complies with the conditions stated in this License. 5. Submission of Contributions. Unless You explicitly state otherwise, any Contribution intentionally submitted for inclusion in the Work by You to the Licensor shall be under the terms and conditions of this License, without any additional terms or conditions. Notwithstanding the above, nothing herein shall supersede or modify the terms of any separate license agreement you may have executed with Licensor regarding such Contributions. 6. Trademarks. This License does not grant permission to use the trade names, trademarks, service marks, or product names of the Licensor, except as required for reasonable and customary use in describing the origin of the Work and reproducing the content of the NOTICE file. 7. Disclaimer of Warranty. Unless required by applicable law or agreed to in writing, Licensor provides the Work (and each Contributor provides its Contributions) on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied, including, without limitation, any warranties or conditions of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A PARTICULAR PURPOSE. You are solely responsible for determining the appropriateness of using or redistributing the Work and assume any risks associated with Your exercise of permissions under this License. 8. Limitation of Liability. In no event and under no legal theory, whether in tort (including negligence), contract, or otherwise, unless required by applicable law (such as deliberate and grossly negligent acts) or agreed to in writing, shall any Contributor be liable to You for damages, including any direct, indirect, special, incidental, or consequential damages of any character arising as a result of this License or out of the use or inability to use the Work (including but not limited to damages for loss of goodwill, work stoppage, computer failure or malfunction, or any and all other commercial damages or losses), even if such Contributor has been advised of the possibility of such damages. 9. Accepting Warranty or Additional Liability. While redistributing the Work or Derivative Works thereof, You may choose to offer, and charge a fee for, acceptance of support, warranty, indemnity, or other liability obligations and/or rights consistent with this License. However, in accepting such obligations, You may act only on Your own behalf and on Your sole responsibility, not on behalf of any other Contributor, and only if You agree to indemnify, defend, and hold each Contributor harmless for any liability incurred by, or claims asserted against, such Contributor by reason of your accepting any such warranty or additional liability. END OF TERMS AND CONDITIONS ================================================ FILE: README.md ================================================ [![License](https://img.shields.io/badge/License-Apache_2.0-blue.svg)](https://opensource.org/licenses/Apache-2.0) ![GitHub commit activity](https://img.shields.io/github/commit-activity/m/newton-physics/newton/main) [![codecov](https://codecov.io/gh/newton-physics/newton/graph/badge.svg?token=V6ZXNPAWVG)](https://codecov.io/gh/newton-physics/newton) [![Push - AWS GPU](https://github.com/newton-physics/newton/actions/workflows/push_aws_gpu.yml/badge.svg)](https://github.com/newton-physics/newton/actions/workflows/push_aws_gpu.yml) # Newton Newton is a GPU-accelerated physics simulation engine built upon [NVIDIA Warp](https://github.com/NVIDIA/warp), specifically targeting roboticists and simulation researchers. Newton extends and generalizes Warp's ([deprecated](https://github.com/NVIDIA/warp/discussions/735)) `warp.sim` module, and integrates [MuJoCo Warp](https://github.com/google-deepmind/mujoco_warp) as its primary backend. Newton emphasizes GPU-based computation, [OpenUSD](https://openusd.org/) support, differentiability, and user-defined extensibility, facilitating rapid iteration and scalable robotics simulation. Newton is a [Linux Foundation](https://www.linuxfoundation.org/) project that is community-built and maintained. Code is licensed under [Apache-2.0](https://github.com/newton-physics/newton/blob/main/LICENSE.md). Documentation is licensed under [CC-BY-4.0](https://creativecommons.org/licenses/by/4.0/). Additional and third-party license texts are available in [`newton/licenses`](https://github.com/newton-physics/newton/tree/main/newton/licenses). Newton was initiated by [Disney Research](https://www.disneyresearch.com/), [Google DeepMind](https://deepmind.google/), and [NVIDIA](https://www.nvidia.com/). ## Requirements - **Python** 3.10+ - **OS:** Linux (x86-64, aarch64), Windows (x86-64), or macOS (CPU only) - **GPU:** NVIDIA GPU (Maxwell or newer), driver 545 or newer (CUDA 12). No local CUDA Toolkit installation required. macOS runs on CPU. For detailed system requirements and tested configurations, see the [installation guide](https://newton-physics.github.io/newton/latest/guide/installation.html). ## Quickstart ```bash pip install "newton[examples]" python -m newton.examples basic_pendulum ``` To install from source with [uv](https://docs.astral.sh/uv/), see the [installation guide](https://newton-physics.github.io/newton/latest/guide/installation.html). ## Examples Before running the examples below, install Newton with the examples extra: ```bash pip install "newton[examples]" ``` If you installed from source with uv, substitute `uv run` for `python` in the commands below.

Basic Examples

Pendulum URDF Viewer
python -m newton.examples basic_pendulum python -m newton.examples basic_urdf python -m newton.examples basic_viewer
Shapes Joints Conveyor
python -m newton.examples basic_shapes python -m newton.examples basic_joints python -m newton.examples basic_conveyor
Heightfield Recording Replay Viewer
python -m newton.examples basic_heightfield python -m newton.examples recording python -m newton.examples replay_viewer
Plotting
python -m newton.examples basic_plotting

Robot Examples

Cartpole G1 H1
python -m newton.examples robot_cartpole python -m newton.examples robot_g1 python -m newton.examples robot_h1
Anymal D Anymal C Walk
python -m newton.examples robot_anymal_d python -m newton.examples robot_anymal_c_walk
Policy UR10 Panda Hydro
python -m newton.examples robot_policy python -m newton.examples robot_ur10 python -m newton.examples robot_panda_hydro
Allegro Hand
python -m newton.examples robot_allegro_hand

Cable Examples

Cable Twist Cable Y-Junction Cable Bundle Hysteresis
python -m newton.examples cable_twist python -m newton.examples cable_y_junction python -m newton.examples cable_bundle_hysteresis
Cable Pile
python -m newton.examples cable_pile

Cloth Examples

Cloth Bending Cloth Hanging Cloth Style3D
python -m newton.examples cloth_bending python -m newton.examples cloth_hanging python -m newton.examples cloth_style3d
Cloth H1 Cloth Twist Cloth Franka
python -m newton.examples cloth_h1 python -m newton.examples cloth_twist python -m newton.examples cloth_franka
Cloth Rollers Cloth Poker Cards
python -m newton.examples cloth_rollers python -m newton.examples cloth_poker_cards

Inverse Kinematics Examples

IK Franka IK H1 IK Custom
python -m newton.examples ik_franka python -m newton.examples ik_h1 python -m newton.examples ik_custom
IK Cube Stacking
python -m newton.examples ik_cube_stacking

MPM Examples

MPM Granular MPM Anymal MPM Two-Way Coupling
python -m newton.examples mpm_granular python -m newton.examples mpm_anymal python -m newton.examples mpm_twoway_coupling
MPM Grain Rendering MPM Multi Material MPM Viscous
python -m newton.examples mpm_grain_rendering python -m newton.examples mpm_multi_material python -m newton.examples mpm_viscous
MPM Beam Twist MPM Snow Ball
python -m newton.examples mpm_beam_twist python -m newton.examples mpm_snow_ball

Sensor Examples

Sensor Contact Sensor Tiled Camera Sensor IMU
python -m newton.examples sensor_contact python -m newton.examples sensor_tiled_camera python -m newton.examples sensor_imu

Selection Examples

Selection Cartpole Selection Materials Selection Articulations
python -m newton.examples selection_cartpole python -m newton.examples selection_materials python -m newton.examples selection_articulations
Selection Multiple
python -m newton.examples selection_multiple

DiffSim Examples

DiffSim Ball DiffSim Cloth DiffSim Drone
python -m newton.examples diffsim_ball python -m newton.examples diffsim_cloth python -m newton.examples diffsim_drone
DiffSim Spring Cage DiffSim Soft Body DiffSim Quadruped
python -m newton.examples diffsim_spring_cage python -m newton.examples diffsim_soft_body python -m newton.examples diffsim_bear

Multi-Physics Examples

Softbody Gift Softbody Dropping to Cloth
python -m newton.examples softbody_gift python -m newton.examples softbody_dropping_to_cloth

Contacts Examples

Nut Bolt Hydro Nut Bolt SDF Brick Stacking
python -m newton.examples nut_bolt_hydro python -m newton.examples nut_bolt_sdf python -m newton.examples brick_stacking
Pyramid RJ45 Plug
python -m newton.examples pyramid python -m newton.examples contacts_rj45_plug

Softbody Examples

Softbody Hanging Softbody Franka
python -m newton.examples softbody_hanging python -m newton.examples softbody_franka
### Example Options The examples support the following command-line arguments: | Argument | Description | Default | | --------------- | --------------------------------------------------------------------------------------------------- | ---------------------------- | | `--viewer` | Viewer type: `gl` (OpenGL window), `usd` (USD file output), `rerun` (ReRun), or `null` (no viewer). | `gl` | | `--device` | Compute device to use, e.g., `cpu`, `cuda:0`, etc. | `None` (default Warp device) | | `--num-frames` | Number of frames to simulate (for USD output). | `100` | | `--output-path` | Output path for USD files (required if `--viewer usd` is used). | `None` | Some examples may add additional arguments (see their respective source files for details). ### Example Usage ```bash # List available examples python -m newton.examples # Run with the USD viewer and save to my_output.usd python -m newton.examples basic_viewer --viewer usd --output-path my_output.usd # Run on a selected device python -m newton.examples basic_urdf --device cuda:0 # Combine options python -m newton.examples basic_viewer --viewer gl --num-frames 500 --device cpu ``` ## Contributing and Development See the [contribution guidelines](https://github.com/newton-physics/newton-governance/blob/main/CONTRIBUTING.md) and the [development guide](https://newton-physics.github.io/newton/latest/guide/development.html) for instructions on how to contribute to Newton. ## Support and Community Discussion For questions, please consult the [Newton documentation](https://newton-physics.github.io/newton/latest/guide/overview.html) first before creating [a discussion in the main repository](https://github.com/newton-physics/newton/discussions). ## Code of Conduct By participating in this community, you agree to abide by the Linux Foundation [Code of Conduct](https://lfprojects.org/policies/code-of-conduct/). ## Project Governance, Legal, and Members Please see the [newton-governance repository](https://github.com/newton-physics/newton-governance) for more information about project governance. ================================================ FILE: SECURITY.md ================================================ Please refer to the [SECURITY.md](https://github.com/newton-physics/newton-governance/blob/main/SECURITY.md) in the newton-governance repository. ================================================ FILE: asv/benchmarks/__init__.py ================================================ ================================================ FILE: asv/benchmarks/benchmark_ik.py ================================================ # SPDX-FileCopyrightText: Copyright (c) 2026 The Newton Developers # SPDX-License-Identifier: Apache-2.0 ########################################################################### # Used for benchmarking the Newton IK solver. # # This module provides shared logic for IK benchmarks on the # Franka Emika Panda robot. ########################################################################### from __future__ import annotations import numpy as np import warp as wp import newton import newton.ik as ik import newton.utils def create_franka_model() -> newton.Model: builder = newton.ModelBuilder() builder.num_rigid_contacts_per_world = 0 builder.default_shape_cfg.density = 100.0 asset_path = newton.utils.download_asset("franka_emika_panda") / "urdf/fr3.urdf" builder.add_urdf(asset_path, floating=False, scale=1.0) return builder.finalize(requires_grad=False) def random_solutions(model: newton.Model, n: int, rng: np.random.Generator) -> np.ndarray: n_coords = model.joint_coord_count lower = model.joint_limit_lower.numpy()[:n_coords] upper = model.joint_limit_upper.numpy()[:n_coords] span = upper - lower mask = np.abs(span) > 1e5 span[mask] = 0.0 q = rng.random((n, n_coords)) * span + lower q[:, mask] = 0.0 return q.astype(np.float32) def build_ik_solver(model: newton.Model, n_problems: int, ee_links: tuple[int, ...]): zero_pos = [wp.zeros(n_problems, dtype=wp.vec3) for _ in ee_links] zero_rot = [wp.zeros(n_problems, dtype=wp.vec4) for _ in ee_links] objectives = [] for ee, link in enumerate(ee_links): objectives.append(ik.IKObjectivePosition(link, wp.vec3(), zero_pos[ee])) for ee, link in enumerate(ee_links): objectives.append( ik.IKObjectiveRotation( link, wp.quat_identity(), zero_rot[ee], canonicalize_quat_err=False, ) ) objectives.append( ik.IKObjectiveJointLimit( model.joint_limit_lower, model.joint_limit_upper, weight=1.0, ) ) solver = ik.IKSolver( model, n_problems, objectives, sampler=ik.IKSampler.ROBERTS, n_seeds=64, lambda_factor=4.0, jacobian_mode=ik.IKJacobianType.ANALYTIC, ) return ( solver, objectives[: len(ee_links)], objectives[len(ee_links) : 2 * len(ee_links)], ) def fk_targets(solver, model: newton.Model, q_batch: np.ndarray, ee_links: tuple[int, ...]): batch_size = q_batch.shape[0] solver._fk_two_pass( model, wp.array(q_batch, dtype=wp.float32), solver.body_q, solver.X_local, batch_size, ) wp.synchronize_device() bq = solver.body_q.numpy()[:batch_size] ee = np.asarray(ee_links) return bq[:, ee, :3].copy(), bq[:, ee, 3:7].copy() def eval_success(solver, model, q_best, tgt_pos, tgt_rot, ee_links, pos_thresh_m, ori_thresh_rad): batch_size = q_best.shape[0] solver._fk_two_pass( model, wp.array(q_best, dtype=wp.float32), solver.body_q, solver.X_local, batch_size, ) wp.synchronize_device() bq = solver.body_q.numpy()[:batch_size] ee = np.asarray(ee_links) pos_err = np.linalg.norm(bq[:, ee, :3] - tgt_pos, axis=-1).max(axis=-1) def _qmul(a, b): # Quaternions stored as (x, y, z, w) — scalar-last, matching Warp convention. x1, y1, z1, w1 = np.moveaxis(a, -1, 0) x2, y2, z2, w2 = np.moveaxis(b, -1, 0) return np.stack( ( w1 * x2 + x1 * w2 + y1 * z2 - z1 * y2, w1 * y2 - x1 * z2 + y1 * w2 + z1 * x2, w1 * z2 + x1 * y2 - y1 * x2 + z1 * w2, w1 * w2 - x1 * x2 - y1 * y2 - z1 * z2, ), axis=-1, ) tgt_conj = np.concatenate([-tgt_rot[..., :3], tgt_rot[..., 3:]], axis=-1) rel = _qmul(tgt_conj, bq[:, ee, 3:7]) rot_err = (2 * np.arctan2(np.linalg.norm(rel[..., :3], axis=-1), np.abs(rel[..., 3]))).max(axis=-1) success = (pos_err < pos_thresh_m) & (rot_err < ori_thresh_rad) return success ================================================ FILE: asv/benchmarks/benchmark_mujoco.py ================================================ # SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers # SPDX-License-Identifier: Apache-2.0 ########################################################################### # Used for benchmarking MjWarp. # # This script allows us to choose between several predefined robots and # provides a large range of customizable options. # ########################################################################### import time import numpy as np import warp as wp wp.config.enable_backward = False import newton import newton.examples import newton.utils from newton.sensors import SensorContact from newton.utils import EventTracer ROBOT_CONFIGS = { "humanoid": { "solver": "newton", "integrator": "implicitfast", "njmax": 80, "nconmax": 25, "ls_parallel": False, "cone": "pyramidal", "sensing_bodies": ["*thigh*", "*shin*", "*foot*", "*arm*"], }, "g1": { "solver": "newton", "integrator": "implicitfast", "njmax": 210, "nconmax": 35, "ls_parallel": False, "cone": "pyramidal", }, "h1": { "solver": "newton", "integrator": "implicitfast", "njmax": 65, "nconmax": 15, "ls_parallel": False, "cone": "pyramidal", }, "cartpole": { "solver": "newton", "integrator": "implicitfast", "njmax": 5, "nconmax": 0, "ls_parallel": False, "cone": "pyramidal", }, "ant": { "solver": "newton", "integrator": "implicitfast", "njmax": 38, "nconmax": 15, "ls_parallel": False, "cone": "pyramidal", }, "quadruped": { "solver": "newton", "integrator": "implicitfast", "njmax": 75, "nconmax": 50, "ls_parallel": False, "cone": "pyramidal", }, "allegro": { "solver": "newton", "integrator": "implicitfast", "njmax": 60, "nconmax": 40, "ls_parallel": False, "cone": "elliptic", }, "kitchen": { "setup_builder": lambda x: _setup_kitchen(x), "njmax": 3800, "nconmax": 900, }, "tabletop": { "setup_builder": lambda x: _setup_tabletop(x), "njmax": 100, "nconmax": 20, }, } def _setup_humanoid(articulation_builder): articulation_builder.add_mjcf( newton.examples.get_asset("nv_humanoid.xml"), ignore_names=["floor", "ground"], up_axis="Z", parse_sites=False, # AD: remove once asset is fixed enable_self_collisions=False, # Keep False for consistent benchmark performance ) # Setting root pose root_dofs = 7 articulation_builder.joint_q[:3] = [0.0, 0.0, 1.5] return root_dofs def _setup_g1(articulation_builder): articulation_builder.default_joint_cfg = newton.ModelBuilder.JointDofConfig( limit_ke=1.0e3, limit_kd=1.0e1, friction=1e-5 ) articulation_builder.default_shape_cfg.ke = 5.0e4 articulation_builder.default_shape_cfg.kd = 5.0e2 articulation_builder.default_shape_cfg.kf = 1.0e3 articulation_builder.default_shape_cfg.mu = 0.75 asset_path = newton.utils.download_asset("unitree_g1") articulation_builder.add_usd( str(asset_path / "usd" / "g1_isaac.usd"), xform=wp.transform(wp.vec3(0, 0, 0.8)), collapse_fixed_joints=True, enable_self_collisions=False, hide_collision_shapes=True, ) for i in range(6, articulation_builder.joint_dof_count): articulation_builder.joint_target_ke[i] = 1000.0 articulation_builder.joint_target_kd[i] = 5.0 # approximate meshes for faster collision detection articulation_builder.approximate_meshes("bounding_box") root_dofs = 7 return root_dofs def _setup_h1(articulation_builder): articulation_builder.default_joint_cfg = newton.ModelBuilder.JointDofConfig( limit_ke=1.0e3, limit_kd=1.0e1, friction=1e-5 ) articulation_builder.default_shape_cfg.ke = 5.0e4 articulation_builder.default_shape_cfg.kd = 5.0e2 articulation_builder.default_shape_cfg.kf = 1.0e3 articulation_builder.default_shape_cfg.mu = 0.75 asset_path = newton.utils.download_asset("unitree_h1") asset_file = str(asset_path / "usd" / "h1_minimal.usda") articulation_builder.add_usd( asset_file, ignore_paths=["/GroundPlane"], collapse_fixed_joints=False, enable_self_collisions=False, hide_collision_shapes=True, ) # approximate meshes for faster collision detection articulation_builder.approximate_meshes("bounding_box") for i in range(articulation_builder.joint_dof_count): articulation_builder.joint_target_ke[i] = 150 articulation_builder.joint_target_kd[i] = 5 root_dofs = 7 return root_dofs def _setup_cartpole(articulation_builder): articulation_builder.default_shape_cfg.density = 100.0 articulation_builder.default_joint_cfg.armature = 0.1 articulation_builder.add_usd( newton.examples.get_asset("cartpole_single_pendulum.usda"), enable_self_collisions=False, collapse_fixed_joints=True, ) armature_inertia = wp.mat33(np.eye(3, dtype=np.float32)) * 0.1 for i in range(articulation_builder.body_count): articulation_builder.body_inertia[i] = articulation_builder.body_inertia[i] + armature_inertia # set initial joint positions (cartpole has 2 joints: prismatic slider + revolute pole) # joint_q[0] = slider position, joint_q[1] = pole angle articulation_builder.joint_q[0] = 0.0 # slider at origin articulation_builder.joint_q[1] = 0.3 # pole tilted # Setting root pose root_dofs = 1 return root_dofs def _setup_ant(articulation_builder): articulation_builder.add_usd( newton.examples.get_asset("ant.usda"), collapse_fixed_joints=True, ) # Setting root pose root_dofs = 7 articulation_builder.joint_q[:3] = [0.0, 0.0, 1.5] return root_dofs def _setup_quadruped(articulation_builder): articulation_builder.default_joint_cfg.armature = 0.01 articulation_builder.default_shape_cfg.ke = 1.0e4 articulation_builder.default_shape_cfg.kd = 1.0e2 articulation_builder.default_shape_cfg.kf = 1.0e2 articulation_builder.default_shape_cfg.mu = 1.0 articulation_builder.add_urdf( newton.examples.get_asset("quadruped.urdf"), xform=wp.transform([0.0, 0.0, 0.7], wp.quat_identity()), floating=True, enable_self_collisions=False, ) armature_inertia = wp.mat33(np.eye(3, dtype=np.float32)) * 0.01 for i in range(articulation_builder.body_count): articulation_builder.body_inertia[i] = articulation_builder.body_inertia[i] + armature_inertia root_dofs = 7 return root_dofs def _setup_allegro(articulation_builder): asset_path = newton.utils.download_asset("wonik_allegro") asset_file = str(asset_path / "usd" / "allegro_left_hand_with_cube.usda") articulation_builder.add_usd( asset_file, xform=wp.transform(wp.vec3(0, 0, 0.5)), enable_self_collisions=True, ignore_paths=[".*Dummy", ".*CollisionPlane", ".*goal", ".*DexCube/visuals"], ) # set joint targets and joint drive gains for i in range(articulation_builder.joint_dof_count): articulation_builder.joint_target_ke[i] = 150 articulation_builder.joint_target_kd[i] = 5 articulation_builder.joint_target_pos[i] = 0.0 root_dofs = 1 return root_dofs def _setup_kitchen(articulation_builder): asset_path = newton.utils.download_asset("kitchen") asset_file = str(asset_path / "mjcf" / "kitchen.xml") articulation_builder.add_mjcf( asset_file, collapse_fixed_joints=True, enable_self_collisions=False, # Keep False for consistent benchmark performance ) # Change pose of the robot to minimize overlap articulation_builder.joint_q[:2] = [1.5, -1.5] def _setup_tabletop(articulation_builder): articulation_builder.add_mjcf( newton.examples.get_asset("tabletop.xml"), collapse_fixed_joints=True, ) class Example: def __init__( self, robot="humanoid", environment="None", stage_path=None, world_count=1, use_cuda_graph=True, use_mujoco_cpu=False, randomize=False, headless=False, actuation="None", solver=None, integrator=None, solver_iteration=None, ls_iteration=None, njmax=None, nconmax=None, builder=None, ls_parallel=None, cone=None, ): fps = 600 self.sim_time = 0.0 self.benchmark_time = 0.0 self.frame_dt = 1.0 / fps self.sim_substeps = 10 self.contacts = None self.sim_dt = self.frame_dt / self.sim_substeps self.world_count = world_count self.use_cuda_graph = use_cuda_graph self.use_mujoco_cpu = use_mujoco_cpu self.actuation = actuation # set numpy random seed self.seed = 123 self.rng = np.random.default_rng(self.seed) if not stage_path: stage_path = "example_" + robot + ".usd" if builder is None: builder = Example.create_model_builder(robot, world_count, environment, randomize, self.seed) # finalize model self.model = builder.finalize() self.solver = Example.create_solver( self.model, robot, use_mujoco_cpu=use_mujoco_cpu, environment=environment, solver=solver, integrator=integrator, solver_iteration=solver_iteration, ls_iteration=ls_iteration, njmax=njmax, nconmax=nconmax, ls_parallel=ls_parallel, cone=cone, ) if stage_path and not headless: self.renderer = newton.viewer.ViewerGL() self.renderer.set_model(self.model) self.renderer.set_world_offsets((4.0, 4.0, 0.0)) else: self.renderer = None self.control = self.model.control() self.state_0, self.state_1 = self.model.state(), self.model.state() newton.eval_fk(self.model, self.model.joint_q, self.model.joint_qd, self.state_0) self.sensor_contact = None sensing_bodies = ROBOT_CONFIGS.get(robot, {}).get("sensing_bodies", None) if sensing_bodies is not None: self.sensor_contact = SensorContact(self.model, sensing_obj_bodies=sensing_bodies, counterpart_bodies="*") self.contacts = newton.Contacts( self.solver.get_max_contact_count(), 0, device=self.model.device, requested_attributes=self.model.get_requested_contact_attributes(), ) self.graph = None if self.use_cuda_graph: # simulate() allocates memory via a clone, so we can't use graph capture if the device does not support mempools cuda_graph_comp = wp.get_device().is_cuda and wp.is_mempool_enabled(wp.get_device()) if not cuda_graph_comp: print("Cannot use graph capture. Graph capture is disabled.") else: with wp.ScopedCapture() as capture: self.simulate() self.graph = capture.graph def simulate(self): for _ in range(self.sim_substeps): self.state_0.clear_forces() self.solver.step(self.state_0, self.state_1, self.control, self.contacts, self.sim_dt) self.state_0, self.state_1 = self.state_1, self.state_0 if self.sensor_contact is not None: self.solver.update_contacts(self.contacts, self.state_0) self.sensor_contact.update(self.state_0, self.contacts) def step(self): if self.actuation == "random": joint_target = wp.array(self.rng.uniform(-1.0, 1.0, size=self.model.joint_dof_count), dtype=wp.float32) wp.copy(self.control.joint_target_pos, joint_target) wp.synchronize_device() start_time = time.time() if self.use_cuda_graph: wp.capture_launch(self.graph) else: self.simulate() wp.synchronize_device() end_time = time.time() self.benchmark_time += end_time - start_time self.sim_time += self.frame_dt def render(self): if self.renderer is None: return self.renderer.begin_frame(self.sim_time) self.renderer.log_state(self.state_0) self.renderer.end_frame() @staticmethod def create_model_builder(robot, world_count, environment="None", randomize=False, seed=123) -> newton.ModelBuilder: rng = np.random.default_rng(seed) articulation_builder = newton.ModelBuilder() articulation_builder.default_shape_cfg.ke = 1.0e3 articulation_builder.default_shape_cfg.kd = 1.0e2 newton.solvers.SolverMuJoCo.register_custom_attributes(articulation_builder) if robot == "humanoid": root_dofs = _setup_humanoid(articulation_builder) elif robot == "g1": root_dofs = _setup_g1(articulation_builder) elif robot == "h1": root_dofs = _setup_h1(articulation_builder) elif robot == "cartpole": root_dofs = _setup_cartpole(articulation_builder) elif robot == "ant": root_dofs = _setup_ant(articulation_builder) elif robot == "quadruped": root_dofs = _setup_quadruped(articulation_builder) elif robot == "allegro": root_dofs = _setup_allegro(articulation_builder) else: raise ValueError(f"Name of the provided robot not recognized: {robot}") custom_setup_fn = ROBOT_CONFIGS.get(environment, {}).get("setup_builder", None) if custom_setup_fn is not None: custom_setup_fn(articulation_builder) builder = newton.ModelBuilder() builder.replicate(articulation_builder, world_count) if randomize: njoint = len(articulation_builder.joint_q) for i in range(world_count): istart = i * njoint builder.joint_q[istart + root_dofs : istart + njoint] = rng.uniform( -1.0, 1.0, size=(njoint - root_dofs) ).tolist() builder.default_shape_cfg.ke = 1.0e3 builder.default_shape_cfg.kd = 1.0e2 if robot != "cartpole": # Disable all collisions for the cartpole benchmark builder.add_ground_plane() return builder @staticmethod def create_solver( model, robot, *, use_mujoco_cpu=False, environment="None", solver=None, integrator=None, solver_iteration=None, ls_iteration=None, njmax=None, nconmax=None, ls_parallel=None, cone=None, ): solver_iteration = solver_iteration if solver_iteration is not None else 100 ls_iteration = ls_iteration if ls_iteration is not None else 50 solver = solver if solver is not None else ROBOT_CONFIGS[robot]["solver"] integrator = integrator if integrator is not None else ROBOT_CONFIGS[robot]["integrator"] njmax = njmax if njmax is not None else ROBOT_CONFIGS[robot]["njmax"] nconmax = nconmax if nconmax is not None else ROBOT_CONFIGS[robot]["nconmax"] ls_parallel = ls_parallel if ls_parallel is not None else ROBOT_CONFIGS[robot]["ls_parallel"] cone = cone if cone is not None else ROBOT_CONFIGS[robot]["cone"] njmax += ROBOT_CONFIGS.get(environment, {}).get("njmax", 0) nconmax += ROBOT_CONFIGS.get(environment, {}).get("nconmax", 0) return newton.solvers.SolverMuJoCo( model, use_mujoco_cpu=use_mujoco_cpu, solver=solver, integrator=integrator, iterations=solver_iteration, ls_iterations=ls_iteration, njmax=njmax, nconmax=nconmax, ls_parallel=ls_parallel, cone=cone, ) def print_trace(trace, indent, steps): if indent == 0: print("================= Profiling =================") for k, v in trace.items(): times, sub_trace = v print(" " * indent + f"{k}: {times / steps:.4f}") print_trace(sub_trace, indent + 1, steps) if indent == 0: step_time = trace["step"][0] step_trace = trace["step"][1] mujoco_warp_step_time = step_trace["_mujoco_warp_step"][0] overhead = 100.0 * (step_time - mujoco_warp_step_time) / step_time print("---------------------------------------------") print(f"Newton overhead:\t{overhead:.2f} %") print("=============================================") if __name__ == "__main__": import argparse parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument("--robot", type=str, default="humanoid", help="Name of the robot to simulate.") parser.add_argument("--env", type=str, default="None", help="Name of the environment where the robot is located.") parser.add_argument( "--event-trace", default=False, action=argparse.BooleanOptionalAction, help="Print profiling information." ) parser.add_argument("--device", type=str, default=None, help="Override the default Warp device.") parser.add_argument( "--stage-path", type=lambda x: None if x == "None" else str(x), default=None, help="Path to the output USD file.", ) parser.add_argument("--num-frames", type=int, default=12000, help="Total number of frames.") parser.add_argument("--world-count", type=int, default=1, help="Total number of simulated worlds.") parser.add_argument("--use-cuda-graph", default=True, action=argparse.BooleanOptionalAction) parser.add_argument( "--use-mujoco-cpu", default=False, action=argparse.BooleanOptionalAction, help="Use Mujoco-C CPU (Not yet supported).", ) parser.add_argument( "--headless", default=False, action=argparse.BooleanOptionalAction, help="Run the simulation in headless mode." ) parser.add_argument( "--random-init", default=False, action=argparse.BooleanOptionalAction, help="Randomize initial pose." ) parser.add_argument( "--actuation", type=str, default="None", choices=["None", "random"], help="Type of action to apply at each step.", ) parser.add_argument( "--solver", type=str, default=None, choices=["cg", "newton"], help="Mujoco model constraint solver used." ) parser.add_argument( "--integrator", type=str, default=None, choices=["euler", "rk4", "implicit"], help="Mujoco integrator used." ) parser.add_argument("--solver-iteration", type=int, default=None, help="Number of solver iterations.") parser.add_argument("--ls-iteration", type=int, default=None, help="Number of linesearch iterations.") parser.add_argument("--njmax", type=int, default=None, help="Maximum number of constraints per world.") parser.add_argument("--nconmax", type=int, default=None, help="Maximum number of collision per world.") parser.add_argument( "--ls-parallel", default=None, action=argparse.BooleanOptionalAction, help="Use parallel line search." ) parser.add_argument("--cone", type=str, default=None, choices=["pyramidal", "elliptic"], help="Friction cone type.") args = parser.parse_known_args()[0] if args.use_mujoco_cpu: args.use_mujoco_cpu = False print("The option ``use-mujoco-cpu`` is not yet supported. Disabling it.") trace = {} with EventTracer(enabled=args.event_trace) as tracer: with wp.ScopedDevice(args.device): example = Example( robot=args.robot, environment=args.env, stage_path=args.stage_path, world_count=args.world_count, use_cuda_graph=args.use_cuda_graph, use_mujoco_cpu=args.use_mujoco_cpu, randomize=args.random_init, headless=args.headless, actuation=args.actuation, solver=args.solver, integrator=args.integrator, solver_iteration=args.solver_iteration, ls_iteration=args.ls_iteration, njmax=args.njmax, nconmax=args.nconmax, ls_parallel=args.ls_parallel, cone=args.cone, ) # Print simulation configuration summary LABEL_WIDTH = 25 TOTAL_WIDTH = 45 title = " Simulation Configuration " print(f"\n{title.center(TOTAL_WIDTH, '=')}") print(f"{'Simulation Steps':<{LABEL_WIDTH}}: {args.num_frames * example.sim_substeps}") print(f"{'World Count':<{LABEL_WIDTH}}: {args.world_count}") print(f"{'Robot Type':<{LABEL_WIDTH}}: {args.robot}") print(f"{'Timestep (dt)':<{LABEL_WIDTH}}: {example.sim_dt:.6f}s") print(f"{'Randomize Initial Pose':<{LABEL_WIDTH}}: {args.random_init!s}") print("-" * TOTAL_WIDTH) # Map MuJoCo solver enum back to string solver_value = example.solver.mj_model.opt.solver solver_map = {0: "PGS", 1: "CG", 2: "Newton"} # mjSOL_PGS = 0, mjSOL_CG = 1, mjSOL_NEWTON = 2 actual_solver = solver_map.get(solver_value, f"unknown({solver_value})") # Map MuJoCo integrator enum back to string integrator_map = { 0: "Euler", 1: "RK4", 2: "Implicit", 3: "Implicitfast", } # mjINT_EULER = 0, mjINT_RK4 = 1, mjINT_IMPLICIT = 2, mjINT_IMPLICITFAST = 3 actual_integrator = integrator_map.get(example.solver.mj_model.opt.integrator, "unknown") # Map MuJoCo cone enum back to string cone_value = example.solver.mj_model.opt.cone cone_map = {0: "pyramidal", 1: "elliptic"} # mjCONE_PYRAMIDAL = 0, mjCONE_ELLIPTIC = 1 actual_cone = cone_map.get(cone_value, f"unknown({cone_value})") # Get actual max constraints and contacts from MuJoCo Warp data actual_njmax = example.solver.mjw_data.njmax actual_nconmax = ( example.solver.mjw_data.naconmax // args.world_count if args.world_count > 0 else example.solver.mjw_data.naconmax ) print(f"{'Solver':<{LABEL_WIDTH}}: {actual_solver}") print(f"{'Integrator':<{LABEL_WIDTH}}: {actual_integrator}") # print(f"{'Parallel Line Search':<{LABEL_WIDTH}}: {example.solver.mj_model.opt.ls_parallel}") print(f"{'Cone':<{LABEL_WIDTH}}: {actual_cone}") print(f"{'Solver Iterations':<{LABEL_WIDTH}}: {example.solver.mj_model.opt.iterations}") print(f"{'Line Search Iterations':<{LABEL_WIDTH}}: {example.solver.mj_model.opt.ls_iterations}") print(f"{'Max Constraints / world':<{LABEL_WIDTH}}: {actual_njmax}") print(f"{'Max Contacts / world':<{LABEL_WIDTH}}: {actual_nconmax}") print(f"{'Joint DOFs':<{LABEL_WIDTH}}: {example.model.joint_dof_count}") print(f"{'Body Count':<{LABEL_WIDTH}}: {example.model.body_count}") print("-" * TOTAL_WIDTH) print(f"{'Execution Device':<{LABEL_WIDTH}}: {wp.get_device()}") print(f"{'Use CUDA Graph':<{LABEL_WIDTH}}: {example.use_cuda_graph!s}") print("=" * TOTAL_WIDTH + "\n") for _ in range(args.num_frames): example.step() example.render() if args.event_trace: trace = tracer.add_trace(trace, tracer.trace()) if args.event_trace: print_trace(trace, 0, args.num_frames * example.sim_substeps) ================================================ FILE: asv/benchmarks/compilation/__init__.py ================================================ ================================================ FILE: asv/benchmarks/compilation/bench_example_load.py ================================================ # SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers # SPDX-License-Identifier: Apache-2.0 import subprocess import sys import warp as wp wp.config.enable_backward = False wp.config.quiet = True from asv_runner.benchmarks.mark import skip_benchmark_if class SlowExampleRobotAnymal: warmup_time = 0 repeat = 2 number = 1 timeout = 600 def setup(self): wp.build.clear_lto_cache() wp.build.clear_kernel_cache() @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_load(self): """Time the amount of time it takes to load and run one frame of the example.""" command = [ sys.executable, "-m", "newton.examples.robot.example_robot_anymal_c_walk", "--num-frames", "1", "--viewer", "null", ] # Run the script as a subprocess subprocess.run(command, capture_output=True, text=True, check=True) class SlowExampleRobotCartpole: warmup_time = 0 repeat = 2 number = 1 timeout = 600 def setup(self): wp.build.clear_lto_cache() wp.build.clear_kernel_cache() @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_load(self): """Time the amount of time it takes to load and run one frame of the example.""" command = [ sys.executable, "-m", "newton.examples.robot.example_robot_cartpole", "--num-frames", "1", "--viewer", "null", ] # Run the script as a subprocess subprocess.run(command, capture_output=True, text=True, check=True) class SlowExampleClothFranka: warmup_time = 0 repeat = 2 number = 1 def setup(self): wp.build.clear_lto_cache() wp.build.clear_kernel_cache() @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_load(self): """Time the amount of time it takes to load and run one frame of the example.""" command = [ sys.executable, "-m", "newton.examples.cloth.example_cloth_franka", "--num-frames", "1", "--viewer", "null", ] # Run the script as a subprocess subprocess.run(command, capture_output=True, text=True, check=True) class SlowExampleClothTwist: warmup_time = 0 repeat = 2 number = 1 def setup(self): wp.build.clear_lto_cache() wp.build.clear_kernel_cache() @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_load(self): """Time the amount of time it takes to load and run one frame of the example.""" command = [ sys.executable, "-m", "newton.examples.cloth.example_cloth_twist", "--num-frames", "1", "--viewer", "null", ] # Run the script as a subprocess subprocess.run(command, capture_output=True, text=True, check=True) class SlowExampleBasicUrdf: warmup_time = 0 repeat = 2 number = 1 timeout = 600 def setup(self): wp.build.clear_lto_cache() wp.build.clear_kernel_cache() @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_load(self): """Time the amount of time it takes to load and run one frame of the example.""" command = [ sys.executable, "-m", "newton.examples.basic.example_basic_urdf", "--num-frames", "1", "--viewer", "null", ] # Run the script as a subprocess subprocess.run(command, capture_output=True, text=True, check=True) if __name__ == "__main__": import argparse from newton.utils import run_benchmark benchmark_list = { "SlowExampleBasicUrdf": SlowExampleBasicUrdf, "SlowExampleRobotAnymal": SlowExampleRobotAnymal, "SlowExampleRobotCartpole": SlowExampleRobotCartpole, "SlowExampleClothFranka": SlowExampleClothFranka, "SlowExampleClothTwist": SlowExampleClothTwist, } parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument( "-b", "--bench", default=None, action="append", choices=benchmark_list.keys(), help="Run a single benchmark." ) args = parser.parse_known_args()[0] if args.bench is None: benchmarks = benchmark_list.keys() else: benchmarks = args.bench for key in benchmarks: benchmark = benchmark_list[key] run_benchmark(benchmark) ================================================ FILE: asv/benchmarks/setup/__init__.py ================================================ ================================================ FILE: asv/benchmarks/setup/bench_model.py ================================================ # SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers # SPDX-License-Identifier: Apache-2.0 import gc import os import sys # Force headless mode for CI environments before any pyglet imports os.environ["PYGLET_HEADLESS"] = "1" import warp as wp wp.config.enable_backward = False wp.config.quiet = True from asv_runner.benchmarks.mark import skip_benchmark_if parent_dir = os.path.abspath(os.path.join(os.path.dirname(__file__), "..")) sys.path.append(parent_dir) from benchmark_mujoco import Example from newton.viewer import ViewerGL class KpiInitializeModel: params = (["humanoid", "g1", "cartpole"], [8192]) param_names = ["robot", "world_count"] rounds = 1 repeat = 3 number = 1 min_run_count = 1 timeout = 3600 def setup(self, robot, world_count): wp.init() @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_initialize_model(self, robot, world_count): builder = Example.create_model_builder(robot, world_count, randomize=True, seed=123) # finalize model _model = builder.finalize() wp.synchronize_device() class KpiInitializeSolver: params = (["humanoid", "g1", "cartpole", "ant"], [8192]) param_names = ["robot", "world_count"] rounds = 1 repeat = 3 number = 1 min_run_count = 1 timeout = 3600 def setup(self, robot, world_count): wp.init() builder = Example.create_model_builder(robot, world_count, randomize=True, seed=123) # finalize model self._model = builder.finalize() @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_initialize_solver(self, robot, world_count): self._solver = Example.create_solver(self._model, robot, use_mujoco_cpu=False) wp.synchronize_device() def teardown(self, robot, world_count): del self._solver del self._model class KpiInitializeViewerGL: params = (["g1"], [8192]) param_names = ["robot", "world_count"] rounds = 1 repeat = 3 number = 1 min_run_count = 1 def setup(self, robot, world_count): wp.init() builder = Example.create_model_builder(robot, world_count, randomize=True, seed=123) # finalize model self._model = builder.finalize() @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_initialize_renderer(self, robot, world_count): # Setting up the renderer self.renderer = ViewerGL(headless=True) self.renderer.set_model(self._model) wp.synchronize_device() self.renderer.close() def teardown(self, robot, world_count): del self._model class FastInitializeModel: params = (["humanoid", "g1", "cartpole"], [256]) param_names = ["robot", "world_count"] rounds = 1 repeat = 3 number = 1 min_run_count = 1 def setup_cache(self): # Load a small model to cache the kernels for robot in self.params[0]: builder = Example.create_model_builder(robot, 1, randomize=False, seed=123) model = builder.finalize(device="cpu") del model del builder @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_initialize_model(self, robot, world_count): builder = Example.create_model_builder(robot, world_count, randomize=True, seed=123) # finalize model _model = builder.finalize() wp.synchronize_device() def peakmem_initialize_model_cpu(self, robot, world_count): gc.collect() with wp.ScopedDevice("cpu"): builder = Example.create_model_builder(robot, world_count, randomize=True, seed=123) # finalize model model = builder.finalize() del model class FastInitializeSolver: params = (["humanoid", "g1", "cartpole"], [256]) param_names = ["robot", "world_count"] rounds = 1 repeat = 3 number = 1 min_run_count = 1 def setup(self, robot, world_count): wp.init() builder = Example.create_model_builder(robot, world_count, randomize=True, seed=123) # finalize model self._model = builder.finalize() @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_initialize_solver(self, robot, world_count): self._solver = Example.create_solver(self._model, robot, use_mujoco_cpu=False) wp.synchronize_device() def teardown(self, robot, world_count): del self._solver del self._model class FastInitializeViewerGL: params = (["g1"], [256]) param_names = ["robot", "world_count"] rounds = 1 repeat = 3 number = 1 min_run_count = 1 def setup(self, robot, world_count): wp.init() builder = Example.create_model_builder(robot, world_count, randomize=True, seed=123) # finalize model self._model = builder.finalize() @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_initialize_renderer(self, robot, world_count): # Setting up the renderer self.renderer = ViewerGL(headless=True) self.renderer.set_model(self._model) wp.synchronize_device() self.renderer.close() def teardown(self, robot, world_count): del self._model if __name__ == "__main__": import argparse from newton.utils import run_benchmark benchmark_list = { "KpiInitializeModel": KpiInitializeModel, "FastInitializeModel": FastInitializeModel, "KpiInitializeSolver": KpiInitializeSolver, "FastInitializeSolver": FastInitializeSolver, "KpiInitializeViewerGL": KpiInitializeViewerGL, "FastInitializeViewerGL": FastInitializeViewerGL, } parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument( "-b", "--bench", default=None, action="append", choices=benchmark_list.keys(), help="Run a single benchmark." ) args = parser.parse_known_args()[0] if args.bench is None: benchmarks = benchmark_list.keys() else: benchmarks = args.bench for key in benchmarks: benchmark = benchmark_list[key] run_benchmark(benchmark) ================================================ FILE: asv/benchmarks/simulation/__init__.py ================================================ ================================================ FILE: asv/benchmarks/simulation/bench_anymal.py ================================================ # SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers # SPDX-License-Identifier: Apache-2.0 import warp as wp from asv_runner.benchmarks.mark import skip_benchmark_if wp.config.enable_backward = False wp.config.quiet = True import newton import newton.examples from newton.examples.robot.example_robot_anymal_c_walk import Example class FastExampleAnymalPretrained: repeat = 3 number = 1 def setup(self): self.num_frames = 50 if hasattr(newton.examples, "default_args"): args = newton.examples.default_args() else: args = None self.example = Example(newton.viewer.ViewerNull(num_frames=self.num_frames), args) @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_simulate(self): for _ in range(self.num_frames): self.example.step() wp.synchronize_device() if __name__ == "__main__": import argparse from newton.utils import run_benchmark benchmark_list = { "FastExampleAnymalPretrained": FastExampleAnymalPretrained, } parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument( "-b", "--bench", default=None, action="append", choices=benchmark_list.keys(), help="Run a single benchmark." ) args = parser.parse_known_args()[0] if args.bench is None: benchmarks = benchmark_list.keys() else: benchmarks = args.bench for key in benchmarks: benchmark = benchmark_list[key] run_benchmark(benchmark) ================================================ FILE: asv/benchmarks/simulation/bench_cable.py ================================================ # SPDX-FileCopyrightText: Copyright (c) 2026 The Newton Developers # SPDX-License-Identifier: Apache-2.0 import warp as wp from asv_runner.benchmarks.mark import skip_benchmark_if wp.config.enable_backward = False wp.config.quiet = True import newton.examples from newton.examples.cable.example_cable_pile import Example as ExampleCablePile from newton.viewer import ViewerNull class FastExampleCablePile: number = 1 rounds = 2 repeat = 2 def setup(self): self.num_frames = 30 if hasattr(newton.examples, "default_args"): args = newton.examples.default_args() else: args = None self.example = ExampleCablePile(ViewerNull(num_frames=self.num_frames), args) wp.synchronize_device() @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_simulate(self): newton.examples.run(self.example, args=None) wp.synchronize_device() if __name__ == "__main__": import argparse from newton.utils import run_benchmark benchmark_list = { "FastExampleCablePile": FastExampleCablePile, } parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument( "-b", "--bench", default=None, action="append", choices=benchmark_list.keys(), help="Run a single benchmark." ) args = parser.parse_known_args()[0] if args.bench is None: benchmarks = benchmark_list.keys() else: benchmarks = args.bench for key in benchmarks: benchmark = benchmark_list[key] run_benchmark(benchmark) ================================================ FILE: asv/benchmarks/simulation/bench_cloth.py ================================================ # SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers # SPDX-License-Identifier: Apache-2.0 import warp as wp from asv_runner.benchmarks.mark import skip_benchmark_if wp.config.quiet = True import newton.examples from newton.examples.cloth.example_cloth_franka import Example as ExampleClothManipulation from newton.examples.cloth.example_cloth_twist import Example as ExampleClothTwist from newton.viewer import ViewerNull class FastExampleClothManipulation: timeout = 300 repeat = 3 number = 1 def setup(self): self.num_frames = 30 if hasattr(newton.examples, "default_args"): args = newton.examples.default_args() else: args = None self.example = ExampleClothManipulation(ViewerNull(num_frames=self.num_frames), args) @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_simulate(self): newton.examples.run(self.example, args=None) wp.synchronize_device() class FastExampleClothTwist: repeat = 5 number = 1 def setup(self): self.num_frames = 100 if hasattr(newton.examples, "default_args"): args = newton.examples.default_args() else: args = None self.example = ExampleClothTwist(ViewerNull(num_frames=self.num_frames), args) @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_simulate(self): newton.examples.run(self.example, None) wp.synchronize_device() if __name__ == "__main__": import argparse from newton.utils import run_benchmark benchmark_list = { "FastExampleClothManipulation": FastExampleClothManipulation, "FastExampleClothTwist": FastExampleClothTwist, } parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument( "-b", "--bench", default=None, action="append", choices=benchmark_list.keys(), help="Run a single benchmark." ) args = parser.parse_known_args()[0] if args.bench is None: benchmarks = benchmark_list.keys() else: benchmarks = args.bench for key in benchmarks: benchmark = benchmark_list[key] run_benchmark(benchmark) ================================================ FILE: asv/benchmarks/simulation/bench_contacts.py ================================================ # SPDX-FileCopyrightText: Copyright (c) 2026 The Newton Developers # SPDX-License-Identifier: Apache-2.0 import warp as wp from asv_runner.benchmarks.mark import SkipNotImplemented, skip_benchmark_if wp.config.enable_backward = False wp.config.quiet = True import importlib import newton.examples from newton.viewer import ViewerNull ISAACGYM_ENVS_REPO_URL = "https://github.com/isaac-sim/IsaacGymEnvs.git" ISAACGYM_NUT_BOLT_FOLDER = "assets/factory/mesh/factory_nut_bolt" try: from newton.examples import download_external_git_folder as _download_external_git_folder except ImportError: from newton._src.utils.download_assets import download_git_folder as _download_external_git_folder def _import_example_class(module_names: list[str]): """Import and return the ``Example`` class from candidate modules. Args: module_names: Ordered module names to try importing. Returns: The first successfully imported module's ``Example`` class. Raises: SkipNotImplemented: If none of the module names can be imported. """ for module_name in module_names: try: module = importlib.import_module(module_name) except ModuleNotFoundError: continue return module.Example raise SkipNotImplemented class FastExampleContactSdfDefaults: """Benchmark the SDF nut-bolt example default configuration.""" repeat = 2 number = 1 def setup_cache(self): _download_external_git_folder(ISAACGYM_ENVS_REPO_URL, ISAACGYM_NUT_BOLT_FOLDER) def setup(self): example_cls = _import_example_class( [ "newton.examples.contacts.example_nut_bolt_sdf", ] ) self.num_frames = 20 if hasattr(newton.examples, "default_args") and hasattr(example_cls, "create_parser"): args = newton.examples.default_args(example_cls.create_parser()) self.example = example_cls(ViewerNull(num_frames=self.num_frames), args) else: self.example = example_cls( viewer=ViewerNull(num_frames=self.num_frames), world_count=100, num_per_world=1, scene="nut_bolt", solver="mujoco", test_mode=False, ) @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_simulate(self): for _ in range(self.num_frames): self.example.step() wp.synchronize_device() class FastExampleContactHydroWorkingDefaults: """Benchmark the hydroelastic nut-bolt example default configuration.""" repeat = 2 number = 1 def setup_cache(self): _download_external_git_folder(ISAACGYM_ENVS_REPO_URL, ISAACGYM_NUT_BOLT_FOLDER) def setup(self): example_cls = _import_example_class( [ "newton.examples.contacts.example_nut_bolt_hydro", ] ) self.num_frames = 20 if hasattr(newton.examples, "default_args") and hasattr(example_cls, "create_parser"): args = newton.examples.default_args(example_cls.create_parser()) self.example = example_cls(ViewerNull(num_frames=self.num_frames), args) else: self.example = example_cls( viewer=ViewerNull(num_frames=self.num_frames), world_count=20, num_per_world=1, scene="nut_bolt", solver="mujoco", test_mode=False, ) @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_simulate(self): for _ in range(self.num_frames): self.example.step() wp.synchronize_device() class FastExampleContactPyramidDefaults: """Benchmark the box pyramid example with default configuration.""" repeat = 2 number = 1 def setup(self): example_cls = _import_example_class( [ "newton.examples.contacts.example_pyramid", ] ) self.num_frames = 20 if hasattr(newton.examples, "default_args") and hasattr(example_cls, "create_parser"): args = newton.examples.default_args(example_cls.create_parser()) self.example = example_cls(ViewerNull(num_frames=self.num_frames), args) else: self.example = example_cls( viewer=ViewerNull(num_frames=self.num_frames), solver="xpbd", test_mode=False, ) @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_simulate(self): for _ in range(self.num_frames): self.example.step() wp.synchronize_device() if __name__ == "__main__": import argparse from newton.utils import run_benchmark benchmark_list = { "FastExampleContactSdfDefaults": FastExampleContactSdfDefaults, "FastExampleContactHydroWorkingDefaults": FastExampleContactHydroWorkingDefaults, "FastExampleContactPyramidDefaults": FastExampleContactPyramidDefaults, } parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument( "-b", "--bench", default=None, action="append", choices=benchmark_list.keys(), help="Run a single benchmark." ) args = parser.parse_known_args()[0] if args.bench is None: benchmarks = benchmark_list.keys() else: benchmarks = args.bench for key in benchmarks: benchmark = benchmark_list[key] run_benchmark(benchmark) ================================================ FILE: asv/benchmarks/simulation/bench_heightfield.py ================================================ # SPDX-FileCopyrightText: Copyright (c) 2026 The Newton Developers # SPDX-License-Identifier: Apache-2.0 import warp as wp from asv_runner.benchmarks.mark import SkipNotImplemented, skip_benchmark_if wp.config.enable_backward = False wp.config.quiet = True import numpy as np import newton def _build_heightfield_scene(num_bodies=200, nrow=100, ncol=100): """Build a scene with many spheres dropped onto a large heightfield.""" builder = newton.ModelBuilder() hx, hy = 20.0, 20.0 x = np.linspace(-hx, hx, ncol) y = np.linspace(-hy, hy, nrow) xx, yy = np.meshgrid(x, y) elevation = np.sin(xx * 0.5) * np.cos(yy * 0.5) * 1.0 hfield = newton.Heightfield(data=elevation, nrow=nrow, ncol=ncol, hx=hx, hy=hy) builder.add_shape_heightfield(heightfield=hfield) # Grid of spheres above the terrain grid_size = int(np.ceil(np.sqrt(num_bodies))) spacing = 2.0 * hx / (grid_size + 1) count = 0 for i in range(grid_size): for j in range(grid_size): if count >= num_bodies: break x_pos = -hx + spacing * (i + 1) y_pos = -hy + spacing * (j + 1) body = builder.add_body( xform=wp.transform(p=wp.vec3(x_pos, y_pos, 3.0), q=wp.quat_identity()), ) builder.add_shape_sphere(body=body, radius=0.3) count += 1 model = builder.finalize() model.rigid_contact_max = num_bodies * 20 return model class HeightfieldCollision: """Benchmark heightfield collision with many spheres on a 100x100 grid.""" repeat = 8 number = 1 def setup(self): cuda_graph_comp = wp.get_device().is_cuda and wp.is_mempool_enabled(wp.get_device()) if not cuda_graph_comp: raise SkipNotImplemented self.num_frames = 50 self.model = _build_heightfield_scene(num_bodies=200, nrow=100, ncol=100) self.solver = newton.solvers.SolverXPBD(self.model, iterations=10) self.contacts = self.model.contacts() self.state_0 = self.model.state() self.state_1 = self.model.state() self.control = self.model.control() self.sim_substeps = 10 self.sim_dt = (1.0 / 100.0) / self.sim_substeps wp.synchronize_device() with wp.ScopedCapture() as capture: for _sub in range(self.sim_substeps): self.state_0.clear_forces() self.model.collide(self.state_0, self.contacts) self.solver.step(self.state_0, self.state_1, self.control, self.contacts, self.sim_dt) self.state_0, self.state_1 = self.state_1, self.state_0 self.graph = capture.graph wp.synchronize_device() @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_simulate(self): for _frame in range(self.num_frames): wp.capture_launch(self.graph) wp.synchronize_device() if __name__ == "__main__": import argparse from newton.utils import run_benchmark benchmark_list = { "HeightfieldCollision": HeightfieldCollision, } parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument( "-b", "--bench", default=None, action="append", choices=benchmark_list.keys(), help="Run a single benchmark." ) args = parser.parse_known_args()[0] if args.bench is None: benchmarks = benchmark_list.keys() else: benchmarks = args.bench for key in benchmarks: benchmark = benchmark_list[key] run_benchmark(benchmark) ================================================ FILE: asv/benchmarks/simulation/bench_ik.py ================================================ # SPDX-FileCopyrightText: Copyright (c) 2026 The Newton Developers # SPDX-License-Identifier: Apache-2.0 from __future__ import annotations import os import sys import numpy as np import warp as wp from asv_runner.benchmarks.mark import SkipNotImplemented, skip_benchmark_if wp.config.quiet = True wp.config.enable_backward = False parent_dir = os.path.abspath(os.path.join(os.path.dirname(__file__), "..")) sys.path.append(parent_dir) from benchmark_ik import build_ik_solver, create_franka_model, eval_success, fk_targets, random_solutions class _IKBenchmark: """Utility base class for IK benchmarks.""" params = None param_names = ["batch_size"] repeat = None number = 1 rounds = 2 EE_LINKS = (9,) ITERATIONS = 16 STEP_SIZE = 1.0 POS_THRESH_M = 5e-3 ORI_THRESH_RAD = 0.05 SEED = 123 NUM_SOLVES = 50 def setup(self, batch_size): if not (wp.get_device().is_cuda and wp.is_mempool_enabled(wp.get_device())): raise SkipNotImplemented self.model = create_franka_model() self.solver, self.pos_obj, self.rot_obj = build_ik_solver(self.model, batch_size, self.EE_LINKS) self.n_coords = self.model.joint_coord_count rng = np.random.default_rng(self.SEED) q_gt = random_solutions(self.model, batch_size, rng) self.tgt_p, self.tgt_r = fk_targets(self.solver, self.model, q_gt, self.EE_LINKS) self.winners_d = wp.zeros((batch_size, self.n_coords), dtype=wp.float32) self.seeds_d = wp.zeros((batch_size, self.n_coords), dtype=wp.float32) # Set targets for ee in range(len(self.EE_LINKS)): self.pos_obj[ee].set_target_positions( wp.array(self.tgt_p[:, ee].astype(np.float32, copy=False), dtype=wp.vec3) ) self.rot_obj[ee].set_target_rotations( wp.array(self.tgt_r[:, ee].astype(np.float32, copy=False), dtype=wp.vec4) ) with wp.ScopedCapture() as cap: self.solver.step(self.seeds_d, self.winners_d, iterations=self.ITERATIONS, step_size=self.STEP_SIZE) self.solve_graph = cap.graph @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_solve(self, batch_size): for _ in range(self.NUM_SOLVES): wp.capture_launch(self.solve_graph) wp.synchronize_device() def teardown(self, batch_size): q_best = self.winners_d.numpy() success = eval_success( self.solver, self.model, q_best, self.tgt_p, self.tgt_r, self.EE_LINKS, self.POS_THRESH_M, self.ORI_THRESH_RAD, ) if not success.all(): n_failed = int((~success).sum()) raise RuntimeError(f"IK failed for {n_failed}/{batch_size} problems") class FastIKSolve(_IKBenchmark): params = ([512],) repeat = 6 if __name__ == "__main__": import argparse from newton.utils import run_benchmark benchmark_list = { "FastSolve": FastIKSolve, } parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument( "-b", "--bench", default=None, action="append", choices=benchmark_list.keys(), help="Run a single benchmark." ) args = parser.parse_known_args()[0] if args.bench is None: benchmarks = benchmark_list.keys() else: benchmarks = args.bench for key in benchmarks: benchmark = benchmark_list[key] run_benchmark(benchmark) ================================================ FILE: asv/benchmarks/simulation/bench_mujoco.py ================================================ # SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers # SPDX-License-Identifier: Apache-2.0 import os import sys import warp as wp wp.config.enable_backward = False wp.config.quiet = True from asv_runner.benchmarks.mark import SkipNotImplemented, skip_benchmark_if parent_dir = os.path.abspath(os.path.join(os.path.dirname(__file__), "..")) sys.path.append(parent_dir) from benchmark_mujoco import Example from newton.utils import EventTracer @wp.kernel def apply_random_control(state: wp.uint32, joint_target: wp.array[float]): tid = wp.tid() joint_target[tid] = wp.randf(state) * 2.0 - 1.0 class _FastBenchmark: """Utility base class for fast benchmarks.""" num_frames = None robot = None number = 1 rounds = 2 repeat = None world_count = None random_init = None environment = "None" def setup(self): if not hasattr(self, "builder") or self.builder is None: self.builder = Example.create_model_builder( self.robot, self.world_count, randomize=self.random_init, seed=123 ) self.example = Example( stage_path=None, robot=self.robot, randomize=self.random_init, headless=True, actuation="None", use_cuda_graph=True, builder=self.builder, environment=self.environment, ) wp.synchronize_device() # Recapture the graph with control application included cuda_graph_comp = wp.get_device().is_cuda and wp.is_mempool_enabled(wp.get_device()) if not cuda_graph_comp: raise SkipNotImplemented else: state = wp.rand_init(self.example.seed) with wp.ScopedCapture() as capture: wp.launch( apply_random_control, dim=(self.example.model.joint_dof_count,), inputs=[state], outputs=[self.example.control.joint_target_pos], ) self.example.simulate() self.graph = capture.graph wp.synchronize_device() def time_simulate(self): for _ in range(self.num_frames): wp.capture_launch(self.graph) wp.synchronize_device() class _KpiBenchmark: """Utility base class for KPI benchmarks.""" param_names = ["world_count"] num_frames = None params = None robot = None samples = None ls_iteration = None random_init = None environment = "None" def setup(self, world_count): if not hasattr(self, "builder") or self.builder is None: self.builder = {} if world_count not in self.builder: self.builder[world_count] = Example.create_model_builder( self.robot, world_count, randomize=self.random_init, seed=123 ) @skip_benchmark_if(wp.get_cuda_device_count() == 0) def track_simulate(self, world_count): total_time = 0.0 for _iter in range(self.samples): example = Example( stage_path=None, robot=self.robot, randomize=self.random_init, headless=True, actuation="random", use_cuda_graph=True, builder=self.builder[world_count], ls_iteration=self.ls_iteration, environment=self.environment, ) wp.synchronize_device() for _ in range(self.num_frames): example.step() wp.synchronize_device() total_time += example.benchmark_time return total_time * 1000 / (self.num_frames * example.sim_substeps * world_count * self.samples) track_simulate.unit = "ms/world-step" class _NewtonOverheadBenchmark: """Utility base class for measuring Newton overhead.""" param_names = ["world_count"] num_frames = None params = None robot = None samples = None ls_iteration = None random_init = None def setup(self, world_count): if not hasattr(self, "builder") or self.builder is None: self.builder = {} if world_count not in self.builder: self.builder[world_count] = Example.create_model_builder( self.robot, world_count, randomize=self.random_init, seed=123 ) @skip_benchmark_if(wp.get_cuda_device_count() == 0) def track_simulate(self, world_count): trace = {} with EventTracer(enabled=True) as tracer: for _iter in range(self.samples): example = Example( stage_path=None, robot=self.robot, randomize=self.random_init, headless=True, actuation="random", world_count=world_count, use_cuda_graph=True, builder=self.builder[world_count], ls_iteration=self.ls_iteration, ) for _ in range(self.num_frames): example.step() trace = tracer.add_trace(trace, tracer.trace()) step_time = trace["step"][0] step_trace = trace["step"][1] mujoco_warp_step_time = step_trace["_mujoco_warp_step"][0] overhead = 100.0 * (step_time - mujoco_warp_step_time) / step_time return overhead track_simulate.unit = "%" class FastCartpole(_FastBenchmark): num_frames = 50 robot = "cartpole" repeat = 8 world_count = 256 random_init = True environment = "None" class KpiCartpole(_KpiBenchmark): params = [[8192]] num_frames = 50 robot = "cartpole" samples = 4 ls_iteration = 3 random_init = True environment = "None" class FastG1(_FastBenchmark): num_frames = 25 robot = "g1" repeat = 2 world_count = 256 random_init = True environment = "None" class KpiG1(_KpiBenchmark): params = [[8192]] num_frames = 50 robot = "g1" timeout = 900 samples = 2 ls_iteration = 10 random_init = True environment = "None" class FastNewtonOverheadG1(_NewtonOverheadBenchmark): params = [[256]] num_frames = 25 robot = "g1" repeat = 2 samples = 1 random_init = True class KpiNewtonOverheadG1(_NewtonOverheadBenchmark): params = [[8192]] num_frames = 50 robot = "g1" timeout = 900 samples = 2 ls_iteration = 10 random_init = True class FastHumanoid(_FastBenchmark): num_frames = 50 robot = "humanoid" repeat = 8 world_count = 256 random_init = True environment = "None" class KpiHumanoid(_KpiBenchmark): params = [[8192]] num_frames = 100 robot = "humanoid" samples = 4 ls_iteration = 15 random_init = True environment = "None" class FastNewtonOverheadHumanoid(_NewtonOverheadBenchmark): params = [[256]] num_frames = 50 robot = "humanoid" repeat = 8 samples = 1 random_init = True class KpiNewtonOverheadHumanoid(_NewtonOverheadBenchmark): params = [[8192]] num_frames = 100 robot = "humanoid" samples = 4 ls_iteration = 15 random_init = True class FastAllegro(_FastBenchmark): num_frames = 100 robot = "allegro" repeat = 2 world_count = 256 random_init = False environment = "None" class KpiAllegro(_KpiBenchmark): params = [[8192]] num_frames = 300 robot = "allegro" samples = 2 ls_iteration = 10 random_init = False environment = "None" class FastKitchenG1(_FastBenchmark): num_frames = 25 robot = "g1" repeat = 2 world_count = 32 random_init = True environment = "kitchen" class KpiKitchenG1(_KpiBenchmark): params = [[512]] num_frames = 50 robot = "g1" timeout = 900 samples = 2 ls_iteration = 10 random_init = True environment = "kitchen" if __name__ == "__main__": import argparse from newton.utils import run_benchmark benchmark_list = { "FastCartpole": FastCartpole, "FastG1": FastG1, "FastHumanoid": FastHumanoid, "FastAllegro": FastAllegro, "FastKitchenG1": FastKitchenG1, "FastNewtonOverheadG1": FastNewtonOverheadG1, "FastNewtonOverheadHumanoid": FastNewtonOverheadHumanoid, "KpiCartpole": KpiCartpole, "KpiG1": KpiG1, "KpiHumanoid": KpiHumanoid, "KpiAllegro": KpiAllegro, "KpiKitchenG1": KpiKitchenG1, "KpiNewtonOverheadG1": KpiNewtonOverheadG1, "KpiNewtonOverheadHumanoid": KpiNewtonOverheadHumanoid, } parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument( "-b", "--bench", default=None, action="append", choices=benchmark_list.keys(), help="Run a single benchmark." ) args = parser.parse_known_args()[0] if args.bench is None: benchmarks = benchmark_list.keys() else: benchmarks = args.bench for key in benchmarks: benchmark = benchmark_list[key] run_benchmark(benchmark) ================================================ FILE: asv/benchmarks/simulation/bench_quadruped_xpbd.py ================================================ # SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers # SPDX-License-Identifier: Apache-2.0 import warp as wp from asv_runner.benchmarks.mark import skip_benchmark_if wp.config.enable_backward = False wp.config.quiet = True import newton import newton.examples from newton.examples.basic.example_basic_urdf import Example class FastExampleQuadrupedXPBD: repeat = 10 number = 1 def setup(self): self.num_frames = 1000 if hasattr(newton.examples, "default_args") and hasattr(Example, "create_parser"): args = newton.examples.default_args(Example.create_parser()) args.world_count = 200 self.example = Example(newton.viewer.ViewerNull(num_frames=self.num_frames), args) else: self.example = Example(newton.viewer.ViewerNull(num_frames=self.num_frames), 200) @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_simulate(self): for _ in range(self.num_frames): self.example.step() wp.synchronize_device() if __name__ == "__main__": import argparse from newton.utils import run_benchmark benchmark_list = { "FastExampleQuadrupedXPBD": FastExampleQuadrupedXPBD, } parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument( "-b", "--bench", default=None, action="append", choices=benchmark_list.keys(), help="Run a single benchmark." ) args = parser.parse_known_args()[0] if args.bench is None: benchmarks = benchmark_list.keys() else: benchmarks = args.bench for key in benchmarks: benchmark = benchmark_list[key] run_benchmark(benchmark) ================================================ FILE: asv/benchmarks/simulation/bench_selection.py ================================================ # SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers # SPDX-License-Identifier: Apache-2.0 import warp as wp from asv_runner.benchmarks.mark import skip_benchmark_if wp.config.enable_backward = False wp.config.quiet = True import newton import newton.examples from newton.examples.selection.example_selection_cartpole import Example class FastExampleSelectionCartpoleMuJoCo: repeat = 10 number = 1 def setup(self): self.num_frames = 200 if hasattr(newton.examples, "default_args") and hasattr(Example, "create_parser"): args = newton.examples.default_args(Example.create_parser()) self.example = Example(newton.viewer.ViewerNull(num_frames=self.num_frames), args) else: self.example = Example( viewer=newton.viewer.ViewerNull(num_frames=self.num_frames), world_count=16, verbose=False ) @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_simulate(self): for _ in range(self.num_frames): self.example.step() wp.synchronize_device() if __name__ == "__main__": import argparse from newton.utils import run_benchmark benchmark_list = { "FastExampleSelectionCartpoleMuJoCo": FastExampleSelectionCartpoleMuJoCo, } parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument( "-b", "--bench", default=None, action="append", choices=benchmark_list.keys(), help="Run a single benchmark." ) args = parser.parse_known_args()[0] if args.bench is None: benchmarks = benchmark_list.keys() else: benchmarks = args.bench for key in benchmarks: benchmark = benchmark_list[key] run_benchmark(benchmark) ================================================ FILE: asv/benchmarks/simulation/bench_sensor_tiled_camera.py ================================================ # SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers # SPDX-License-Identifier: Apache-2.0 import warp as wp from asv_runner.benchmarks.mark import skip_benchmark_if wp.config.enable_backward = False wp.config.quiet = True import math import newton from newton.sensors import SensorTiledCamera NICE_NAMES = {} def nice_name(value): def decorator(func): func._nice_name = value return func return decorator def nice_name_collector(): def decorator(instance): for name, attr in instance.__dict__.items(): if nice_name := getattr(attr, "_nice_name", None): NICE_NAMES[name] = nice_name return instance return decorator @nice_name_collector() class SensorTiledCameraBenchmark: param_names = ["resolution", "world_count", "iterations"] params = ([64], [4096], [50]) def setup(self, resolution: int, world_count: int, iterations: int): self.device = wp.get_preferred_device() franka = newton.ModelBuilder() franka.add_urdf( newton.utils.download_asset("franka_emika_panda") / "urdf/fr3_franka_hand.urdf", floating=False, ) scene = newton.ModelBuilder() scene.replicate(franka, world_count) scene.add_ground_plane() self.model = scene.finalize() self.state = self.model.state() newton.eval_fk(self.model, self.model.joint_q, self.model.joint_qd, self.state) self.camera_transforms = wp.array( [ [ wp.transformf( wp.vec3f(2.4, 0.0, 0.8), wp.quatf(0.4187639653682709, 0.4224344491958618, 0.5708873867988586, 0.5659270882606506), ) ] * world_count ], dtype=wp.transformf, ) self.tiled_camera_sensor = SensorTiledCamera(model=self.model) self.tiled_camera_sensor.utils.create_default_light(enable_shadows=False) self.tiled_camera_sensor.utils.assign_checkerboard_material_to_all_shapes() self.camera_rays = self.tiled_camera_sensor.utils.compute_pinhole_camera_rays( resolution, resolution, math.radians(45.0) ) self.color_image = self.tiled_camera_sensor.utils.create_color_image_output(resolution, resolution) self.depth_image = self.tiled_camera_sensor.utils.create_depth_image_output(resolution, resolution) self.tiled_camera_sensor.sync_transforms(self.state) # Warmup Kernels self.tiled_camera_sensor.render_config.render_order = SensorTiledCamera.RenderOrder.TILED self.tiled_camera_sensor.render_config.tile_width = 8 self.tiled_camera_sensor.render_config.tile_height = 8 for out_color, out_depth in [(True, True), (True, False), (False, True)]: for _ in range(iterations): self.tiled_camera_sensor.update( None, self.camera_transforms, self.camera_rays, color_image=self.color_image if out_color else None, depth_image=self.depth_image if out_depth else None, ) self.tiled_camera_sensor.render_config.render_order = SensorTiledCamera.RenderOrder.PIXEL_PRIORITY for out_color, out_depth in [(True, True), (True, False), (False, True)]: for _ in range(iterations): self.tiled_camera_sensor.update( None, self.camera_transforms, self.camera_rays, color_image=self.color_image if out_color else None, depth_image=self.depth_image if out_depth else None, ) @nice_name("Rendering (Pixel)") @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_rendering_pixel_priority_color_depth(self, resolution: int, world_count: int, iterations: int): self.tiled_camera_sensor.render_config.render_order = SensorTiledCamera.RenderOrder.PIXEL_PRIORITY for _ in range(iterations): self.tiled_camera_sensor.update( None, self.camera_transforms, self.camera_rays, color_image=self.color_image, depth_image=self.depth_image, refit_bvh=False, ) wp.synchronize() @nice_name("Rendering (Pixel) (Color Only)") @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_rendering_pixel_priority_color_only(self, resolution: int, world_count: int, iterations: int): self.tiled_camera_sensor.render_config.render_order = SensorTiledCamera.RenderOrder.PIXEL_PRIORITY for _ in range(iterations): self.tiled_camera_sensor.update( None, self.camera_transforms, self.camera_rays, color_image=self.color_image, refit_bvh=False, ) wp.synchronize() @nice_name("Rendering (Pixel) (Depth Only)") @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_rendering_pixel_priority_depth_only(self, resolution: int, world_count: int, iterations: int): self.tiled_camera_sensor.render_config.render_order = SensorTiledCamera.RenderOrder.PIXEL_PRIORITY for _ in range(iterations): self.tiled_camera_sensor.update( None, self.camera_transforms, self.camera_rays, depth_image=self.depth_image, refit_bvh=False, ) wp.synchronize() @nice_name("Rendering (Tiled)") @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_rendering_tiled_color_depth(self, resolution: int, world_count: int, iterations: int): self.tiled_camera_sensor.render_config.render_order = SensorTiledCamera.RenderOrder.TILED self.tiled_camera_sensor.render_config.tile_width = 8 self.tiled_camera_sensor.render_config.tile_height = 8 for _ in range(iterations): self.tiled_camera_sensor.update( None, self.camera_transforms, self.camera_rays, color_image=self.color_image, depth_image=self.depth_image, refit_bvh=False, ) wp.synchronize() @nice_name("Rendering (Tiled) (Color Only)") @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_rendering_tiled_color_only(self, resolution: int, world_count: int, iterations: int): self.tiled_camera_sensor.render_config.render_order = SensorTiledCamera.RenderOrder.TILED self.tiled_camera_sensor.render_config.tile_width = 8 self.tiled_camera_sensor.render_config.tile_height = 8 for _ in range(iterations): self.tiled_camera_sensor.update( None, self.camera_transforms, self.camera_rays, color_image=self.color_image, refit_bvh=False, ) wp.synchronize() @nice_name("Rendering (Tiled) (Depth Only)") @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_rendering_tiled_depth_only(self, resolution: int, world_count: int, iterations: int): self.tiled_camera_sensor.render_config.render_order = SensorTiledCamera.RenderOrder.TILED self.tiled_camera_sensor.render_config.tile_width = 8 self.tiled_camera_sensor.render_config.tile_height = 8 for _ in range(iterations): self.tiled_camera_sensor.update( None, self.camera_transforms, self.camera_rays, depth_image=self.depth_image, refit_bvh=False, ) wp.synchronize() def print_fps(name: str, duration: float, resolution: int, world_count: int, iterations: int): camera_count = 1 title = f"{name}" if iterations > 1: title += " average" average = f"{duration * 1000.0 / iterations:.2f} ms" fps = f"({(1.0 / (duration / iterations) * (world_count * camera_count)):,.2f} fps)" print(f"{title} {'.' * (50 - len(title) - len(average))} {average} {fps if iterations > 1 else ''}") def print_fps_results(results: dict[tuple[str, tuple[int, int, int]], float]): print("") print("=== Benchmark Results (FPS) ===") for (method_name, params), avg in results.items(): print_fps(NICE_NAMES.get(method_name, method_name), avg, *params) print("") if __name__ == "__main__": from newton.utils import run_benchmark results = run_benchmark(SensorTiledCameraBenchmark) print_fps_results(results) ================================================ FILE: asv/benchmarks/simulation/bench_viewer.py ================================================ # SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers # SPDX-License-Identifier: Apache-2.0 import os import sys # Force headless mode for CI environments before any pyglet imports os.environ["PYGLET_HEADLESS"] = "1" import warp as wp wp.config.enable_backward = False wp.config.quiet = True from asv_runner.benchmarks.mark import skip_benchmark_if parent_dir = os.path.abspath(os.path.join(os.path.dirname(__file__), "..")) sys.path.append(parent_dir) from benchmark_mujoco import Example from newton.viewer import ViewerGL class KpiViewerGL: params = (["g1"], [8192]) param_names = ["robot", "world_count"] rounds = 1 repeat = 3 number = 1 min_run_count = 1 def setup(self, robot, world_count): wp.init() builder = Example.create_model_builder(robot, world_count, randomize=True, seed=123) # finalize model self._model = builder.finalize() self._state = self._model.state() # Setting up the renderer self.renderer = ViewerGL(headless=True) self.renderer.set_model(self._model) @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_rendering_frame(self, robot, world_count): # Rendering one frame self.renderer.begin_frame(0.0) self.renderer.log_state(self._state) self.renderer.end_frame() wp.synchronize_device() def teardown(self, robot, world_count): self.renderer.close() del self.renderer del self._model del self._state class FastViewerGL: params = (["g1"], [256]) param_names = ["robot", "world_count"] rounds = 1 repeat = 3 number = 1 min_run_count = 1 def setup(self, robot, world_count): wp.init() builder = Example.create_model_builder(robot, world_count, randomize=True, seed=123) # finalize model self._model = builder.finalize() self._state = self._model.state() # Setting up the renderer self.renderer = ViewerGL(headless=True) self.renderer.set_model(self._model) @skip_benchmark_if(wp.get_cuda_device_count() == 0) def time_rendering_frame(self, robot, world_count): # Rendering one frame self.renderer.begin_frame(0.0) self.renderer.log_state(self._state) self.renderer.end_frame() wp.synchronize_device() def teardown(self, robot, world_count): self.renderer.close() del self.renderer del self._model del self._state if __name__ == "__main__": import argparse from newton.utils import run_benchmark benchmark_list = { "KpiViewerGL": KpiViewerGL, "FastViewerGL": FastViewerGL, } parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument( "-b", "--bench", default=None, action="append", choices=benchmark_list.keys(), help="Run a single benchmark." ) args = parser.parse_known_args()[0] if args.bench is None: benchmarks = benchmark_list.keys() else: benchmarks = args.bench for key in benchmarks: benchmark = benchmark_list[key] run_benchmark(benchmark) ================================================ FILE: asv.conf.json ================================================ { "version": 1, "project": "newton", "project_url": "https://github.com/newton-physics/newton", "repo": ".", "branches": ["main"], "dvcs": "git", "environment_type": "virtualenv", "show_commit_url": "https://github.com/newton-physics/newton/commit/", "benchmark_dir": "asv/benchmarks", "env_dir": "asv/env", "results_dir": "asv/results", "html_dir": "asv/html", "build_cache_size": 20, "default_benchmark_timeout": 600, "build_command": ["python -m build --wheel -o {build_cache_dir} {build_dir}"], "install_command": [ "python -m pip install -U numpy", "python -m pip install -U warp-lang==1.12.0 --index-url=https://pypi.nvidia.com/", "python -m pip install -U mujoco==3.6.0", "python -m pip install -U mujoco-warp==3.6.0", "python -m pip install -U torch==2.10.0+cu130 --index-url https://download.pytorch.org/whl/cu130", "in-dir={env_dir} python -m pip install {wheel_file}[dev]" ] } ================================================ FILE: docs/Makefile ================================================ # Minimal makefile for Sphinx documentation # # You can set these variables from the command line, and also # from the environment for the first two. SPHINXOPTS ?= -j auto SPHINXBUILD ?= sphinx-build SOURCEDIR = . BUILDDIR = _build # Put it first so that "make" without argument is like "make help". help: @$(SPHINXBUILD) -M help "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) .PHONY: help Makefile # Catch-all target: route all unknown targets to Sphinx using the new # "make mode" option. $(O) is meant as a shortcut for $(SPHINXOPTS). %: Makefile @$(SPHINXBUILD) -M $@ "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) ================================================ FILE: docs/_ext/autodoc_filter.py ================================================ # SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers # SPDX-License-Identifier: Apache-2.0 from __future__ import annotations import sys from typing import Any # NOTE: This file is *imported by Sphinx* when building the docs. # It must therefore avoid heavy third-party imports that might not be # available in the documentation environment. # --------------------------------------------------------------------------- # Skip handler implementation def _should_skip_member( app: Any, # Sphinx application (unused) what: str, name: str, obj: Any, skip: bool, options: Any, # autodoc options (unused) ) -> bool | None: """Determine whether *obj* should be skipped by autodoc. We apply two simple rules that make API pages cleaner: 1. Private helpers (names that start with an underscore but are not special dunder methods) are hidden unless they are explicitly marked as public via a ``:meta public:`` field. 2. Public members that have **no** docstring are hidden. This keeps the generated documentation focused on the public, documented API. Returning ``True`` tells Sphinx to skip the member, ``False`` to include it, and ``None`` to fall back to Sphinx's default behaviour. """ # Respect decisions made by other handlers first. if skip: return True # Keep dunder methods that are explicitly requested elsewhere. if name.startswith("__") and name.endswith("__"): return None # keep default behaviour # Skip private helpers (single underscore) that are not explicitly public. if name.startswith("_"): # Let users override via :meta public: doc = getattr(obj, "__doc__", "") or "" if ":meta public:" not in doc: return True return None # If the member is public but undocumented, decide based on its nature. doc = getattr(obj, "__doc__", None) if not doc: # Keep an undocumented callable **only** if it overrides a documented # attribute from a base-class. This covers cases like ``step`` in # solver subclasses while still hiding brand-new helpers that have no # documentation. is_callable = callable(obj) or isinstance( obj, property | staticmethod | classmethod, ) if is_callable and what == "class": # Try to determine the parent class from the qualified name. qualname = getattr(obj, "__qualname__", "") parts = qualname.split(".") if len(parts) >= 2: cls_name = parts[-2] module = sys.modules.get(obj.__module__) parent_cls = getattr(module, cls_name, None) if isinstance(parent_cls, type): for base in parent_cls.__mro__[1:]: if hasattr(base, name): return None # overrides something -> keep it # Otherwise hide the undocumented member to keep the page concise. return True # Default: do not override Sphinx's decision. return None def setup(app): # type: ignore[override] """Hook into the Sphinx build.""" app.connect("autodoc-skip-member", _should_skip_member) # Tell Sphinx our extension is parallel-safe. return { "parallel_read_safe": True, "parallel_write_safe": True, } ================================================ FILE: docs/_ext/autodoc_wpfunc.py ================================================ # SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers # SPDX-License-Identifier: Apache-2.0 """Sphinx extension to document Warp `@wp.func` functions. This extension registers a custom *autodoc* documenter that recognises `warp.types.Function` objects (created by the :pyfunc:`warp.func` decorator), unwraps them to their original Python function (stored in the ``.func`` attribute) and then delegates all further processing to the standard :class:`sphinx.ext.autodoc.FunctionDocumenter`. With this in place, *autosummary* and *autodoc* treat Warp kernels exactly like regular Python functions: the original signature and docstring are used and `__all__` filtering works as expected. """ from __future__ import annotations import inspect from typing import Any from sphinx.ext.autodoc import FunctionDocumenter # NOTE: We do **not** import warp at module import time. Doing so would require # CUDA and other heavy deps during the Sphinx build. Instead, detection of a # Warp function is performed purely via *duck typing* (checking attributes and # class name) so the extension is safe even when Warp cannot be imported. class WarpFunctionDocumenter(FunctionDocumenter): """Autodoc documenter that unwraps :pyclass:`warp.types.Function`.""" objtype = "warpfunc" directivetype = "function" # Ensure we run *before* the builtin FunctionDocumenter (higher priority) priority = FunctionDocumenter.priority + 10 # --------------------------------------------------------------------- # Helper methods # --------------------------------------------------------------------- @staticmethod def _looks_like_warp_function(obj: Any) -> bool: """Return *True* if *obj* appears to be a `warp.types.Function`.""" cls = obj.__class__ return getattr(cls, "__name__", "") == "Function" and hasattr(obj, "func") @classmethod def can_document_member( cls, member: Any, member_name: str, isattr: bool, parent, ) -> bool: """Return *True* when *member* is a Warp function we can handle.""" return cls._looks_like_warp_function(member) # ------------------------------------------------------------------ # Autodoc overrides - we proxy to the underlying Python function. # ------------------------------------------------------------------ def _unwrap(self): """Return the original Python function or *self.object* as fallback.""" orig = getattr(self.object, "func", None) if orig and inspect.isfunction(orig): return orig return self.object # Each of these hooks replaces *self.object* with the unwrapped function # *before* delegating to the base implementation. def format_args(self): self.object = self._unwrap() return super().format_args() def get_doc(self, *args: Any, **kwargs: Any) -> list[list[str]]: self.object = self._unwrap() return super().get_doc(*args, **kwargs) def add_directive_header(self, sig: str) -> None: self.object = self._unwrap() super().add_directive_header(sig) # ---------------------------------------------------------------------------- # Sphinx extension entry point # ---------------------------------------------------------------------------- def setup(app): # type: ignore[override] """Register the :class:`WarpFunctionDocumenter` with *app*.""" app.add_autodocumenter(WarpFunctionDocumenter, override=True) # Declare the extension safe for parallel reading/writing return { "parallel_read_safe": True, "parallel_write_safe": True, } ================================================ FILE: docs/_static/custom.css ================================================ /* Reduce spacing between class members */ .py-attribute, .py-method, .py-property, .py-class { margin-top: 0.5em !important; margin-bottom: 0.5em !important; } /* Reduce spacing in docstring sections */ .section > dl > dt { margin-top: 0.2em !important; margin-bottom: 0.2em !important; } /* Reduce padding in parameter lists */ .field-list .field { margin-bottom: 0.2em !important; padding-bottom: 0.2em !important; } /* Reduce spacing between headings and content */ h2, h3, h4, h5, h6 { margin-top: 1em !important; margin-bottom: 0.5em !important; } /* Reduce spacing in enum documentation */ .py.class .py.attribute { margin-bottom: 0.5em !important; } /* Reduce spacing between enum values */ dl.py.attribute { margin-bottom: 0.3em !important; } ================================================ FILE: docs/_static/gh-pages-404.html ================================================ Page Not Found - Newton Documentation

Page Not Found

The page you requested does not exist. Visit the Newton documentation.

================================================ FILE: docs/_static/switcher.json ================================================ [ { "name": "dev", "version": "dev", "url": "https://newton-physics.github.io/newton/latest/" } ] ================================================ FILE: docs/_templates/autosummary/class.rst ================================================ {{ fullname | escape | underline }} .. autoclass:: {{ fullname }} :members: :undoc-members: :show-inheritance: :member-order: groupwise ================================================ FILE: docs/_templates/class.rst ================================================ {{ fullname | escape | underline}} .. currentmodule:: {{ module }} .. autoclass:: {{ objname }} :members: :inherited-members: :member-order: groupwise {% block methods %} {% if methods %} .. rubric:: {{ _('Methods') }} .. autosummary:: {% for item in methods %} ~{{ name }}.{{ item }} {%- endfor %} {% endif %} {% endblock %} {% block attributes %} {% if attributes %} .. rubric:: {{ _('Attributes') }} .. autosummary:: {% for item in attributes %} ~{{ name }}.{{ item }} {%- endfor %} {% endif %} {% endblock %} ================================================ FILE: docs/_templates/genindex.html ================================================ {# basic/genindex.html ~~~~~~~~~~~~~~~~~~~ Template for an "all indices" page. :copyright: Copyright 2007-2023 by the Sphinx team, see AUTHORS. :license: BSD, see LICENSE for details. #} {% extends "layout.html" %} {% set title = _('Index') %} {% block body %}

{{ _('Index') }}

{% for key, dummy in genindexentries %} {{ key }} {% if not loop.last %}| {% endif %} {% endfor %}
{%- for key, entries in genindexentries %}

{{ key }}

{%- for column in entries|slice_index(2) %} {%- endfor %}
{%- for entryname, (links, subitems, _) in column %}
{%- if links %} {{ entryname }} {%- for islast, link in links[1:] -%} {%- if loop.first %}, {% endif -%} {{ loop.index }} {%- if not loop.last %}, {% endif -%} {%- endfor %} {%- else %} {{ entryname }} {%- endif %}
{%- if subitems %}
{%- for subentryname, subentrylinks in subitems %}
{{ subentryname }} {%- for islast, link in subentrylinks[1:] -%} {%- if loop.first %}, {% endif -%} {{ loop.index }} {%- if not loop.last %}, {% endif -%} {%- endfor -%}
{%- endfor %}
{%- endif -%} {%- endfor %}
{% endfor %} {% endblock %} ================================================ FILE: docs/_templates/py-modindex.html ================================================ {# basic/modindex.html ~~~~~~~~~~~~~~~~~~~ Template for the module index. :copyright: Copyright 2007-2023 by the Sphinx team, see AUTHORS. :license: BSD, see LICENSE for details. #} {% extends "layout.html" %} {% set title = _('Python Module Index') %} {% block body %}

{{ _('Python Module Index') }}

{% if modulenames %}
{%- for letter in letters %} {{ letter }}{% if not loop.last %} | {% endif %} {%- endfor %}
{% endif %} {% if modulenames %} {%- for letter, entries in modindexentries %} {%- for name, (uri, synopsis, platform, deprecated) in entries %} {%- endfor %} {%- endfor %} {% else %} {% endif %}
 
{{ letter }}
{% if deprecated %} {% endif %} {%- if uri %} {{ name }} {%- else %} {{ name }} {%- endif %} {% if deprecated %} {% endif %} {% if synopsis %} ({{ synopsis }}){% endif %} {% if platform %} ({{ platform }}){% endif %}

{{ _('No modules found in project.') }}

{% endblock %} ================================================ FILE: docs/_templates/search.html ================================================ {# basic/search.html ~~~~~~~~~~~~~~~~ Template for the search page. :copyright: Copyright 2007-2023 by the Sphinx team, see AUTHORS. :license: BSD, see LICENSE for details. #} {% extends "layout.html" %} {% set title = _('Search') %} {% block scripts %} {{ super() }} {% endblock %} {% block extrahead %} {{ super() }} {% endblock %} {% block body %}

{{ _('Search') }}

{% block scriptwarning %}

{% trans %}Please activate JavaScript to enable the search functionality.{% endtrans %}

{% endblock %} {% block searchresults %}
{% endblock %} {% endblock %} ================================================ FILE: docs/_templates/sidebar-nav-bs.html ================================================ {# Displays the TOC-subtree for pages nested under the currently active top-level TOCtree element. #} ================================================ FILE: docs/api/newton.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 newton ====== .. py:module:: newton .. currentmodule:: newton .. toctree:: :hidden: newton_geometry newton_ik newton_math newton_selection newton_sensors newton_solvers newton_usd newton_utils newton_viewer .. rubric:: Submodules - :doc:`newton.geometry ` - :doc:`newton.ik ` - :doc:`newton.math ` - :doc:`newton.selection ` - :doc:`newton.sensors ` - :doc:`newton.solvers ` - :doc:`newton.usd ` - :doc:`newton.utils ` - :doc:`newton.viewer ` .. rubric:: Classes .. autosummary:: :toctree: _generated :nosignatures: Axis BodyFlags CollisionPipeline Contacts Control EqType Gaussian GeoType Heightfield JointTargetMode JointType Mesh Model ModelBuilder ParticleFlags SDF ShapeFlags State TetMesh .. rubric:: Functions .. autosummary:: :toctree: _generated :signatures: long AxisType eval_fk eval_ik eval_jacobian eval_mass_matrix .. rubric:: Constants .. list-table:: :header-rows: 1 * - Name - Value * - ``MAXVAL`` - ``10000000000.0`` * - ``__version__`` - ``1.1.0.dev0`` ================================================ FILE: docs/api/newton_geometry.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 newton.geometry =============== .. py:module:: newton.geometry .. currentmodule:: newton.geometry .. rubric:: Classes .. autosummary:: :toctree: _generated :nosignatures: BroadPhaseAllPairs BroadPhaseExplicit BroadPhaseSAP HydroelasticSDF NarrowPhase .. rubric:: Functions .. autosummary:: :toctree: _generated :signatures: long collide_box_box collide_capsule_box collide_capsule_capsule collide_plane_box collide_plane_capsule collide_plane_cylinder collide_plane_ellipsoid collide_plane_sphere collide_sphere_box collide_sphere_capsule collide_sphere_cylinder collide_sphere_sphere compute_inertia_shape compute_offset_mesh create_empty_sdf_data sdf_box sdf_capsule sdf_cone sdf_cylinder sdf_mesh sdf_plane sdf_sphere transform_inertia ================================================ FILE: docs/api/newton_ik.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 newton.ik ========= Public inverse-kinematics API for defining objectives and solving IK problems. .. py:module:: newton.ik .. currentmodule:: newton.ik .. rubric:: Classes .. autosummary:: :toctree: _generated :nosignatures: IKJacobianType IKObjective IKObjectiveJointLimit IKObjectivePosition IKObjectiveRotation IKOptimizer IKOptimizerLBFGS IKOptimizerLM IKSampler IKSolver ================================================ FILE: docs/api/newton_math.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 newton.math =========== .. py:module:: newton.math .. currentmodule:: newton.math .. rubric:: Functions .. autosummary:: :toctree: _generated :signatures: long boltzmann leaky_max leaky_min normalize_with_norm orthonormal_basis quat_between_axes quat_between_vectors_robust quat_decompose quat_velocity safe_div smooth_max smooth_min transform_twist transform_wrench vec_abs vec_allclose vec_inside_limits vec_leaky_max vec_leaky_min vec_max vec_min velocity_at_point ================================================ FILE: docs/api/newton_selection.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 newton.selection ================ .. py:module:: newton.selection .. currentmodule:: newton.selection .. rubric:: Classes .. autosummary:: :toctree: _generated :nosignatures: ArticulationView ================================================ FILE: docs/api/newton_sensors.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 newton.sensors ============== .. py:module:: newton.sensors .. currentmodule:: newton.sensors .. rubric:: Classes .. autosummary:: :toctree: _generated :nosignatures: SensorContact SensorFrameTransform SensorIMU SensorRaycast SensorTiledCamera ================================================ FILE: docs/api/newton_solvers.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 newton.solvers ============== Solvers are used to integrate the dynamics of a Newton model. The typical workflow is to construct a :class:`~newton.Model` and a :class:`~newton.State` object, then use a solver to advance the state forward in time via the :meth:`~newton.solvers.SolverBase.step` method: .. mermaid:: :config: {"theme": "forest", "themeVariables": {"lineColor": "#76b900"}} flowchart LR subgraph Input["Input Data"] M[newton.Model] S[newton.State] C[newton.Control] K[newton.Contacts] DT[Time step dt] end STEP["solver.step()"] subgraph Output["Output Data"] SO["newton.State (updated)"] end %% Connections M --> STEP S --> STEP C --> STEP K --> STEP DT --> STEP STEP --> SO Supported Features ------------------ .. list-table:: :header-rows: 1 :widths: auto :stub-columns: 0 * - Solver - :abbr:`Integration (Available methods for integrating the dynamics)` - Rigid bodies - :ref:`Articulations ` - Particles - Cloth - Soft bodies - Differentiable * - :class:`~newton.solvers.SolverFeatherstone` - Explicit - ✅ - ✅ generalized coordinates - ✅ - 🟨 no self-collision - ✅ - 🟨 basic :sup:`2` * - :class:`~newton.solvers.SolverImplicitMPM` - Implicit - ❌ - ❌ - ✅ - ❌ - ❌ - ❌ * - :class:`~newton.solvers.SolverKamino` - Semi-implicit: Euler, Moreau-Jean - ✅ maximal coordinates - ✅ maximal coordinates - ❌ - ❌ - ❌ - ❌ * - :class:`~newton.solvers.SolverMuJoCo` - Explicit, Semi-implicit, Implicit - ✅ :sup:`1` - ✅ generalized coordinates - ❌ - ❌ - ❌ - ❌ * - :class:`~newton.solvers.SolverSemiImplicit` - Semi-implicit - ✅ - ✅ maximal coordinates - ✅ - 🟨 no self-collision - ✅ - 🟨 basic :sup:`2` * - :class:`~newton.solvers.SolverStyle3D` - Implicit - ❌ - ❌ - ✅ - ✅ - ❌ - ❌ * - :class:`~newton.solvers.SolverVBD` - Implicit - ✅ - 🟨 :ref:`limited joint support ` - ✅ - ✅ - ❌ - ❌ * - :class:`~newton.solvers.SolverXPBD` - Implicit - ✅ - ✅ maximal coordinates - ✅ - 🟨 no self-collision - 🟨 experimental - ❌ | :sup:`1` Uses its own collision pipeline from MuJoCo/mujoco_warp by default, unless ``use_mujoco_contacts`` is set to ``False``. | :sup:`2` ``basic`` means Newton includes several examples that use these solvers in diffsim workflows, see :ref:`Differentiability` for further details. .. _Joint feature support: Joint Feature Support --------------------- Not every solver supports every joint type or joint property. The tables below document which joint features each solver handles. Only :class:`~newton.solvers.SolverFeatherstone` and :class:`~newton.solvers.SolverMuJoCo` operate on :ref:`articulations ` (generalized/reduced coordinates). The maximal-coordinate solvers (:class:`~newton.solvers.SolverSemiImplicit`, :class:`~newton.solvers.SolverXPBD`, and :class:`~newton.solvers.SolverKamino`) enforce joints as pairwise body constraints but do not use the articulation kinematic-tree structure. :class:`~newton.solvers.SolverVBD` supports a subset of joint types via soft constraints (AVBD). :class:`~newton.solvers.SolverStyle3D` and :class:`~newton.solvers.SolverImplicitMPM` do not support joints. **Joint types** .. list-table:: :header-rows: 1 :widths: auto :stub-columns: 1 * - Joint type - :class:`~newton.solvers.SolverFeatherstone` - :class:`~newton.solvers.SolverSemiImplicit` - :class:`~newton.solvers.SolverXPBD` - :class:`~newton.solvers.SolverMuJoCo` - :class:`~newton.solvers.SolverVBD` - :class:`~newton.solvers.SolverKamino` * - PRISMATIC - |yes| - |yes| - |yes| - |yes| - |yes| - |yes| * - REVOLUTE - |yes| - |yes| - |yes| - |yes| - |yes| - |yes| * - BALL - |yes| - |yes| - |yes| - |yes| - |yes| - |yes| * - FIXED - |yes| - |yes| - |yes| - |yes| - |yes| - |yes| * - FREE - |yes| - |yes| - |yes| - |yes| - |yes| - |yes| * - DISTANCE - 🟨 :sup:`1` - 🟨 :sup:`1` - |yes| - |no| - |no| - |no| * - D6 - |yes| - |yes| - |yes| - |yes| - |yes| - |no| * - CABLE - |no| - |no| - |no| - |no| - |yes| - |no| | :sup:`1` DISTANCE joints are treated as FREE (no distance constraint enforcement). **Joint properties** .. list-table:: :header-rows: 1 :widths: auto :stub-columns: 1 * - Property - :class:`~newton.solvers.SolverFeatherstone` - :class:`~newton.solvers.SolverSemiImplicit` - :class:`~newton.solvers.SolverXPBD` - :class:`~newton.solvers.SolverMuJoCo` - :class:`~newton.solvers.SolverVBD` - :class:`~newton.solvers.SolverKamino` * - :attr:`~newton.Model.joint_enabled` - |no| - |yes| - |yes| - |no| - |yes| - |no| * - :attr:`~newton.Model.joint_armature` - |yes| - |no| - |no| - |yes| - |no| - |yes| * - :attr:`~newton.Model.joint_friction` - |no| - |no| - |no| - |yes| - |no| - |no| * - :attr:`~newton.Model.joint_limit_lower` / :attr:`~newton.Model.joint_limit_upper` - |yes| - |yes| :sup:`2` - |yes| - |yes| - |yes| - |yes| * - :attr:`~newton.Model.joint_limit_ke` / :attr:`~newton.Model.joint_limit_kd` - |yes| - |yes| :sup:`2` - |no| - |yes| - |yes| :sup:`4` - |no| * - :attr:`~newton.Model.joint_effort_limit` - |no| - |no| - |no| - |yes| - |no| - |no| * - :attr:`~newton.Model.joint_velocity_limit` - |no| - |no| - |no| - |no| - |no| - |no| | :sup:`2` Not enforced for BALL joints in SemiImplicit. **Actuation and control** .. list-table:: :header-rows: 1 :widths: auto :stub-columns: 1 * - Feature - :class:`~newton.solvers.SolverFeatherstone` - :class:`~newton.solvers.SolverSemiImplicit` - :class:`~newton.solvers.SolverXPBD` - :class:`~newton.solvers.SolverMuJoCo` - :class:`~newton.solvers.SolverVBD` - :class:`~newton.solvers.SolverKamino` * - :attr:`~newton.Model.joint_target_ke` / :attr:`~newton.Model.joint_target_kd` - |yes| - |yes| :sup:`2` - |yes| - |yes| - |yes| :sup:`4` - |yes| * - :attr:`~newton.Model.joint_target_mode` - |no| - |no| - |no| - |yes| - |no| - |yes| * - :attr:`~newton.Control.joint_f` (feedforward forces) - |yes| - |yes| - |yes| - |yes| - |yes| - |yes| **Constraints** .. list-table:: :header-rows: 1 :widths: auto :stub-columns: 1 * - Feature - :class:`~newton.solvers.SolverFeatherstone` - :class:`~newton.solvers.SolverSemiImplicit` - :class:`~newton.solvers.SolverXPBD` - :class:`~newton.solvers.SolverMuJoCo` - :class:`~newton.solvers.SolverVBD` - :class:`~newton.solvers.SolverKamino` * - Equality constraints (CONNECT, WELD, JOINT) - |no| - |no| - |no| - |yes| - |no| - |no| * - Mimic constraints - |no| - |no| - |no| - |yes| :sup:`3` - |no| - |no| | :sup:`3` Mimic constraints in MuJoCo are supported for REVOLUTE and PRISMATIC joints only. | :sup:`4` VBD interprets ``joint_target_kd`` and ``joint_limit_kd`` as dimensionless Rayleigh damping coefficients (``D = kd * ke``), not absolute units. .. _Differentiability: Differentiability ----------------- Differentiable simulation in Newton typically runs a forward rollout inside ``wp.Tape()``, computes a scalar loss from the simulated state, and then calls ``tape.backward(loss)`` to populate gradients on differentiable state, control, or model arrays. In practice, this starts by calling :meth:`~newton.ModelBuilder.finalize` with ``requires_grad=True``. .. testcode:: import warp as wp import newton @wp.kernel def loss_kernel(particle_q: wp.array[wp.vec3], target: wp.vec3, loss: wp.array[float]): delta = particle_q[0] - target loss[0] = wp.dot(delta, delta) builder = newton.ModelBuilder() builder.add_particle(pos=wp.vec3(0.0, 0.0, 0.0), vel=wp.vec3(1.0, 0.0, 0.0), mass=1.0) model = builder.finalize(requires_grad=True) solver = newton.solvers.SolverSemiImplicit(model) state_in = model.state() state_out = model.state() control = model.control() loss = wp.zeros(1, dtype=float, requires_grad=True) target = wp.vec3(0.25, 0.0, 0.0) tape = wp.Tape() with tape: state_in.clear_forces() solver.step(state_in, state_out, control, None, 1.0 / 60.0) wp.launch( loss_kernel, dim=1, inputs=[state_out.particle_q, target], outputs=[loss], ) tape.backward(loss) initial_velocity_grad = state_in.particle_qd.grad.numpy() assert float(initial_velocity_grad[0, 0]) < 0.0 See the `DiffSim examples on GitHub`_ for the current reference workflows. .. _DiffSim examples on GitHub: https://github.com/newton-physics/newton/tree/main/newton/examples/diffsim .. |yes| unicode:: U+2705 .. |no| unicode:: U+274C .. py:module:: newton.solvers .. currentmodule:: newton.solvers .. toctree:: :hidden: newton_solvers_style3d .. rubric:: Submodules - :doc:`newton.solvers.style3d ` .. rubric:: Classes .. autosummary:: :toctree: _generated :nosignatures: SolverBase SolverFeatherstone SolverImplicitMPM SolverKamino SolverMuJoCo SolverNotifyFlags SolverSemiImplicit SolverStyle3D SolverVBD SolverXPBD ================================================ FILE: docs/api/newton_solvers_style3d.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 newton.solvers.style3d ====================== Style3D solver module. This module provides helper functions for setting up Style3D cloth assets. Use :class:`~newton.solvers.SolverStyle3D` as the canonical public solver import path. .. py:module:: newton.solvers.style3d .. currentmodule:: newton.solvers.style3d .. rubric:: Functions .. autofunction:: add_cloth_grid .. autofunction:: add_cloth_mesh ================================================ FILE: docs/api/newton_usd.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 newton.usd ========== Utilities for working with the Universal Scene Description (USD) format. This module provides both low-level USD utility helpers and public schema resolver types used by :meth:`newton.ModelBuilder.add_usd`. .. py:module:: newton.usd .. currentmodule:: newton.usd .. rubric:: Classes .. autosummary:: :toctree: _generated :nosignatures: PrimType SchemaResolver SchemaResolverMjc SchemaResolverNewton SchemaResolverPhysx .. rubric:: Functions .. autosummary:: :toctree: _generated :signatures: long find_tetmesh_prims get_attribute get_attributes_in_namespace get_custom_attribute_declarations get_custom_attribute_values get_float get_gprim_axis get_mesh get_quat get_scale get_tetmesh get_transform has_applied_api_schema has_attribute type_to_warp value_to_warp ================================================ FILE: docs/api/newton_utils.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 newton.utils ============ .. py:module:: newton.utils .. currentmodule:: newton.utils .. rubric:: Classes .. autosummary:: :toctree: _generated :nosignatures: EventTracer MeshAdjacency .. rubric:: Functions .. autosummary:: :toctree: _generated :signatures: long bourke_color_map color_graph compute_world_offsets create_cable_stiffness_from_elastic_moduli create_parallel_transport_cable_quaternions create_straight_cable_points create_straight_cable_points_and_quaternions download_asset event_scope load_texture normalize_texture plot_graph remesh_mesh run_benchmark solidify_mesh string_to_warp ================================================ FILE: docs/api/newton_viewer.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 newton.viewer ============= .. py:module:: newton.viewer .. currentmodule:: newton.viewer .. rubric:: Classes .. autosummary:: :toctree: _generated :nosignatures: ViewerBase ViewerFile ViewerGL ViewerNull ViewerRerun ViewerUSD ViewerViser ================================================ FILE: docs/concepts/articulations.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 .. currentmodule:: newton .. _Articulations: Articulations ============= Articulations are a way to represent a collection of rigid bodies that are connected by joints. .. _Articulation parameterization: Generalized and maximal coordinates ----------------------------------- There are two types of parameterizations to describe the configuration of an articulation: generalized coordinates and maximal coordinates. Generalized (sometimes also called "reduced") coordinates describe an articulation in terms of its joint positions and velocities. For example, a double-pendulum articulation has two revolute joints, so its generalized state consists of two joint angles in :attr:`newton.State.joint_q` and two corresponding joint velocities in :attr:`newton.State.joint_qd`. See the table below for the number of generalized coordinates for each joint type. For a floating-base articulation (one connected to the world by a free joint), the generalized coordinates also include the base link pose: a 3D position and an XYZW quaternion. Maximal coordinates describe the configuration of an articulation in terms of the body link positions and velocities. Each rigid body's pose is represented by 7 parameters (3D position and XYZW quaternion) in :attr:`newton.State.body_q`, and its velocity by 6 parameters (3D linear and 3D angular) in :attr:`newton.State.body_qd`. To convert between these two representations, we use forward and inverse kinematics: forward kinematics (:func:`newton.eval_fk`) converts generalized coordinates to maximal coordinates, and inverse kinematics (:func:`newton.eval_ik`) converts maximal coordinates to generalized coordinates. Newton supports both parameterizations, and each solver chooses which one it treats as the primary articulation state representation. For example, :class:`~newton.solvers.SolverMuJoCo` and :class:`~newton.solvers.SolverFeatherstone` use generalized coordinates, while :class:`~newton.solvers.SolverXPBD`, :class:`~newton.solvers.SolverSemiImplicit`, and :class:`~newton.solvers.SolverVBD` use maximal coordinates. Note that collision detection, e.g., via :meth:`newton.Model.collide` requires the maximal coordinates to be current in the state. To showcase how an articulation state is initialized using reduced coordinates, let's consider an example where we create an articulation with a single revolute joint and initialize its joint angle to 0.5 and joint velocity to 10.0: .. testcode:: builder = newton.ModelBuilder() # create an articulation with a single revolute joint body = builder.add_link() builder.add_shape_box(body) # add a shape to the body to add some inertia joint = builder.add_joint_revolute(parent=-1, child=body, axis=wp.vec3(0.0, 0.0, 1.0)) # add a revolute joint to the body builder.add_articulation([joint]) # create articulation from the joint builder.joint_q[-1] = 0.5 builder.joint_qd[-1] = 10.0 model = builder.finalize() state = model.state() # The generalized coordinates have been initialized by the revolute joint: assert all(state.joint_q.numpy() == [0.5]) assert all(state.joint_qd.numpy() == [10.0]) While the generalized coordinates have been initialized by the values we set through the :attr:`newton.ModelBuilder.joint_q` and :attr:`newton.ModelBuilder.joint_qd` definitions, the body poses (maximal coordinates) are still initialized by the identity transform (since we did not provide a ``xform`` argument to the :meth:`newton.ModelBuilder.add_link` call, it defaults to the identity transform). This is not a problem for generalized-coordinate solvers, as they do not use the body poses (maximal coordinates) to represent the state of the articulation but only the generalized coordinates. In order to update the body poses (maximal coordinates), we need to use the forward kinematics function :func:`newton.eval_fk`: .. testcode:: newton.eval_fk(model, state.joint_q, state.joint_qd, state) Now, the body poses (maximal coordinates) have been updated by the forward kinematics and a maximal-coordinate solver can simulate the scene starting from these initial conditions. As mentioned above, this call is not needed for generalized-coordinate solvers. When declaring an articulation using the :class:`~newton.ModelBuilder`, the rigid body poses (maximal coordinates :attr:`newton.State.body_q`) are initialized by the ``xform`` argument: .. testcode:: builder = newton.ModelBuilder() tf = wp.transform(wp.vec3(1.0, 2.0, 3.0), wp.quat_from_axis_angle(wp.vec3(0.0, 0.0, 1.0), 0.5 * wp.pi)) body = builder.add_body(xform=tf) builder.add_shape_box(body) # add a shape to the body to add some inertia model = builder.finalize() state = model.state() # The body poses (maximal coordinates) are initialized by the xform argument: assert all(state.body_q.numpy()[0] == [*tf]) # Note: add_body() automatically creates a free joint, so generalized coordinates exist: assert len(state.joint_q) == 7 # 7 DOF for a free joint (3 position + 4 quaternion) In this setup, we have a body with a box shape that both maximal-coordinate and generalized-coordinate solvers can simulate. Since :meth:`~newton.ModelBuilder.add_body` automatically adds a free joint, the body already has the necessary degrees of freedom in generalized coordinates (:attr:`newton.State.joint_q`). .. testcode:: builder = newton.ModelBuilder() tf = wp.transform(wp.vec3(1.0, 2.0, 3.0), wp.quat_from_axis_angle(wp.vec3(0.0, 0.0, 1.0), 0.5 * wp.pi)) body = builder.add_link(xform=tf) builder.add_shape_box(body) # add a shape to the body to add some inertia joint = builder.add_joint_free(body) # add a free joint to connect the body to the world builder.add_articulation([joint]) # create articulation from the joint # The free joint's coordinates (joint_q) are initialized by its child body's pose, # so we do not need to specify them here # builder.joint_q[-7:] = *tf model = builder.finalize() state = model.state() # The body poses (maximal coordinates) are initialized by the xform argument: assert all(state.body_q.numpy()[0] == [*tf]) # Now, the generalized coordinates are initialized by the free joint: assert len(state.joint_q) == 7 assert all(state.joint_q.numpy() == [*tf]) This scene can now be simulated by both maximal-coordinate and generalized-coordinate solvers. .. _Kinematic links: Kinematic links and bodies -------------------------- Newton distinguishes three motion modes for rigid bodies: **Static** Does not move. Typical examples are world-attached shapes or links attached to world with a fixed joint. **Kinematic** Moves only from user-prescribed state updates. It can have joint DOFs (free, revolute, etc.), but external forces do not accelerate it. **Dynamic** Moves from forces, constraints, and contacts during solver integration. Kinematic bodies are created through the ``is_kinematic=True`` flag on :meth:`~newton.ModelBuilder.add_link` or :meth:`~newton.ModelBuilder.add_body`. Only root links (joint parent ``-1``) may be kinematic. Setting a non-root link to kinematic raises a :class:`ValueError` during articulation construction. Common combinations ^^^^^^^^^^^^^^^^^^^ The following patterns are valid and commonly used: 1. **Kinematic free-base body**: ``add_body(is_kinematic=True)`` (free joint root). 2. **Kinematic articulated root**: root link is kinematic and attached to world with a non-fixed joint (for example revolute), with dynamic descendants. 3. **Static fixed-root body**: root link is kinematic and attached to world with a fixed joint. This has zero joint DOFs and behaves as static. .. testcode:: articulation-kinematic-combinations builder = newton.ModelBuilder() # 1) Kinematic free-base body (add_body creates free joint + articulation) kinematic_free = builder.add_body(is_kinematic=True, mass=1.0) # 2) Kinematic revolute root with a dynamic child root = builder.add_link(is_kinematic=True, mass=1.0) child = builder.add_link(mass=1.0) j_root = builder.add_joint_revolute(parent=-1, child=root, axis=newton.Axis.Z) j_child = builder.add_joint_revolute(parent=root, child=child, axis=newton.Axis.Z) builder.add_articulation([j_root, j_child]) # 3) Static fixed-root body (zero joint DOFs) static_root = builder.add_link(is_kinematic=True, mass=1.0) j_static = builder.add_joint_fixed(parent=-1, child=static_root) builder.add_articulation([j_static]) model = builder.finalize() .. list-table:: Static vs kinematic vs dynamic bodies/links :header-rows: 1 :widths: 22 26 26 26 * - Property - Static - Kinematic - Dynamic * - Typical definition - World-attached shape, or root link fixed to world - ``is_kinematic=True`` on a root link/body with free/revolute/etc. joint - Default link/body (no kinematic flag) * - Joint DOFs - 0 for fixed-root links - Joint-dependent (free/revolute/D6/etc.) - Joint-dependent * - Position/velocity state - Constant (not integrated) - User-prescribed ``q``/``qd`` (or ``body_q``/``body_qd`` depending on solver coordinates) - Integrated by solver from dynamics * - Response to applied force/torque - No acceleration - No acceleration (force-immune for own motion) - Accelerates according to dynamics * - Collision/contact participation - Yes (acts as obstacle/support) - Yes (can push dynamic bodies while following prescribed motion) - Yes * - Mass/inertia (see :ref:`Mass and Inertia`) - Not used for motion when fixed - Preserved for body properties and future dynamic switching - Fully used by dynamics * - Mass matrix / constraint role - No active DOFs when fixed to world - Solver-dependent infinite-mass approximation along kinematic DOFs - Standard articulated mass matrix * - Typical applications - Environment geometry, fixtures - Conveyors, robot bases on trajectories, scripted mechanism roots - Physically simulated robots and objects Velocity consistency for prescribed motion ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ For prescribed motion, it is up to the user to keep position and velocity updates consistent across time. In particular, ``qd`` should be consistent with the finite-differenced motion implied by ``q``. For scalar coordinates, this is the familiar ``q_next = q + qd * dt`` relation; quaternion-based coordinates (for example FREE/BALL joint) require manifold-consistent quaternion integration instead of direct addition. When writing kinematic state values: - For generalized-coordinate workflows, write :attr:`newton.State.joint_q` and :attr:`newton.State.joint_qd`, then call :func:`newton.eval_fk` so maximal coordinates (for collisions and body-space consumers) are current. - For maximal-coordinate workflows, write :attr:`newton.State.body_q` and :attr:`newton.State.body_qd` directly. Rigid-body solver behavior ^^^^^^^^^^^^^^^^^^^^^^^^^^ The rigid-body solvers (:class:`~newton.solvers.SolverMuJoCo`, :class:`~newton.solvers.SolverFeatherstone`, :class:`~newton.solvers.SolverXPBD`, :class:`~newton.solvers.SolverSemiImplicit`, :class:`~newton.solvers.SolverVBD`) support the same user-facing kinematic authoring model: - Kinematic links keep their declared joint type (free/revolute/etc.). - A kinematic root attached to world by a fixed joint remains fixed (zero DOFs). - Kinematic links participate in collisions/contacts and can impart motion to dynamic bodies. - Applied forces do not drive kinematic motion; motion is user-prescribed. Implementation details differ by coordinate formulation: - Generalized-coordinate solvers (:class:`~newton.solvers.SolverMuJoCo`, :class:`~newton.solvers.SolverFeatherstone`) treat kinematic motion through prescribed joint state. - Maximal-coordinate solvers (:class:`~newton.solvers.SolverXPBD`, :class:`~newton.solvers.SolverSemiImplicit`, :class:`~newton.solvers.SolverVBD`) use prescribed body transforms/twists. - Contact handling of kinematic bodies is not identical across the solvers. :class:`~newton.solvers.SolverXPBD`, :class:`~newton.solvers.SolverVBD`, :class:`~newton.solvers.SolverMuJoCo`, and :class:`~newton.solvers.SolverFeatherstone` treat kinematic bodies like infinite-mass colliders for contact response, while :class:`~newton.solvers.SolverSemiImplicit` currently preserves prescribed state but does not zero inverse mass/inertia inside its contact solver. Contacts against kinematic bodies can therefore be softer under SemiImplicit. In :class:`~newton.solvers.SolverMuJoCo`, kinematic DOFs are regularized with a large internal armature value; see :ref:`Kinematic Links and Fixed Roots ` for details. .. _Joint types: Joint types ----------- .. list-table:: :header-rows: 1 :widths: auto :stub-columns: 0 * - Joint Type - Description - Coordinates in ``joint_q`` - DOFs in ``joint_qd`` * - ``JointType.PRISMATIC`` - Prismatic (slider) joint with 1 linear degree of freedom - 1 - 1 * - ``JointType.REVOLUTE`` - Revolute (hinge) joint with 1 angular degree of freedom - 1 - 1 * - ``JointType.BALL`` - Ball (spherical) joint with quaternion state representation - 4 - 3 * - ``JointType.FIXED`` - Fixed (static) joint with no degrees of freedom - 0 - 0 * - ``JointType.FREE`` - Free (floating) joint with 6 degrees of freedom in velocity space - 7 (3D position + 4D quaternion) - 6 (see :ref:`Twist conventions in Newton `) * - ``JointType.DISTANCE`` - Distance joint that keeps two bodies at a distance within its joint limits - 7 - 6 * - ``JointType.D6`` - Generic D6 joint with up to 3 translational and 3 rotational degrees of freedom - up to 6 - up to 6 * - ``JointType.CABLE`` - Cable joint with 1 linear (stretch/shear) and 1 angular (bend/twist) degree of freedom - 2 - 2 D6 joints are the most general joint type in Newton and can be used to represent any combination of translational and rotational degrees of freedom. Prismatic, revolute, planar, and universal joints can be seen as special cases of the D6 joint. Definition of ``joint_q`` ^^^^^^^^^^^^^^^^^^^^^^^^^ The :attr:`newton.Model.joint_q` array stores the default generalized joint positions for all joints in the model and is used to initialize :attr:`newton.State.joint_q`. Both arrays share the same per-joint layout. For scalar-coordinate joints (for example this D6 joint), the positional coordinates can be queried as follows: .. testsetup:: articulation-joint-layout builder = newton.ModelBuilder() body = builder.add_link() builder.add_shape_box(body, hx=0.1, hy=0.1, hz=0.1) joint = builder.add_joint_d6( parent=-1, child=body, linear_axes=[newton.ModelBuilder.JointDofConfig(axis=newton.Axis.X, limit_lower=-0.5, limit_upper=0.5)], angular_axes=[newton.ModelBuilder.JointDofConfig(axis=newton.Axis.Z, limit_lower=-1.0, limit_upper=1.0)], ) builder.add_articulation([joint]) model = builder.finalize() state = model.state() control = model.control() joint_id = 0 joint_q_start = model.joint_q_start.numpy() joint_qd_start = model.joint_qd_start.numpy() joint_q = state.joint_q.numpy() joint_qd = state.joint_qd.numpy() joint_dof_dim = model.joint_dof_dim.numpy() joint_axis = model.joint_axis.numpy() joint_limit_lower = model.joint_limit_lower.numpy() joint_target_pos = control.joint_target_pos.numpy() joint_f = control.joint_f.numpy() .. testcode:: articulation-joint-layout q_start = joint_q_start[joint_id] coord_count = joint_dof_dim[joint_id, 0] + joint_dof_dim[joint_id, 1] # now the positional coordinates can be queried as follows: q = joint_q[q_start : q_start + coord_count] q0 = q[0] q1 = q[1] Definition of ``joint_qd`` ^^^^^^^^^^^^^^^^^^^^^^^^^^ The :attr:`newton.Model.joint_qd` array stores the default generalized joint velocities for all joints in the model and is used to initialize :attr:`newton.State.joint_qd`. The generalized joint forces at :attr:`newton.Control.joint_f` use the same DOF order. Several other arrays also use this same DOF-ordered layout, indexed from :attr:`newton.Model.joint_qd_start` rather than :attr:`newton.Model.joint_q_start`. This includes :attr:`newton.Model.joint_axis`, joint limits and other per-DOF properties defined via :class:`newton.ModelBuilder.JointDofConfig`, and the position targets at :attr:`newton.Control.joint_target_pos`. For every joint, these per-DOF arrays are stored consecutively, with linear DOFs first and angular DOFs second. Use :attr:`newton.Model.joint_dof_dim` to query how many of each a joint has. The velocity DOFs for each joint can be queried as follows: .. testcode:: articulation-joint-layout qd_start = joint_qd_start[joint_id] dof_count = joint_dof_dim[joint_id, 0] + joint_dof_dim[joint_id, 1] # now the velocity DOFs can be queried as follows: qd = joint_qd[qd_start : qd_start + dof_count] qd0 = qd[0] qd1 = qd[1] # the generalized joint forces can be queried as follows: f = joint_f[qd_start : qd_start + dof_count] f0 = f[0] f1 = f[1] The same start index can be used to query other per-DOF arrays for that joint: .. testcode:: articulation-joint-layout num_linear_dofs = joint_dof_dim[joint_id, 0] num_angular_dofs = joint_dof_dim[joint_id, 1] # all per-DOF arrays for this joint start at this index: dof_start = joint_qd_start[joint_id] # the axis vector for the first linear DOF first_lin_axis = joint_axis[dof_start] # the position target for this linear DOF first_lin_target = joint_target_pos[dof_start] # the joint limit of this linear DOF first_lin_limit = joint_limit_lower[dof_start] # the axis vector for the first angular DOF comes after all linear DOFs first_ang_axis = joint_axis[dof_start + num_linear_dofs] # the position target for this angular DOF first_ang_target = joint_target_pos[dof_start + num_linear_dofs] # the joint limit of this angular DOF first_ang_limit = joint_limit_lower[dof_start + num_linear_dofs] assert (num_linear_dofs, num_angular_dofs) == (1, 1) assert np.allclose(first_lin_axis, [1.0, 0.0, 0.0]) assert np.allclose(first_ang_axis, [0.0, 0.0, 1.0]) assert np.allclose([first_lin_limit, first_ang_limit], [-0.5, -1.0]) Common articulation workflows ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Center ``joint_q`` between joint limits with Warp kernels """"""""""""""""""""""""""""""""""""""""""""""""""""""""" Joint limits are stored in DOF order (``joint_qd`` layout), while ``joint_q`` stores generalized joint coordinates (which may include quaternion coordinates for free/ball joints). The pattern below sets each scalar coordinate to the midpoint between its lower and upper limits. A robust pattern is: 1. Loop over joints. 2. Use ``Model.joint_qd_start`` to find the first DOF index for each joint. 3. Use ``Model.joint_dof_dim`` to get the number of linear and angular DOFs for that joint. 4. Use ``Model.joint_q_start`` to find where that joint starts in ``State.joint_q``. 5. Center only scalar coordinates (for example, revolute/prismatic axes) and skip quaternion joints. .. testsetup:: articulation-center-joint-q builder = newton.ModelBuilder() parent = builder.add_link() child = builder.add_link(xform=wp.transform(wp.vec3(1.0, 0.0, 0.0), wp.quat_identity())) builder.add_shape_box(parent, hx=0.1, hy=0.1, hz=0.1) builder.add_shape_box(child, hx=0.1, hy=0.1, hz=0.1) j0 = builder.add_joint_revolute( parent=-1, child=parent, axis=wp.vec3(0.0, 0.0, 1.0), limit_lower=-1.0, limit_upper=1.0, ) j1 = builder.add_joint_revolute( parent=parent, child=child, axis=wp.vec3(0.0, 0.0, 1.0), parent_xform=wp.transform(wp.vec3(1.0, 0.0, 0.0), wp.quat_identity()), child_xform=wp.transform_identity(), limit_lower=0.0, limit_upper=2.0, ) builder.add_articulation([j0, j1]) model = builder.finalize() state = model.state() .. testcode:: articulation-center-joint-q @wp.kernel def center_joint_q_from_limits( joint_q_start: wp.array(dtype=wp.int32), joint_qd_start: wp.array(dtype=wp.int32), joint_dof_dim: wp.array2d(dtype=wp.int32), joint_type: wp.array(dtype=wp.int32), joint_limit_lower: wp.array(dtype=float), joint_limit_upper: wp.array(dtype=float), joint_q: wp.array(dtype=float), ): joint_id = wp.tid() # First DOF index for this joint in qd-order arrays (limits/axes/forces) qd_begin = joint_qd_start[joint_id] dof_count = joint_dof_dim[joint_id, 0] + joint_dof_dim[joint_id, 1] # Start index for this joint in generalized coordinates q q_begin = joint_q_start[joint_id] # Skip free/ball joints because their q entries include quaternion coordinates. jt = joint_type[joint_id] if ( jt == newton.JointType.FREE or jt == newton.JointType.BALL or jt == newton.JointType.DISTANCE ): return # For scalar joints, q coordinates align with this joint's total DOF count. for local_dof in range(dof_count): qd_idx = qd_begin + local_dof q_idx = q_begin + local_dof lower = joint_limit_lower[qd_idx] upper = joint_limit_upper[qd_idx] if wp.isfinite(lower) and wp.isfinite(upper): joint_q[q_idx] = 0.5 * (lower + upper) # Launch over all joints in the model wp.launch( kernel=center_joint_q_from_limits, dim=model.joint_count, inputs=[ model.joint_q_start, model.joint_qd_start, model.joint_dof_dim, model.joint_type, model.joint_limit_lower, model.joint_limit_upper, state.joint_q, ], ) # Recompute transforms after editing generalized coordinates newton.eval_fk(model, state.joint_q, state.joint_qd, state) ArticulationView: selection interface for RL and batched control """""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""" :class:`newton.selection.ArticulationView` is the high-level interface for selecting a subset of articulations and accessing their joints/links/DOFs with stable tensor shapes. This is especially useful in RL pipelines where the same observation/action logic is applied to many parallel environments. Construct a view by matching articulation keys with a pattern and optional filters: .. testsetup:: articulation-view builder = newton.ModelBuilder() for i in range(2): root = builder.add_link( xform=wp.transform(wp.vec3(float(i) * 2.0, 0.0, 0.0), wp.quat_identity()) ) tip = builder.add_link( xform=wp.transform(wp.vec3(float(i) * 2.0 + 1.0, 0.0, 0.0), wp.quat_identity()) ) builder.add_shape_box(root, hx=0.1, hy=0.1, hz=0.1) builder.add_shape_box(tip, hx=0.1, hy=0.1, hz=0.1) j_root = builder.add_joint_free(parent=-1, child=root) j_tip = builder.add_joint_revolute( parent=root, child=tip, axis=wp.vec3(0.0, 0.0, 1.0), parent_xform=wp.transform(wp.vec3(1.0, 0.0, 0.0), wp.quat_identity()), child_xform=wp.transform_identity(), ) builder.add_articulation([j_root, j_tip], label=f"robot_{i}") model = builder.finalize() state = model.state() .. testcode:: articulation-view # select all articulations whose key starts with "robot" view = newton.selection.ArticulationView(model, pattern="robot*") assert view.count == 2 # select only scalar-joint articulations (exclude quaternion-root joint types) scalar_view = newton.selection.ArticulationView( model, pattern="robot*", include_joint_types=[newton.JointType.PRISMATIC, newton.JointType.REVOLUTE], exclude_joint_types=[newton.JointType.FREE, newton.JointType.BALL], ) assert scalar_view.get_dof_positions(state).shape == (1, 2, 1) Use views to read/write batched state slices (joint positions/velocities, root transforms, link transforms) without manual index bookkeeping. Move articulations in world space """"""""""""""""""""""""""""""""" Use :meth:`newton.selection.ArticulationView.set_root_transforms` to move selected articulations: .. testcode:: articulation-view view = newton.selection.ArticulationView(model, pattern="robot*") root_tf = view.get_root_transforms(state).numpy() # shift +0.2 m along world x for all selected articulations root_tf[..., 0] += 0.2 view.set_root_transforms(state, root_tf) # recompute link transforms from generalized coordinates newton.eval_fk(model, state.joint_q, state.joint_qd, state) assert np.allclose(view.get_root_transforms(state).numpy()[0, :, 0], [0.2, 2.2]) For floating-base articulations (root joint type ``FREE`` or ``DISTANCE``), this updates the root coordinates in ``joint_q``. For non-floating-base articulations (for example ``FIXED`` or a world-attached ``REVOLUTE`` root), ``set_root_transforms()`` moves the articulation by writing ``Model.joint_X_p`` because there is no root pose stored in state coordinates. Use ``ArticulationView`` to inspect and modify selected articulations """"""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""" ``ArticulationView`` provides stable, per-articulation access to links, joints, DOFs, and attributes: .. testcode:: articulation-view view = newton.selection.ArticulationView(model, pattern="robot*") scalar_view = newton.selection.ArticulationView( model, pattern="robot*", include_joint_types=[newton.JointType.PRISMATIC, newton.JointType.REVOLUTE], exclude_joint_types=[newton.JointType.FREE, newton.JointType.BALL], ) # inspect q = scalar_view.get_dof_positions(state) # shape [world_count, articulation_count, dof_count] qd = scalar_view.get_dof_velocities(state) # shape [world_count, articulation_count, dof_count] link_q = view.get_link_transforms(state) # shape [world_count, articulation_count, link_count] assert q.shape == (1, 2, 1) assert qd.shape == (1, 2, 1) assert link_q.shape == (1, 2, 2) # edit selected articulation values in-place q_np = q.numpy() q_np[..., 0] = 0.0 scalar_view.set_dof_positions(state, q_np) assert np.allclose(scalar_view.get_dof_positions(state).numpy()[0, :, 0], 0.0) # if model attributes are edited through the view, notify the solver afterwards # solver.notify_model_changed() .. _FK-IK: Forward / Inverse Kinematics ---------------------------- Articulated rigid-body mechanisms are kinematically described by the joints that connect the bodies as well as the relative transform from the parent and child body to the respective anchor frames of the joint in the parent and child body: .. image:: /_static/joint_transforms.png :width: 400 :align: center .. list-table:: Variable names in the articulation kernels :widths: 10 90 :header-rows: 1 * - Symbol - Description * - x_wp - World transform of the parent body (stored at :attr:`State.body_q`) * - x_wc - World transform of the child body (stored at :attr:`State.body_q`) * - x_pj - Transform from the parent body to the joint parent anchor frame (defined by :attr:`Model.joint_X_p`) * - x_cj - Transform from the child body to the joint child anchor frame (defined by :attr:`Model.joint_X_c`) * - x_j - Joint transform from the joint parent anchor frame to the joint child anchor frame In the forward kinematics, the joint transform is determined by the joint coordinates (generalized joint positions :attr:`State.joint_q` and velocities :attr:`State.joint_qd`). Given the parent body's world transform :math:`x_{wp}` and the joint transform :math:`x_{j}`, the child body's world transform :math:`x_{wc}` is computed as: .. math:: x_{wc} = x_{wp} \cdot x_{pj} \cdot x_{j} \cdot x_{cj}^{-1}. .. autofunction:: newton.eval_fk :noindex: .. autofunction:: newton.eval_ik :noindex: .. _Orphan joints: Orphan joints ------------- An **orphan joint** is a joint that is not part of any articulation. This situation can arise when: * The USD asset does not define a ``PhysicsArticulationRootAPI`` on any prim, so no articulations are discovered during parsing. * A joint connects two bodies that are not under any ``PhysicsArticulationRootAPI`` prim, even though other articulations exist in the scene. When orphan joints are detected during USD parsing (:meth:`~newton.ModelBuilder.add_usd`), Newton issues a warning that lists the affected joint paths. **Validation and finalization** By default, :meth:`~newton.ModelBuilder.finalize` validates that every joint belongs to an articulation and raises a :class:`ValueError` if orphan joints are found. To proceed with orphan joints, skip this validation: .. testsetup:: articulation-orphan-joints builder = newton.ModelBuilder() body = builder.add_link() builder.add_shape_box(body, hx=0.1, hy=0.1, hz=0.1) builder.add_joint_revolute(parent=-1, child=body, axis=newton.Axis.Z) .. testcode:: articulation-orphan-joints model = builder.finalize(skip_validation_joints=True) **Solver compatibility** Only maximal-coordinate solvers (:class:`~newton.solvers.SolverXPBD`, :class:`~newton.solvers.SolverSemiImplicit`) support orphan joints. Generalized-coordinate solvers (:class:`~newton.solvers.SolverFeatherstone`, :class:`~newton.solvers.SolverMuJoCo`) require every joint to belong to an articulation. ================================================ FILE: docs/concepts/collisions.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 .. currentmodule:: newton .. _Collisions: Collisions ========== Newton provides a GPU-accelerated collision detection system with: - **Full shape-pair coverage** — every shape type collides with every other shape type (see :ref:`Shape Compatibility`). - **Mesh-mesh contacts** via precomputed SDFs for O(1) distance queries on complex geometry. - **Hydroelastic contacts** that sample contacts across the contact surface for improved fidelity in torsional friction and force distribution, especially in non-convex and manipulation scenarios. - **Drop-in replacement for MuJoCo's contacts** — use Newton's pipeline with :class:`~solvers.SolverMuJoCo` for advanced contact models (see :ref:`MuJoCo Warp Integration`). This page starts with a :ref:`conceptual overview ` of how geometry representations and narrow phase algorithms combine, then covers each stage in detail. .. _Collision Overview: Conceptual Overview ------------------- Newton's collision pipeline runs in two stages: a **broad phase** that quickly eliminates shape pairs whose bounding boxes do not overlap, followed by a **narrow phase** that computes the actual contact geometry for surviving pairs. The narrow phase algorithm used for a given pair depends on how the shapes are represented: .. mermaid:: :config: {"theme": "forest", "themeVariables": {"lineColor": "#76b900"}} flowchart LR BP["Broad Phase
(AABB culling)"] --> Triage subgraph Triage ["Pair Triage"] G1["Convex / primitive
pairs"] G2["Mesh pairs
(BVH or SDF)"] end subgraph NP ["Narrow Phase"] A["MPR / GJK"] B["Distance queries
+ contact reduction"] C["Hydroelastic
+ contact reduction"] end G1 --> A --> Contacts G2 --> B --> Contacts G2 -.->|"both shapes
hydroelastic"| C --> Contacts **Geometry representations** 1. **Convex hulls and primitives** — sphere, box, capsule, cylinder, cone, ellipsoid, and convex mesh shapes expose canonical support functions. These feed directly into the **MPR/GJK** narrow phase which produces contact points without further reduction. See :ref:`Narrow Phase`. 2. **Live BVH queries** — triangle meshes that do *not* have a precomputed SDF are queried through Warp's BVH (Bounding Volume Hierarchy). This path computes on-the-fly distance queries and generates contacts with optional contact reduction. It works out of the box but can be slow for high-triangle-count meshes. Hydroelastic contacts are **not** available on this path. See :ref:`Mesh Collisions`. 3. **Precomputed SDFs** — calling ``mesh.build_sdf(...)`` on a mesh precomputes a signed distance field that provides O(1) distance lookups. Primitive shapes can also generate SDF grids via ``ShapeConfig`` SDF parameters (see :ref:`Shape Configuration`). This path supports both **distance-query** and **hydroelastic** contact generation (with contact reduction). Hydroelastic contacts require SDF on *both* shapes in a pair. See :ref:`Mesh Collisions` and :ref:`Hydroelastic Contacts`. .. note:: **Contact reduction** applies to the SDF-based and hydroelastic paths where many raw contacts are generated from distance field queries. The direct MPR/GJK path for convex pairs produces a small number of contacts and does not require reduction. See :ref:`Contact Reduction`. .. tip:: For scenes with expensive collision (SDF or hydroelastic), running ``collide`` once per frame instead of every substep can significantly improve performance. See :ref:`Common Patterns` for the different collision-frequency patterns. .. _Contact Model: Contact Geometry ^^^^^^^^^^^^^^^^ The output of the narrow phase is a set of **contacts**: lightweight geometric descriptors that decouple the solver from the underlying shape complexity. A mesh may contain hundreds of thousands of triangles, but the collision pipeline distills the interaction into a manageable number of contacts that the solver can process efficiently. Each contact carries the following geometric data: .. figure:: ../images/contact_model.svg :alt: Contact geometry: normal, contact points, contact distance :width: 70% :align: center A contact between two shapes (A and B). The **contact normal** (blue, unit length) points from shape A to shape B. **Body-frame contact points** (yellow) are stored in each body's local frame. The **contact midpoint** (red) — the average of the two world-space contact points — is not stored but is useful for visualization and debugging. The **contact distance** encodes the signed separation or penetration depth. - **Contact normal** (world frame) — a unit vector pointing from shape A toward shape B. - **Contact points** (body frame) — the contact location on each shape (``rigid_contact_point0/1``), stored in the parent body's local coordinate frame. - **Contact distance** — the signed separation between the two contact points along the normal. Negative values indicate penetration. Because contacts are self-contained geometric objects, the solver never needs to query mesh triangles or SDF grids — it only works with the contact arrays stored in :class:`~Contacts`. See :ref:`Contact Generation` for the full data layout. .. _MuJoCo Warp Integration: MuJoCo Warp Integration ^^^^^^^^^^^^^^^^^^^^^^^^ :class:`~solvers.SolverMuJoCo` (the MuJoCo Warp backend) ships with its own built-in collision pipeline that handles convex primitive contacts. For many use cases this is sufficient and requires no extra setup. Newton's collision pipeline can also **replace** MuJoCo's contact generation, enabling SDF-based mesh-mesh contacts and hydroelastic contacts that MuJoCo's built-in pipeline does not support. Examples: - **Hydroelastic mesh contacts** — :github:`newton/examples/contacts/example_nut_bolt_hydro.py` - **SDF mesh contacts** — :github:`newton/examples/contacts/example_nut_bolt_sdf.py` - **Robot manipulation with SDF** — :github:`newton/examples/contacts/example_brick_stacking.py` See :ref:`Solver Integration` for the full code pattern showing how to configure this. .. _Collision Pipeline: Collision Pipeline ------------------ Newton's collision pipeline implementation supports multiple broad phase algorithms and advanced contact models (SDF-based, hydroelastic, cylinder/cone primitives). See :ref:`Collision Pipeline Details` for details. Basic usage: .. testsetup:: pipeline-basics import warp as wp import newton builder = newton.ModelBuilder() builder.add_ground_plane() body = builder.add_body(xform=wp.transform((0.0, 0.0, 2.0), wp.quat_identity())) builder.add_shape_sphere(body, radius=0.5) model = builder.finalize() state = model.state() .. testcode:: pipeline-basics # Default: creates CollisionPipeline with EXPLICIT broad phase (precomputed pairs) contacts = model.contacts() model.collide(state, contacts) # Or create a pipeline explicitly to choose broad phase mode from newton import CollisionPipeline pipeline = CollisionPipeline( model, broad_phase="sap", ) contacts = pipeline.contacts() pipeline.collide(state, contacts) .. _Quick Start: Quick Start ----------- A minimal end-to-end example that creates shapes, runs collision detection, and steps the solver (see also the :doc:`Introduction tutorial ` and ``example_basic_shapes.py`` — :github:`newton/examples/basic/example_basic_shapes.py`): .. testcode:: quickstart import warp as wp import newton builder = newton.ModelBuilder() builder.add_ground_plane() # Dynamic sphere body = builder.add_body(xform=wp.transform((0.0, 0.0, 2.0), wp.quat_identity())) builder.add_shape_sphere(body, radius=0.5) model = builder.finalize() solver = newton.solvers.SolverXPBD(model, iterations=5) state_0 = model.state() state_1 = model.state() control = model.control() contacts = model.contacts() dt = 1.0 / 60.0 / 10.0 for frame in range(120): for substep in range(10): state_0.clear_forces() model.collide(state_0, contacts) solver.step(state_0, state_1, control, contacts, dt) state_0, state_1 = state_1, state_0 .. _Supported Shape Types: Supported Shape Types --------------------- Newton supports the following geometry types via :class:`~GeoType`: .. list-table:: :header-rows: 1 :widths: 20 80 * - Type - Description * - ``PLANE`` - Infinite plane (ground) * - ``HFIELD`` - Heightfield terrain (2D elevation grid) * - ``SPHERE`` - Sphere primitive * - ``CAPSULE`` - Cylinder with hemispherical ends * - ``BOX`` - Axis-aligned box * - ``CYLINDER`` - Cylinder * - ``CONE`` - Cone * - ``ELLIPSOID`` - Ellipsoid * - ``MESH`` - Triangle mesh (arbitrary, including non-convex) * - ``CONVEX_MESH`` - Convex hull mesh .. note:: **SDF is collision data, not a standalone shape type.** For mesh shapes, build and attach an SDF explicitly with ``mesh.build_sdf(...)`` and then pass that mesh to ``builder.add_shape_mesh(...)``. For primitive hydroelastic workflows, SDF generation uses ``ShapeConfig`` SDF parameters. .. _Shapes and Bodies: Shapes and Rigid Bodies ----------------------- Collision shapes are attached to rigid bodies. Each shape has: - **Body index** (``shape_body``): The rigid body this shape is attached to. Use ``body=-1`` for static/world-fixed shapes. - **Local transform** (``shape_transform``): Position and orientation relative to the body frame. - **Scale** (``shape_scale``): 3D scale factors applied to the shape geometry. - **Margin** (``shape_margin``): Surface offset that shifts where contact points are placed. See :ref:`Margin and gap semantics `. - **Gap** (``shape_gap``): Extra detection distance that shifts when contacts are generated. See :ref:`Margin and gap semantics `. - **Source geometry** (``shape_source``): Reference to the underlying geometry object (e.g., :class:`~Mesh`). During collision detection, shapes are transformed to world space using their parent body's pose: .. code-block:: python # Shape world transform = body_pose * shape_local_transform X_world_shape = body_q[shape_body] * shape_transform[shape_id] Contacts are generated between shapes, not bodies. Depending on the type of solver, the motion of the bodies is affected by forces or constraints that resolve the penetrations between their attached shapes. .. _Collision Filtering: Collision Filtering ------------------- The collision pipeline uses filtering rules based on world indices and collision groups. .. _World IDs: World Indices ^^^^^^^^^^^^^ World indices enable multi-world simulations, primarily for reinforcement learning, where objects belonging to different worlds coexist but do not interact through contacts: - **Index -1**: Global entities that collide with all worlds (e.g., ground plane) - **Index 0, 1, 2, ...**: World-specific entities that only interact within their world .. testcode:: world-indices builder = newton.ModelBuilder() # Global ground (default world -1, collides with all worlds) builder.add_ground_plane() # Robot template robot_builder = newton.ModelBuilder() body = robot_builder.add_link() robot_builder.add_shape_sphere(body, radius=0.5) joint = robot_builder.add_joint_free(body) robot_builder.add_articulation([joint]) # Instantiate in separate worlds - robots won't collide with each other builder.add_world(robot_builder) # World 0 builder.add_world(robot_builder) # World 1 model = builder.finalize() For heterogeneous worlds, use :meth:`~ModelBuilder.begin_world` and :meth:`~ModelBuilder.end_world`. For large-scale parallel simulations (e.g., RL), :meth:`~ModelBuilder.replicate` stamps out many copies of a template environment builder into separate worlds in one call: .. testcode:: replicate # Template environment: one sphere per world env_builder = newton.ModelBuilder() body = env_builder.add_body() env_builder.add_shape_sphere(body, radius=0.5) # Combined builder: global geometry + 1024 replicated worlds main = newton.ModelBuilder() main.add_ground_plane() # global (world -1), shared across all worlds main.replicate(env_builder, world_count=1024) model = main.finalize() .. note:: MJWarp does not currently support heterogeneous environments (different models per world). World indices are stored in :attr:`~Model.shape_world`, :attr:`~Model.body_world`, etc. .. _Collision Groups: Collision Groups ^^^^^^^^^^^^^^^^ Collision groups control which shapes collide within the same world: - **Group 0**: Collisions disabled - **Positive groups (1, 2, ...)**: Collide with same group or any negative group - **Negative groups (-1, -2, ...)**: Collide with shapes in any positive or negative group, except shapes in the same negative group .. list-table:: :header-rows: 1 :widths: 15 15 15 55 * - Group A - Group B - Collide? - Reason * - 0 - Any - ❌ - Group 0 disables collision * - 1 - 1 - ✅ - Same positive group * - 1 - 2 - ❌ - Different positive groups * - 1 - -2 - ✅ - Positive with any negative * - -1 - -1 - ❌ - Same negative group * - -1 - -2 - ✅ - Different negative groups .. testcode:: collision-groups builder = newton.ModelBuilder() # Group 1: only collides with group 1 and negative groups body1 = builder.add_body() builder.add_shape_sphere(body1, radius=0.5, cfg=builder.ShapeConfig(collision_group=1)) # Group -1: collides with everything (except other -1) body2 = builder.add_body() builder.add_shape_sphere(body2, radius=0.5, cfg=builder.ShapeConfig(collision_group=-1)) model = builder.finalize() **Self-collision within articulations** Self-collisions within an articulation can be enabled or disabled with ``enable_self_collisions`` when loading models. By default, adjacent body collisions (parent-child pairs connected by joints) are disabled via ``collision_filter_parent=True``. .. code-block:: python # Enable self-collisions when loading models builder.add_usd("robot.usda", enable_self_collisions=True) builder.add_mjcf("robot.xml", enable_self_collisions=True) # Or control per-shape (also applies to max-coordinate jointed bodies) cfg = builder.ShapeConfig(collision_group=-1, collision_filter_parent=False) **Controlling particle collisions** Use ``has_shape_collision`` and ``has_particle_collision`` for fine-grained control over what a shape collides with. Setting both to ``False`` is equivalent to ``collision_group=0``. .. testcode:: particle-collision builder = newton.ModelBuilder() # Shape that only collides with particles (not other shapes) cfg = builder.ShapeConfig(has_shape_collision=False, has_particle_collision=True) # Shape that only collides with other shapes (not particles) cfg = builder.ShapeConfig(has_shape_collision=True, has_particle_collision=False) UsdPhysics Collision Filtering ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Newton follows the `UsdPhysics collision filtering specification `_, which provides two complementary mechanisms for controlling which shapes collide: 1. **Collision Groups** - Group-based filtering using ``UsdPhysicsCollisionGroup`` 2. **Pairwise Filtering** - Explicit shape pair exclusions using ``physics:filteredPairs`` **Collision Groups** In UsdPhysics, shapes can be assigned to collision groups defined by ``UsdPhysicsCollisionGroup`` prims. When importing USD files, Newton reads the ``collisionGroups`` attribute from each shape and maps each unique collision group name to a positive integer ID (starting from 1). Shapes in different collision groups will not collide with each other unless their groups are configured to interact. .. code-block:: usda # Define a collision group in USD def "CollisionGroup_Robot" ( prepend apiSchemas = ["PhysicsCollisionGroup"] ) { } # Assign shape to a collision group def Sphere "RobotPart" ( prepend apiSchemas = ["PhysicsCollisionAPI"] ) { rel physics:collisionGroup = } When loading this USD, Newton automatically assigns each collision group a unique integer ID and sets the shape's ``collision_group`` accordingly. **Pairwise Filtering** For fine-grained control, UsdPhysics supports explicit pair filtering via the ``physics:filteredPairs`` relationship. This allows excluding specific shape pairs from collision detection regardless of their collision groups. .. code-block:: usda # Exclude specific shape pairs in USD def Sphere "ShapeA" ( prepend apiSchemas = ["PhysicsCollisionAPI"] ) { rel physics:filteredPairs = [] } Newton reads these relationships during USD import and converts them to :attr:`~ModelBuilder.shape_collision_filter_pairs`. **Collision Enabled Flag** Shapes with ``physics:collisionEnabled=false`` are excluded from all collisions by adding filter pairs against all other shapes in the scene. Shape Collision Filter Pairs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^ The :attr:`~ModelBuilder.shape_collision_filter_pairs` list stores explicit shape pair exclusions. This is Newton's internal representation for pairwise filtering (including pairs imported from UsdPhysics ``physics:filteredPairs`` relationships). .. testcode:: filter-pairs builder = newton.ModelBuilder() # Add shapes body = builder.add_body() shape_a = builder.add_shape_sphere(body, radius=0.5) shape_b = builder.add_shape_box(body, hx=0.5, hy=0.5, hz=0.5) # Exclude this specific pair from collision detection builder.add_shape_collision_filter_pair(shape_a, shape_b) Filter pairs are automatically populated in several cases: - **Adjacent bodies**: Parent-child body pairs connected by joints (when ``collision_filter_parent=True``). Also applies to max-coordinate jointed bodies. - **Same-body shapes**: Shapes attached to the same rigid body - **Disabled self-collision**: All shape pairs within an articulation when ``enable_self_collisions=False`` - **USD filtered pairs**: Pairs defined by ``physics:filteredPairs`` relationships in USD files - **USD collision disabled**: Shapes with ``physics:collisionEnabled=false`` (filtered against all other shapes) The resulting filter pairs are stored in :attr:`~Model.shape_collision_filter_pairs` as a set of ``(shape_index_a, shape_index_b)`` tuples (canonical order: ``a < b``). **USD Import Example** .. code-block:: python # Newton automatically imports UsdPhysics collision filtering builder = newton.ModelBuilder() builder.add_usd("scene.usda") # Collision groups and filter pairs are now populated: # - shape_collision_group: integer IDs mapped from UsdPhysicsCollisionGroup # - shape_collision_filter_pairs: pairs from physics:filteredPairs relationships model = builder.finalize() .. _Collision Pipeline Details: Broad Phase and Shape Compatibility ----------------------------------- :class:`~CollisionPipeline` provides configurable broad phase algorithms: .. list-table:: :header-rows: 1 :widths: 15 85 * - Mode - Description * - **NxN** - All-pairs AABB broad phase. O(N²), optimal for small scenes (<100 shapes). * - **SAP** - Sweep-and-prune AABB broad phase. O(N log N), better for larger scenes with spatial coherence. * - **EXPLICIT** - Uses precomputed shape pairs (default). Combines static pair efficiency with advanced contact algorithms. .. testsetup:: broad-phase import warp as wp import newton builder = newton.ModelBuilder() builder.add_ground_plane() body = builder.add_body(xform=wp.transform((0.0, 0.0, 2.0), wp.quat_identity())) builder.add_shape_sphere(body, radius=0.5) model = builder.finalize() state = model.state() .. testcode:: broad-phase from newton import CollisionPipeline # Default: EXPLICIT (precomputed pairs) pipeline = CollisionPipeline(model) # NxN for small scenes pipeline = CollisionPipeline(model, broad_phase="nxn") # SAP for larger scenes pipeline = CollisionPipeline(model, broad_phase="sap") contacts = pipeline.contacts() pipeline.collide(state, contacts) .. _Shape Compatibility: Shape Compatibility ^^^^^^^^^^^^^^^^^^^ Shape compatibility summary (rigid + soft particle-shape): .. list-table:: :header-rows: 1 :widths: 11 7 7 7 7 7 7 7 7 7 7 7 7 * - - Plane - HField - Sphere - Capsule - Box - Cylinder - Cone - Ellipsoid - ConvexHull - Mesh - SDF - Particle * - **Plane** - [1] - [1] - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ * - **HField** - [1] - [1] - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅⚠️ - ✅ - ✅ * - **Sphere** - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ * - **Capsule** - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ * - **Box** - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ * - **Cylinder** - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ * - **Cone** - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ * - **Ellipsoid** - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ * - **ConvexHull** - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ * - **Mesh** - ✅ - ✅⚠️ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅⚠️ - ✅⚠️ - ✅ * - **SDF** - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅⚠️ - ✅ - ✅ * - **Particle** - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - ✅ - [2] **Legend:** ⚠️ = Can be slow for meshes with high triangle counts; performance can often be improved by attaching a precomputed SDF to the mesh (``mesh.build_sdf(...)``). | [1] Plane and heightfield shapes are static (world-attached) in Newton; static-static pairs are filtered from rigid collision generation. | [2] Particle-particle interactions are handled by the particle/soft-body solver self-collision path, not by the shape compatibility pipeline in this table. .. note:: ``Particle`` in this table refers to soft particle-shape contacts generated automatically by the collision pipeline. These contacts additionally require the shape to have particle collision enabled (``ShapeFlags.COLLIDE_PARTICLES`` / ``ShapeConfig.has_particle_collision``). For examples, see cloth and cable scenes that use the collision pipeline for particle-shape contacts. .. note:: **Heightfield representation:** A heightfield (``HFIELD``) stores a regular 2D grid of elevation samples. For rigid contacts, Newton uses dedicated heightfield narrow-phase routes: heightfield-vs-convex uses per-cell triangle GJK/MPR, while mesh-vs-heightfield routes through the mesh/SDF path with on-the-fly triangle extraction from the grid. For soft contacts, the collision pipeline automatically samples the heightfield signed distance and normal. .. note:: **SDF** in this table refers to shapes with precomputed SDF data. There is no ``GeoType.SDF`` enum value; this row is a conceptual collision mode for shapes carrying SDF resources. Mesh SDFs are attached through ``mesh.build_sdf(...)`` and provide O(1) distance queries. .. _Narrow Phase: Narrow Phase Algorithms ----------------------- After broad phase identifies candidate pairs, the narrow phase generates contact points. The algorithm used depends on the shape types in each pair. .. _Convex Primitive Contacts: Convex Primitive Contacts ^^^^^^^^^^^^^^^^^^^^^^^^^ **MPR (Minkowski Portal Refinement) and GJK** MPR is the primary algorithm for convex shape pairs. It uses support mapping functions to find the closest points between shapes via Minkowski difference sampling. Works with all convex primitives (sphere, box, capsule, cylinder, cone, ellipsoid) and convex meshes. Newton uses MPR for penetration depth computation (not EPA); GJK handles the separated-shapes distance query. **Multi-contact generation** For convex primitive pairs, multiple contact points are generated for stable stacking and resting contacts. The collision pipeline estimates buffer sizes based on the model; you can override this value with ``rigid_contact_max`` when instantiating the pipeline. .. _Mesh Collisions: Mesh Collision Handling ^^^^^^^^^^^^^^^^^^^^^^^ Mesh collisions use different strategies depending on the pair type: **Mesh vs Primitive (e.g., Sphere, Box)** Uses BVH (Bounding Volume Hierarchy) queries to find nearby triangles, then generates contacts between primitive vertices and triangle surfaces, plus triangle vertices against the primitive. **Mesh vs Plane** Projects mesh vertices onto the plane and generates contacts for vertices below the plane surface. **Mesh vs Mesh** Two approaches available: 1. **BVH-based** (default when no SDF configured): Iterates mesh vertices against the other mesh's BVH. Performance scales with triangle count - can be very slow for complex meshes. 2. **SDF-based** (recommended): Uses precomputed signed distance fields for fast queries. For mesh shapes, call ``mesh.build_sdf(...)`` once and reuse the mesh. .. warning:: If SDF is not precomputed, mesh-mesh contacts fall back to on-the-fly BVH distance queries which are **significantly slower**. For production use with complex meshes, precompute and attach SDF data on meshes: .. code-block:: python my_mesh.build_sdf(max_resolution=64) builder.add_shape_mesh(body, mesh=my_mesh) .. tip:: **Build an SDF on every mesh that can collide**, even when high-precision contacts are not required. A low-resolution SDF (e.g., ``max_resolution=64``) uses very little memory yet still provides O(1) distance queries that are dramatically faster than the BVH fallback. Without an SDF, mesh-vs-mesh and mesh-vs-primitive contacts must walk the BVH for every query point, which dominates collision cost in most scenes. Attaching even a coarse SDF eliminates this bottleneck. :meth:`~Mesh.build_sdf` accepts several optional keyword arguments (defaults shown in parentheses): .. code-block:: python mesh.build_sdf( max_resolution=256, # Max voxels along longest AABB axis; must be divisible by 8 (None) narrow_band_range=(-0.005, 0.005), # SDF narrow band [m] ((-0.1, 0.1)) margin=0.005, # Extra AABB padding [m] (0.05) shape_margin=0.001, # Shrink SDF surface inward [m] (0.0) scale=(1.0, 1.0, 1.0), # Bake non-unit scale into the SDF (None) ) ``max_resolution`` sets the voxel count along the longest AABB axis (must be divisible by 8); voxel size is uniform across all axes. Use ``target_voxel_size`` instead to specify resolution in meters directly — it takes precedence over ``max_resolution`` when both are provided. Use ``narrow_band_range`` to limit the SDF computation to a thin shell around the surface (saves memory and build time). Set the SDF ``margin`` to at least the sum of the shape's :ref:`margin and gap ` so the SDF covers the full contact detection range. Pass ``scale`` when the shape will be added with non-unit scale to bake it into the SDF grid. ``shape_margin`` is mainly useful for hydroelastic collision where a compliant-layer offset is desired. **Mesh simplification for collision** For imported models (URDF, MJCF, USD) whose visual meshes are too detailed for efficient collision, :meth:`~ModelBuilder.approximate_meshes` replaces mesh collision shapes with convex hulls, bounding boxes, or convex decompositions: .. code-block:: python builder.add_usd("robot.usda") # Replace all collision meshes with convex hulls (default) builder.approximate_meshes() # Or target specific shapes and keep visual geometry builder.approximate_meshes( method="convex_hull", shape_indices=non_finger_shapes, keep_visual_shapes=True, ) Supported methods: ``"convex_hull"`` (default), ``"bounding_box"``, ``"bounding_sphere"``, ``"coacd"`` (convex decomposition), ``"vhacd"``. .. note:: ``approximate_meshes()`` modifies the builder's shape geometry in-place. By default (``keep_visual_shapes=False``), the original mesh is replaced for both collision and rendering. Pass ``keep_visual_shapes=True`` to preserve the original mesh as a visual-only shape alongside the simplified collision shape. .. _Contact Reduction: Contact Reduction ^^^^^^^^^^^^^^^^^ Contact reduction is enabled by default. For scenes with many mesh-mesh interactions that generate thousands of contacts, reduction selects a significantly smaller representative set that maintains stable contact behavior while improving solver performance. **How it works:** 1. Contacts are binned by normal direction (polyhedron face directions) 2. Within each bin, contacts are scored by spatial distribution and penetration depth 3. Representative contacts are selected to preserve coverage and depth cues To disable reduction, set ``reduce_contacts=False`` when creating the pipeline. **Configuring contact reduction (HydroelasticSDF.Config):** For hydroelastic and SDF-based contacts, use :class:`~geometry.HydroelasticSDF.Config` to tune reduction behavior: .. testsetup:: hydro-config import warp as wp import newton from newton import CollisionPipeline builder = newton.ModelBuilder() builder.add_ground_plane() body = builder.add_body(xform=wp.transform((0.0, 0.0, 2.0), wp.quat_identity())) builder.add_shape_sphere(body, radius=0.5) model = builder.finalize() .. testcode:: hydro-config from newton.geometry import HydroelasticSDF config = HydroelasticSDF.Config( reduce_contacts=True, # Enable contact reduction (default) buffer_fraction=0.2, # Reduce GPU buffer allocations (default: 1.0) normal_matching=True, # Align reduced normals with aggregate force anchor_contact=False, # Optional center-of-pressure anchor contact ) pipeline = CollisionPipeline(model, sdf_hydroelastic_config=config) **Other reduction options:** .. list-table:: :header-rows: 1 :widths: 30 70 * - Parameter - Description * - ``normal_matching`` - Rotates selected contact normals so their weighted sum aligns with the aggregate force direction from all unreduced contacts. Preserves net force direction after reduction. Default: True. * - ``anchor_contact`` - Adds an anchor contact at the center of pressure for each normal bin to better preserve moments. Default: False. * - ``margin_contact_area`` - Lower bound on contact area. Hydroelastic stiffness is ``area * k_eff``, but contacts within the contact margin that are not yet penetrating (speculative contacts) have zero geometric area. This provides a floor value so they still generate repulsive force. Default: 0.01. .. _Shape Configuration: Shape Configuration ------------------- Shape collision behavior is controlled via :class:`~ModelBuilder.ShapeConfig`: **Collision control:** .. list-table:: :header-rows: 1 :widths: 30 70 * - Parameter - Description * - ``collision_group`` - Collision group ID. 0 disables collisions. Default: 1. * - ``collision_filter_parent`` - Filter collisions with adjacent body (parent in articulation or connected via joint). Default: True. * - ``has_shape_collision`` - Whether shape collides with other shapes. Default: True. * - ``has_particle_collision`` - Whether shape collides with particles. Default: True. **Geometry parameters:** .. list-table:: :header-rows: 1 :widths: 25 75 * - Parameter - Description * - ``margin`` - Surface offset used by narrow phase. Pairwise effect is additive (``m_a + m_b``): contacts are evaluated against the signed distance to the margin-shifted surfaces, so resting separation is ``m_a + m_b``. Helps thin shells/cloth stability and reduces self-intersections. Default: 0.0. * - ``gap`` - Additional detection threshold. Pairwise effect is additive (``g_a + g_b``). Broad phase expands each shape AABB by ``(margin + gap)`` per shape; narrow phase then keeps a candidate contact when ``d <= g_a + g_b`` (with ``d`` measured relative to margin-shifted surfaces). Increasing gap detects contacts earlier and helps reduce tunneling. Default: None (uses ``builder.rigid_gap``, which defaults to 0.1). * - ``is_solid`` - Whether shape is solid or hollow. Affects inertia and SDF sign. Default: True. * - ``is_hydroelastic`` - Whether the shape uses SDF-based hydroelastic contacts. Both shapes in a pair must have this enabled. See :ref:`Hydroelastic Contacts`. Default: False. * - ``kh`` - Contact stiffness for hydroelastic collisions. Used by MuJoCo, Featherstone, SemiImplicit when ``is_hydroelastic=True``. Default: 1.0e10. .. _margin-gap-semantics: **Margin and gap semantics (where vs when):** - **Where contacts are placed** is controlled by ``margin``. - **When contacts are generated** is controlled by ``gap``. For a shape pair ``(a, b)``: - Pair margin: ``m = margin_a + margin_b`` - Pair gap: ``g = gap_a + gap_b`` - Surface distance (true geometry, no offsets): ``s`` - Contact-space distance used by Newton: ``d = s - m`` Contacts are generated when: .. math:: d \leq g \quad\Leftrightarrow\quad s \leq (m + g) Broad phase uses the same idea by expanding each shape AABB by: .. math:: margin_i + gap_i This keeps broad-phase culling and narrow-phase contact generation consistent. The solver enforces ``d >= 0``, so objects at rest settle with surfaces separated by ``margin_a + margin_b``. .. figure:: ../images/margin_and_gap.svg :alt: Margin and gap contact generation phases :width: 90% :align: center Margin sets contact location (surface offset), while gap adds speculative detection distance on top of margin. Left: no contact generated. Middle: contact generated but not yet active. Right: active contact support. **SDF configuration (primitive generation defaults):** .. list-table:: :header-rows: 1 :widths: 30 70 * - Parameter - Description * - ``sdf_max_resolution`` - Maximum SDF grid dimension (must be divisible by 8) for primitive SDF generation. * - ``sdf_target_voxel_size`` - Target voxel size for primitive SDF generation. Takes precedence over ``sdf_max_resolution``. * - ``sdf_narrow_band_range`` - SDF narrow band distance range (inner, outer). Default: (-0.1, 0.1). The :meth:`~ModelBuilder.ShapeConfig.configure_sdf` helper sets SDF and hydroelastic options in one call: .. testcode:: configure-sdf builder = newton.ModelBuilder() cfg = builder.ShapeConfig() cfg.configure_sdf(max_resolution=64, is_hydroelastic=True, kh=1.0e11) Example (mesh SDF workflow): .. code-block:: python cfg = builder.ShapeConfig( collision_group=-1, # Collide with everything margin=0.001, # 1mm margin gap=0.01, # 1cm detection gap ) my_mesh.build_sdf(max_resolution=64) builder.add_shape_mesh(body, mesh=my_mesh, cfg=cfg) **Builder default gap:** The builder's ``rigid_gap`` (default 0.1) applies to shapes without explicit ``gap``. Alternatively, use ``builder.default_shape_cfg.gap``. .. _Common Patterns: Common Patterns --------------- **Creating static/ground geometry** Use ``body=-1`` to attach shapes to the static world frame: .. testcode:: static-geometry builder = newton.ModelBuilder() # Static ground plane builder.add_ground_plane() # Convenience method # Or manually create static shapes builder.add_shape_plane(body=-1, xform=wp.transform_identity()) builder.add_shape_box(body=-1, hx=5.0, hy=5.0, hz=0.1) # Static floor **Setting default shape configuration** Use ``builder.default_shape_cfg`` to set defaults for all shapes: .. testcode:: default-shape-cfg builder = newton.ModelBuilder() # Set defaults before adding shapes builder.default_shape_cfg.ke = 1.0e6 builder.default_shape_cfg.kd = 1000.0 builder.default_shape_cfg.mu = 0.5 builder.default_shape_cfg.is_hydroelastic = True builder.default_shape_cfg.sdf_max_resolution = 64 # Primitive SDF defaults **Collision frequency in the simulation loop** There are two common patterns for when to call ``collide`` relative to the substep loop: .. testsetup:: sim-loop import warp as wp import newton from newton import CollisionPipeline builder = newton.ModelBuilder() builder.add_ground_plane() body = builder.add_body(xform=wp.transform((0.0, 0.0, 2.0), wp.quat_identity())) builder.add_shape_sphere(body, radius=0.5) model = builder.finalize() solver = newton.solvers.SolverXPBD(model, iterations=5) pipeline = CollisionPipeline(model, broad_phase="sap") state_0 = model.state() state_1 = model.state() control = model.control() contacts = model.contacts() num_frames = 2 sim_substeps = 3 sim_dt = 1.0 / 60.0 / sim_substeps collide_every_n = 2 *Every substep* (most accurate, used by most basic examples): .. testcode:: sim-loop for frame in range(num_frames): for substep in range(sim_substeps): model.collide(state_0, contacts) solver.step(state_0, state_1, control, contacts, dt=sim_dt) state_0, state_1 = state_1, state_0 *Once per frame* (faster, common for hydroelastic/SDF-heavy scenes): .. testcode:: sim-loop for frame in range(num_frames): contacts = model.collide(state_0, collision_pipeline=pipeline) for substep in range(sim_substeps): solver.step(state_0, state_1, control, contacts, dt=sim_dt) state_0, state_1 = state_1, state_0 Another pattern is to run collision detection every N substeps for a middle ground: .. testcode:: sim-loop for frame in range(num_frames): for substep in range(sim_substeps): if substep % collide_every_n == 0: pipeline.collide(state_0, contacts) solver.step(state_0, state_1, control, contacts, dt=sim_dt) state_0, state_1 = state_1, state_0 **Soft contacts (particle-shape)** Soft contacts are generated automatically when particles are present. They use a separate margin: .. testsetup:: soft-contacts import warp as wp import newton from newton import CollisionPipeline builder = newton.ModelBuilder() builder.add_ground_plane() builder.add_particle(pos=wp.vec3(0, 0, 1), vel=wp.vec3(0, 0, 0), mass=1.0) model = builder.finalize() state = model.state() .. testcode:: soft-contacts # Set soft contact margin pipeline = CollisionPipeline(model, soft_contact_margin=0.01) contacts = pipeline.contacts() pipeline.collide(state, contacts) # Access soft contact data n_soft = contacts.soft_contact_count.numpy()[0] particles = contacts.soft_contact_particle.numpy()[:n_soft] shapes = contacts.soft_contact_shape.numpy()[:n_soft] .. _Contact Generation: Contact Data ------------ The :class:`~Contacts` class stores the results from the collision detection step and is consumed by the solver :meth:`~solvers.SolverBase.step` method for contact handling. **Rigid contacts:** .. list-table:: :header-rows: 1 :widths: 35 65 * - Attribute - Description * - ``rigid_contact_count`` - Number of active rigid contacts (scalar). * - ``rigid_contact_shape0``, ``rigid_contact_shape1`` - Indices of colliding shapes. * - ``rigid_contact_point0``, ``rigid_contact_point1`` - Contact point on each shape (body frame). This is the narrow-phase contact location used by the solver for the normal constraint and lever-arm computation. * - ``rigid_contact_offset0``, ``rigid_contact_offset1`` - Body-frame friction-anchor offset per shape, equal to the contact normal scaled by ``effective_radius + margin``. Added to the contact point to form a shifted friction anchor that accounts for rotational effects of finite contact thickness in tangential friction calculations. * - ``rigid_contact_normal`` - Contact normal, pointing from shape 0 toward shape 1 (world frame). * - ``rigid_contact_margin0``, ``rigid_contact_margin1`` - Per-shape thickness: effective radius + margin (scalar). **Soft contacts (particle-shape):** .. list-table:: :header-rows: 1 :widths: 35 65 * - Attribute - Description * - ``soft_contact_count`` - Number of active soft contacts. * - ``soft_contact_particle`` - Particle indices. * - ``soft_contact_shape`` - Shape indices. * - ``soft_contact_body_pos``, ``soft_contact_body_vel`` - Contact position and velocity on shape. * - ``soft_contact_normal`` - Contact normal. **Extended contact attributes** (see :ref:`extended_contact_attributes`): .. list-table:: :header-rows: 1 :widths: 22 78 * - Attribute - Description * - :attr:`~Contacts.force` - Contact spatial forces (used by :class:`~sensors.SensorContact`) Example usage: .. testsetup:: contact-data import warp as wp import newton builder = newton.ModelBuilder() builder.add_ground_plane() body = builder.add_body(xform=wp.transform((0.0, 0.0, 2.0), wp.quat_identity())) builder.add_shape_sphere(body, radius=0.5) model = builder.finalize() state = model.state() .. testcode:: contact-data contacts = model.contacts() model.collide(state, contacts) n = contacts.rigid_contact_count.numpy()[0] points0 = contacts.rigid_contact_point0.numpy()[:n] points1 = contacts.rigid_contact_point1.numpy()[:n] normals = contacts.rigid_contact_normal.numpy()[:n] # Shape indices shape0 = contacts.rigid_contact_shape0.numpy()[:n] shape1 = contacts.rigid_contact_shape1.numpy()[:n] .. _Differentiable Contacts: Differentiable Contacts ----------------------- When ``requires_grad=True``, the :class:`~newton.Contacts` object provides an additional set of **differentiable** rigid-contact arrays that participate in :class:`wp.Tape` autodiff. These arrays give first-order gradients of contact distance and world-space contact points with respect to body poses (``state.body_q``). .. note:: Rigid-contact differentiability is **experimental**. Accuracy and fitness for real-world optimization or learning workflows should be validated case by case before relying on these gradients. Making the full narrow-phase pipeline differentiable end-to-end would be prohibitively expensive and numerically fragile — iterative GJK/MPR solvers, BVH traversals, and discrete contact-set changes all introduce discontinuities or ill-conditioned gradients. Newton therefore keeps the narrow phase frozen (``enable_backward=False``) and applies a lightweight **post-processing** step: it re-reads the contact geometry produced by the narrow phase (body-local points, world normal, margins) and reconstructs the world-space quantities through the differentiable ``body_q``. The result is a first-order tangent-plane approximation that is cheap, stable, and sufficient for most gradient-based optimization and reinforcement-learning workflows. **Differentiable arrays** (allocated only when ``requires_grad=True``): .. list-table:: :header-rows: 1 :widths: 40 60 * - Attribute - Description * - ``rigid_contact_diff_distance`` - Signed contact distance [m] (negative = penetration). * - ``rigid_contact_diff_normal`` - World-space contact normal (A → B). * - ``rigid_contact_diff_point0_world`` - World-space contact point on shape 0 [m]. * - ``rigid_contact_diff_point1_world`` - World-space contact point on shape 1 [m]. Gradients flow through the contact points and distance; the normal direction is treated as a frozen constant. .. testsetup:: diff-contacts import warp as wp import newton .. testcode:: diff-contacts builder = newton.ModelBuilder(gravity=0.0) body = builder.add_body(xform=wp.transform((0.0, 0.0, 0.3))) builder.add_shape_sphere(body=body, radius=0.5) builder.add_ground_plane() model = builder.finalize(requires_grad=True) pipeline = newton.CollisionPipeline(model) contacts = pipeline.contacts() state = model.state(requires_grad=True) with wp.Tape() as tape: pipeline.collide(state, contacts) # Backpropagate through differentiable distance tape.backward(grads={ contacts.rigid_contact_diff_distance: wp.ones( contacts.rigid_contact_max, dtype=float ) }) grad_body_q = tape.gradients[state.body_q] .. note:: The standard (non-differentiable) rigid-contact arrays (``rigid_contact_point0``, ``rigid_contact_normal``, etc.) are unaffected and remain available for solvers. The ``rigid_contact_diff_*`` arrays are an additional output intended for gradient-based optimization and ML workflows. .. _Creating Contacts: Creating and Populating Contacts -------------------------------- :meth:`~Model.contacts` creates a :class:`~Contacts` buffer using a default :class:`~CollisionPipeline` (EXPLICIT broad phase, cached on first call). :meth:`~Model.collide` populates it and returns the :class:`~Contacts` object: .. testsetup:: creating-contacts import warp as wp import newton builder = newton.ModelBuilder() builder.add_ground_plane() body = builder.add_body(xform=wp.transform((0.0, 0.0, 2.0), wp.quat_identity())) builder.add_shape_sphere(body, radius=0.5) model = builder.finalize() state = model.state() .. testcode:: creating-contacts contacts = model.contacts() model.collide(state, contacts) The contacts buffer can be reused across steps -- ``collide`` clears it each time. Both methods accept an optional ``collision_pipeline`` keyword to override the default pipeline. When ``contacts`` is omitted from ``collide``, a buffer is allocated automatically: .. testcode:: creating-contacts from newton import CollisionPipeline pipeline = CollisionPipeline( model, broad_phase="sap", rigid_contact_max=50000, ) # Option A: explicit buffer contacts = pipeline.contacts() pipeline.collide(state, contacts) # Option B: use model helpers with a custom pipeline contacts = model.contacts(collision_pipeline=pipeline) model.collide(state, contacts) # Option C: let collide allocate the buffer for you contacts = model.collide(state, collision_pipeline=pipeline) .. _Hydroelastic Contacts: Hydroelastic Contacts --------------------- Hydroelastic contacts are an **opt-in** feature that generates contact areas (not just points) using SDF-based collision detection. This provides more realistic and continuous force distribution, particularly useful for robotic manipulation scenarios. **Default behavior (hydroelastic disabled):** When ``is_hydroelastic=False`` (default), shapes use **hard SDF contacts** - point contacts computed from SDF distance queries. This is efficient and suitable for most rigid body simulations. **Opt-in hydroelastic behavior:** When ``is_hydroelastic=True`` on **both** shapes in a pair, the system generates distributed contact areas instead of point contacts. This is useful for: - More stable and continuous contact forces for non-convex shape interactions - Better force distribution across large contact patches - Realistic friction behavior for flat-on-flat contacts **Requirements:** - Both shapes in a pair must have ``is_hydroelastic=True`` - Shapes must have SDF data available: - mesh shapes: call ``mesh.build_sdf(...)`` - primitive shapes: use ``sdf_max_resolution`` or ``sdf_target_voxel_size`` in ``ShapeConfig`` - For non-unit shape scale, the attached SDF must be scale-baked - Only volumetric shapes supported (not planes, heightfields, or non-watertight meshes) .. testcode:: hydroelastic builder = newton.ModelBuilder() body = builder.add_body() cfg = builder.ShapeConfig( is_hydroelastic=True, # Opt-in to hydroelastic contacts sdf_max_resolution=64, # Required for hydroelastic kh=1.0e11, # Contact stiffness ) builder.add_shape_box(body, hx=0.5, hy=0.5, hz=0.5, cfg=cfg) **How it works:** 1. SDF intersection finds overlapping regions between shapes 2. Marching cubes extracts the contact iso-surface 3. Contact points are distributed across the surface area 4. Optional contact reduction selects representative points **Hydroelastic stiffness (kh):** The ``kh`` parameter on each shape controls area-dependent contact stiffness. For a pair, the effective stiffness is computed as the harmonic mean: ``k_eff = 2 * k_a * k_b / (k_a + k_b)``. Tune this for desired penetration behavior. Contact reduction options for hydroelastic contacts are configured via :class:`~geometry.HydroelasticSDF.Config` (see :ref:`Contact Reduction`). Hydroelastic memory can be tuned with ``buffer_fraction`` on :class:`~geometry.HydroelasticSDF.Config`. This scales broadphase, iso-refinement, and hydroelastic face-contact buffer allocations as a fraction of the worst-case size. Lower values reduce memory usage but also reduce overflow headroom. .. testcode:: hydro-buffer from newton.geometry import HydroelasticSDF config = HydroelasticSDF.Config( reduce_contacts=True, buffer_fraction=0.2, # 20% of worst-case (default: 1.0) ) The default ``buffer_fraction`` is ``1.0`` (full worst-case allocation). Lowering it reduces GPU memory usage but may cause overflow in dense contact scenes. If runtime overflow warnings appear, increase ``buffer_fraction`` (or stage-specific ``buffer_mult_*`` values) until warnings disappear in your target scenes. .. _Contact Material Properties: Contact Materials ----------------- Shape material properties control contact resolution. Configure via :class:`~ModelBuilder.ShapeConfig`: .. list-table:: :header-rows: 1 :widths: 10 25 18 9 19 19 * - Property - Description - Solvers - Default - ShapeConfig - Model Array * - ``mu`` - Dynamic friction coefficient - All - 1.0 - :attr:`~ModelBuilder.ShapeConfig.mu` - :attr:`~Model.shape_material_mu` * - ``ke`` - Contact elastic stiffness - SemiImplicit, Featherstone, MuJoCo - 2.5e3 - :attr:`~ModelBuilder.ShapeConfig.ke` - :attr:`~Model.shape_material_ke` * - ``kd`` - Contact damping - SemiImplicit, Featherstone, MuJoCo - 100.0 - :attr:`~ModelBuilder.ShapeConfig.kd` - :attr:`~Model.shape_material_kd` * - ``kf`` - Friction damping coefficient - SemiImplicit, Featherstone - 1000.0 - :attr:`~ModelBuilder.ShapeConfig.kf` - :attr:`~Model.shape_material_kf` * - ``ka`` - Adhesion distance - SemiImplicit, Featherstone - 0.0 - :attr:`~ModelBuilder.ShapeConfig.ka` - :attr:`~Model.shape_material_ka` * - ``restitution`` - Bounciness (requires ``enable_restitution=True`` in solver) - XPBD - 0.0 - :attr:`~ModelBuilder.ShapeConfig.restitution` - :attr:`~Model.shape_material_restitution` * - ``mu_torsional`` - Resistance to spinning at contact - XPBD, MuJoCo - 0.005 - :attr:`~ModelBuilder.ShapeConfig.mu_torsional` - :attr:`~Model.shape_material_mu_torsional` * - ``mu_rolling`` - Resistance to rolling motion - XPBD, MuJoCo - 0.0001 - :attr:`~ModelBuilder.ShapeConfig.mu_rolling` - :attr:`~Model.shape_material_mu_rolling` * - ``kh`` - Hydroelastic stiffness - SemiImplicit, Featherstone, MuJoCo - 1.0e10 - :attr:`~ModelBuilder.ShapeConfig.kh` - :attr:`~Model.shape_material_kh` .. note:: Material properties interact differently with each solver. ``ke``, ``kd``, ``kf``, and ``ka`` are used by force-based solvers (SemiImplicit, Featherstone, MuJoCo), while ``restitution`` only applies to XPBD. See the :doc:`../api/newton_solvers` API reference for solver-specific behavior. Example: .. testcode:: material-config builder = newton.ModelBuilder() cfg = builder.ShapeConfig( mu=0.8, # High friction ke=1.0e6, # Stiff contact kd=1000.0, # Damping restitution=0.5, # Bouncy (XPBD only) ) .. _USD Collision: USD Integration --------------- Custom collision properties can be authored in USD: .. code-block:: usda def Xform "Box" ( prepend apiSchemas = ["PhysicsRigidBodyAPI", "PhysicsCollisionAPI"] ) { custom int newton:collision_group = 1 custom int newton:world = 0 custom float newton:contact_ke = 100000.0 custom float newton:contact_kd = 1000.0 custom float newton:contact_kf = 1000.0 custom float newton:contact_ka = 0.0 custom float newton:margin = 0.00001 } See :doc:`custom_attributes` and :doc:`usd_parsing` for details. .. _Performance: Performance ----------- - Use **EXPLICIT** (default) when collision pairs are limited (<100 shapes with most pairs filtered) - Use **SAP** for >100 shapes with spatial coherence - Use **NxN** for small scenes (<100 shapes) or uniform spatial distribution - Minimize global entities (world=-1) as they interact with all worlds - Use positive collision groups to reduce candidate pairs - Use world indices for parallel simulations (essential for RL with many environments) - Contact reduction is enabled by default for mesh-heavy scenes - Pass ``rigid_contact_max`` to :class:`~CollisionPipeline` to limit memory in complex scenes - Use :meth:`~ModelBuilder.approximate_meshes` to replace detailed visual meshes with convex hulls for collision - Use ``viewer.log_contacts(contacts, state)`` in the render loop to visualize contact points and normals for debugging **Troubleshooting** - **No contacts generated?** Check that both shapes have compatible ``collision_group`` values (group 0 disables collision) and belong to the same world index. - **Mesh-mesh contacts slow?** Attach an SDF with ``mesh.build_sdf(...)`` — without it, Newton falls back to O(N) BVH vertex queries. - **Objects tunneling through each other?** Increase ``gap`` to detect contacts earlier, or increase substep count (decrease simulation ``dt``). - **Hydroelastic buffer overflow warnings?** Increase ``buffer_fraction`` in :class:`~geometry.HydroelasticSDF.Config`. **CUDA graph capture** On CUDA devices, the simulation loop (including ``collide`` and ``solver.step``) can be captured into a CUDA graph with ``wp.ScopedCapture`` for reduced kernel launch overhead. Place ``collide`` inside the captured region so it is replayed each frame: .. code-block:: python if wp.get_device().is_cuda: with wp.ScopedCapture() as capture: model.collide(state_0, contacts) for _ in range(sim_substeps): solver.step(state_0, state_1, control, contacts, dt) state_0, state_1 = state_1, state_0 graph = capture.graph # Each frame: wp.capture_launch(graph) .. _Solver Integration: Solver Integration ------------------ Newton's collision pipeline works with all built-in solvers (:class:`~solvers.SolverXPBD`, :class:`~solvers.SolverVBD`, :class:`~solvers.SolverSemiImplicit`, :class:`~solvers.SolverFeatherstone`, :class:`~solvers.SolverMuJoCo`). Pass the :class:`~Contacts` object to :meth:`~solvers.SolverBase.step`: .. code-block:: python solver.step(state_0, state_1, control, contacts, dt) **MuJoCo solver** (see also :ref:`MuJoCo Warp Integration`) By default (``use_mujoco_contacts=True``), :class:`~solvers.SolverMuJoCo` runs its own contact generation and the ``contacts`` argument to ``step`` should be ``None``. To replace MuJoCo's contact generation with Newton's pipeline — enabling advanced contact models (SDF, hydroelastic) — set ``use_mujoco_contacts=False`` and pass a populated :class:`~Contacts` object to :meth:`~solvers.SolverMuJoCo.step`: .. testsetup:: mujoco-solver import warp as wp import newton builder = newton.ModelBuilder() builder.add_ground_plane() body = builder.add_body(xform=wp.transform((0.0, 0.0, 2.0), wp.quat_identity())) builder.add_shape_sphere(body, radius=0.5) model = builder.finalize() state_0 = model.state() state_1 = model.state() control = model.control() num_steps = 2 .. testcode:: mujoco-solver pipeline = newton.CollisionPipeline(model, broad_phase="sap") solver = newton.solvers.SolverMuJoCo( model, use_mujoco_contacts=False, ) contacts = pipeline.contacts() for step in range(num_steps): pipeline.collide(state_0, contacts) solver.step(state_0, state_1, control, contacts, dt=1.0/60.0) state_0, state_1 = state_1, state_0 .. _Advanced Customization: Advanced Customization ---------------------- :class:`~CollisionPipeline` covers the vast majority of use cases, but Newton also exposes the underlying broad phase, narrow phase, and primitive collision building blocks for users who need full control — for example, writing contacts in a custom format, implementing a domain-specific culling strategy, or integrating Newton's collision detection into an external solver. **Pipeline stages** The standard pipeline runs three stages: 1. **AABB computation** — shape bounding boxes in world space. 2. **Broad phase** — identifies candidate shape pairs whose AABBs overlap. 3. **Narrow phase** — generates contacts for each candidate pair. You can replace or compose these stages independently. **Broad phase classes** All broad phase classes expose a ``launch`` method that writes candidate pairs (``wp.array(dtype=wp.vec2i)``) and a pair count: .. list-table:: :header-rows: 1 :widths: 25 75 * - Class - Description * - :class:`~geometry.BroadPhaseAllPairs` - All-pairs O(N²) AABB test. Accepts ``shape_world`` and optional ``shape_flags``. * - :class:`~geometry.BroadPhaseSAP` - Sweep-and-prune. Same interface, with optional ``sweep_thread_count_multiplier`` and ``sort_type`` tuning parameters. * - :class:`~geometry.BroadPhaseExplicit` - Tests precomputed ``shape_pairs`` against AABBs. No constructor arguments. .. code-block:: python from newton.geometry import BroadPhaseSAP bp = BroadPhaseSAP(model.shape_world, model.shape_flags) bp.launch( shape_lower=shape_aabb_lower, shape_upper=shape_aabb_upper, shape_gap=model.shape_gap, shape_collision_group=model.shape_collision_group, shape_world=model.shape_world, shape_count=model.shape_count, candidate_pair=candidate_pair_buffer, candidate_pair_count=candidate_pair_count, device=device, ) **Narrow phase** :class:`~geometry.NarrowPhase` accepts the candidate pairs from any broad phase and generates contacts: .. code-block:: python from newton.geometry import NarrowPhase narrow_phase = NarrowPhase( max_candidate_pairs=10000, reduce_contacts=True, device=device, ) narrow_phase.launch( candidate_pair=candidate_pairs, candidate_pair_count=pair_count, shape_types=..., shape_data=..., shape_transform=..., # ... remaining geometry arrays from Model contact_pair=out_pairs, contact_position=out_positions, contact_normal=out_normals, contact_penetration=out_depths, contact_count=out_count, device=device, ) To write contacts in a custom format, pass a ``contact_writer_warp_func`` (a Warp ``@wp.func``) to the constructor to define the per-contact write logic, then call ``launch_custom_write`` instead of ``launch``, providing a ``writer_data`` struct that matches your writer function. Together these give full control over how and where contacts are stored. **Primitive collision functions** For per-pair queries outside the pipeline, ``newton.geometry`` exports Warp device functions (``@wp.func``) for specific shape combinations: - ``collide_sphere_sphere``, ``collide_sphere_capsule``, ``collide_sphere_box``, ``collide_sphere_cylinder`` - ``collide_capsule_capsule``, ``collide_capsule_box`` - ``collide_box_box`` - ``collide_plane_sphere``, ``collide_plane_capsule``, ``collide_plane_box``, ``collide_plane_cylinder``, ``collide_plane_ellipsoid`` These return signed distance (negative = penetration), contact position, and contact normal. Multi-contact variants (e.g., ``collide_box_box``) return fixed-size vectors with unused slots set to ``MAXVAL``. Because they are ``@wp.func``, they must be called from within Warp kernels. **GJK, MPR, and multi-contact generators** For convex shapes that lack a dedicated ``collide_*`` function, Newton provides factory functions that create Warp device functions from a support-map interface: - ``create_solve_mpr(support_func)`` — Minkowski Portal Refinement for boolean collision and signed distance. - ``create_solve_closest_distance(support_func)`` — GJK closest-point query. - ``create_solve_convex_multi_contact(support_func, writer_func, post_process_contact)`` — generates a stable multi-contact manifold and writes results through a callback. .. note:: These factory functions are internal building blocks available from ``newton._src.geometry``. They are not part of the public API and may change between releases, but are accessible for advanced users building custom narrow-phase routines. See Also -------- **Imports:** .. testcode:: see-also-imports import newton from newton import ( CollisionPipeline, Contacts, GeoType, ) from newton.geometry import ( BroadPhaseAllPairs, BroadPhaseExplicit, BroadPhaseSAP, HydroelasticSDF, NarrowPhase, ) **API Reference:** - :meth:`~Model.contacts` - Create a contacts buffer (accepts ``collision_pipeline=``) - :meth:`~Model.collide` - Run collision detection (accepts ``collision_pipeline=``, returns :class:`~Contacts`) - :class:`~CollisionPipeline` - Collision pipeline with configurable broad phase - ``broad_phase`` - Broad phase algorithm: ``"nxn"``, ``"sap"``, or ``"explicit"`` - :class:`~Contacts` - Contact data container - :class:`~GeoType` - Shape geometry types - :class:`~ModelBuilder.ShapeConfig` - Shape configuration options - :meth:`~ModelBuilder.ShapeConfig.configure_sdf` - Set SDF and hydroelastic options in one call - :class:`~geometry.HydroelasticSDF.Config` - Hydroelastic contact configuration - :meth:`~CollisionPipeline.contacts` - Allocate a contacts buffer for a custom pipeline - :meth:`~Mesh.build_sdf` - Precompute SDF for a mesh - :meth:`~ModelBuilder.approximate_meshes` - Replace mesh collision shapes with simpler geometry - :meth:`~ModelBuilder.replicate` - Stamp out multi-world copies of a template builder - :class:`~geometry.BroadPhaseAllPairs`, :class:`~geometry.BroadPhaseSAP`, :class:`~geometry.BroadPhaseExplicit` - Broad phase implementations - :class:`~geometry.NarrowPhase` - Narrow phase contact generation **Model attributes:** - :attr:`~Model.shape_collision_group` - Per-shape collision groups - :attr:`~Model.shape_world` - Per-shape world indices - :attr:`~Model.shape_gap` - Per-shape contact gaps (detection threshold) - :attr:`~Model.shape_margin` - Per-shape margin values (signed distance padding) **Related documentation:** - :doc:`../api/newton_solvers` - Solver API reference (material property behavior per solver) - :doc:`custom_attributes` - USD custom attributes for collision properties - :doc:`usd_parsing` - USD import options including collision settings - :doc:`sites` - Non-colliding reference points ================================================ FILE: docs/concepts/conventions.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 Conventions =========== This document covers the various conventions used across physics engines and graphics frameworks when working with Newton and other simulation systems. Primer: Reference Points for Rigid-Body Spatial Force and Velocity ------------------------------------------------------------------ Newton uses rigid-body spatial forces (wrenches) and velocities (twists) in its API. These spatial vectors are defined with respect to a **reference point**. When shifting the reference point, the force and velocity are updated in order to preserve the effect of the wrench, and the velocity field described by the twist, with respect to the new reference point. The 6D wrench and twist are composed of a linear and an angular 3D-vector component, and in the context of these spatial vectors, their reference-point dependence is as follows: - **Point-independent components**: linear force :math:`\mathbf{f}`, angular velocity :math:`\boldsymbol{\omega}`. - **Point-dependent components**: angular torque (moment) :math:`\boldsymbol{\tau}`, linear velocity :math:`\mathbf{v}`. Shifting the reference point by :math:`\mathbf{r} = (\mathbf{p}_{\text{new}} - \mathbf{p}_{\text{old}})` changes the point-dependent vector components as follows: .. math:: \boldsymbol{\tau}_{\text{new}} = \boldsymbol{\tau} + \mathbf{r} \times \mathbf{f}, \qquad \mathbf{v}_{\text{new}} = \mathbf{v} + \boldsymbol{\omega} \times \mathbf{r}. Keep this distinction in mind below: In addition to the coordinate frame that wrenches and twists are expressed in, Newton documentation states the **reference point** that it expects. If you compute e.g. a wrench with respect to a different reference point, you must shift it to the expected reference point. Spatial Twist Conventions -------------------------- Twists in Modern Robotics ~~~~~~~~~~~~~~~~~~~~~~~~~~ In robotics, a **twist** is a 6-dimensional velocity vector combining angular and linear velocity. *Modern Robotics* (Lynch & Park) defines two equivalent representations of a rigid body's twist, depending on the coordinate frame used: * **Body twist** (:math:`V_b`): uses the body's *body frame* (often at the body's center of mass). Here :math:`\omega_b` is the angular velocity expressed in the body frame, and :math:`v_b` is the linear velocity of a point at the body origin (e.g. the COM) expressed in the body frame. Thus :math:`V_b = (\omega_b,\;v_b)` gives the body's own-frame view of its motion. * **Spatial twist** (:math:`V_s`): uses the fixed *space frame* (world/inertial frame). :math:`v_s` represents the linear velocity of a hypothetical point on the moving body that is instantaneously at the world origin, and :math:`\omega_s` is the angular velocity expressed in world coordinates. Equivalently, .. math:: v_s \;=\; \dot p \;-\; \omega_s \times p, where :math:`p` is the vector from the world origin to the body origin. Hence :math:`V_s = (v_s,\;\omega_s)` is called the **spatial twist**. *Note:* :math:`v_s` is **not** simply the COM velocity (that would be :math:`\dot p`); it is the velocity of the *world origin* as if rigidly attached to the body. In summary, *Modern Robotics* lets us express the same physical motion either in the body frame or in the world frame. The angular velocity is identical up to coordinate rotation; the linear component depends on the chosen reference point (world origin vs. body origin). Physics-Engine Conventions (Drake, MuJoCo, Isaac) ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ Most physics engines store the **COM linear velocity** together with the **angular velocity** of the body, typically both in world coordinates. This corresponds conceptually to a twist taken at the COM and expressed in the world frame, though details vary: * **Drake** Drake's multibody library uses full spatial vectors with explicit frame names. The default, :math:`V_{MB}^{E}`, reads "velocity of frame *B* measured in frame *M*, expressed in frame *E*." In normal use :math:`V_{WB}^{W}` (body *B* in world *W*, expressed in *W*) contains :math:`(\omega_{WB}^{W},\;v_{WB_o}^{W})`, i.e. both components in the world frame. This aligns with the usual physics-engine convention. * **MuJoCo** MuJoCo employs a *mixed-frame* format for free bodies: the linear part :math:`(v_x,v_y,v_z)` is the velocity of the **body frame origin** (i.e., where ``qpos[0:3]`` is located) in the world frame, while the angular part :math:`(\omega_x,\omega_y,\omega_z)` is expressed in the **body frame**. The choice follows from quaternion integration (angular velocities "live" in the quaternion's tangent space, a local frame). Note that when the body's center of mass (``body_ipos``) is offset from the body frame origin, the linear velocity is *not* the CoM velocity—see :ref:`MuJoCo conversion ` below for the relationship. * **Isaac Lab / Isaac Gym** NVIDIA's Isaac tools provide **both** linear and angular velocities in the world frame. The root-state tensor returns :math:`(v_x,v_y,v_z,\;\omega_x,\omega_y,\omega_z)` all expressed globally. This matches Bullet/ODE/PhysX practice. .. _Twist conventions: Newton Conventions ~~~~~~~~~~~~~~~~~~ **Newton** follows the standard physics engine convention for most solvers, aligning with Isaac Lab's approach. Newton's public ``spatial_vector`` arrays use ``(linear, angular)`` ordering, unlike Warp's native ``(angular, linear)`` convention. This applies to arrays such as :attr:`newton.State.body_qd` and :attr:`newton.State.body_f`. Newton's :attr:`State.body_qd ` stores **both** linear and angular velocities in the world frame. .. code-block:: python @wp.kernel def get_body_twist(body_qd: wp.array(dtype=wp.spatial_vector)): body_id = wp.tid() # body_qd is a 6D wp.spatial_vector in world frame twist = body_qd[body_id] # linear velocity is the velocity of the body's center of mass in world frame linear_velocity = twist[0:3] # angular velocity is the angular velocity of the body in world frame angular_velocity = twist[3:6] wp.launch(get_body_twist, dim=model.body_count, inputs=[state.body_qd]) The linear velocity represents the COM velocity in world coordinates, while the angular velocity is also expressed in world coordinates. This matches the Isaac Lab convention exactly. Note that Newton will automatically convert from this convention to MuJoCo's mixed-frame format when using the SolverMuJoCo, including both the angular velocity frame conversion (world ↔ body) and the linear velocity reference point conversion (CoM ↔ body frame origin). Summary of Conventions ~~~~~~~~~~~~~~~~~~~~~~ .. list-table:: :header-rows: 1 :widths: 28 27 27 18 * - **System** - **Linear velocity (translation)** - **Angular velocity (rotation)** - **Twist term** * - *Modern Robotics* — **Body twist** - Body origin (chosen point; often COM), body frame - Body frame - "Body twist" (:math:`V_b`) * - *Modern Robotics* — **Spatial twist** - World origin, world frame - World frame - "Spatial twist" (:math:`V_s`) * - **Drake** - Body-frame origin :math:`B_o` (not necessarily COM), world frame - World frame - Spatial velocity :math:`V_{WB}^{W}` * - **MuJoCo** - Body-frame origin, world frame - Body frame - Mixed-frame 6-vector * - **Isaac Gym / Sim** - COM, world frame - World frame - "Root" linear/angular velocity * - **PhysX** - COM, world frame - World frame - Not named "twist"; typically treated as :math:`[\mathbf{v}_{com}^W;\ \boldsymbol{\omega}^W]` * - **Newton** (except the Featherstone solver; see below) - COM, world frame - World frame - :attr:`~newton.State.body_qd` .. warning:: :class:`~newton.solvers.SolverFeatherstone` does not correctly handle angular velocity for free-floating bodies with **non-zero center of mass offsets**. The body may not rotate purely about its CoM. This issue is tracked at https://github.com/newton-physics/newton/issues/1366. Mapping Between Representations ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ **Body ↔ Spatial (Modern Robotics)** For body pose :math:`T_{sb}=(R,p)`: .. math:: \omega_s \;=\; R\,\omega_b, \qquad v_s \;=\; R\,v_b \;+\; \omega_s \times p. This is :math:`V_s = \mathrm{Ad}_{(R,p)}\,V_b`; the inverse uses :math:`R^{\mathsf T}` and :math:`-R^{\mathsf T}p`. **Physics engine → MR** Given engine values :math:`(v_{\text{com}}^{W},\;\omega^{W})` (world-frame COM velocity and angular velocity): 1. Spatial twist at COM :math:`V_{WB}^{W} = (v_{\text{com}}^{W},\;\omega^{W})` 2. Body-frame twist :math:`\omega_b = R^{\mathsf T}\omega^{W}`, :math:`v_b = R^{\mathsf T}v_{\text{com}}^{W}`. 3. Shift to another origin offset :math:`r` from COM: :math:`v_{\text{origin}}^{W} = v_{\text{com}}^{W} + \omega^{W}\times r^{W}`, where :math:`r^{W}=R\,r`. .. _MuJoCo conversion: **MuJoCo conversion** Two conversions are needed between Newton and MuJoCo: 1. **Angular velocity frame**: Rotate MuJoCo's body-frame angular velocity by :math:`R` to obtain the world-frame angular velocity (or vice versa): .. math:: \omega^{W} = R\,\omega^{B}, \qquad \omega^{B} = R^{\mathsf T}\omega^{W} 2. **Linear velocity reference point**: MuJoCo's linear velocity is at the body frame origin, while Newton uses the CoM velocity. When the body has a non-zero CoM offset :math:`r` (``body_ipos`` in MuJoCo, ``body_com`` in Newton), convert using: .. math:: v_{\text{origin}}^{W} = v_{\text{com}}^{W} - \omega^{W} \times r^{W}, \qquad v_{\text{com}}^{W} = v_{\text{origin}}^{W} + \omega^{W} \times r^{W} where :math:`r^{W} = R\,r^{B}` is the CoM offset expressed in world coordinates. In all cases the conversion boils down to the **reference point** (COM vs. another point) and the **frame** (world vs. body) used for each component. Physics is unchanged; any linear velocity at one point follows :math:`v_{\text{new}} = v + \omega\times r`. Spatial Wrench Conventions -------------------------- Newton represents external rigid-body forces as **spatial wrenches** in :attr:`State.body_f `. The 6D wrench is stored in world frame as: .. math:: \mathbf{w} = \begin{bmatrix} \mathbf{f} \\ \boldsymbol{\tau} \end{bmatrix}, where :math:`\mathbf{f}` is the **linear force** and :math:`\boldsymbol{\tau}` is the **moment about the body's center of mass (COM)**, both expressed in world coordinates. The reference point matters for the moment term, so shifting the wrench to a point offset by :math:`\mathbf{r}` changes the torque as: .. math:: \boldsymbol{\tau}_{\text{new}} = \boldsymbol{\tau} + \mathbf{r} \times \mathbf{f}. This convention is used in all Newton solvers, except for :class:`~newton.solvers.SolverFeatherstone`, which does not correctly handle torque application for free-floating bodies with **non-zero center of mass offsets**. .. warning:: :class:`~newton.solvers.SolverFeatherstone` does not correctly handle torque application for free-floating bodies with **non-zero center of mass offsets**. A pure torque will incorrectly cause the CoM to translate instead of remaining stationary. This issue is tracked at https://github.com/newton-physics/newton/issues/1366. The array of joint forces (torques) in generalized coordinates is stored in :attr:`Control.joint_f `. For free joints, the corresponding 6 dimensions in this array are the spatial wrench applied at the body's center of mass (COM) in world frame, following exactly the same convention as :attr:`State.body_f `. .. note:: MuJoCo represents free-joint generalized forces in a mixed-frame convention in ``qfrc_applied``. To preserve Newton's COM-wrench semantics, :class:`~newton.solvers.SolverMuJoCo` applies free-joint :attr:`Control.joint_f ` through ``xfrc_applied`` (world-frame wrench at the COM) and uses ``qfrc_applied`` only for non-free joints. This keeps free-joint ``joint_f`` behavior aligned with :attr:`State.body_f `. We avoid converting free-joint wrenches into ``qfrc_applied`` directly because ``qfrc_applied`` is **generalized-force space**, not a physical wrench. For free joints the 6-DOF basis depends on the current ``cdof`` (subtree COM frame), and the rotational components are expressed in the body frame. A naive world-to-body rotation is insufficient because the correct mapping is the Jacobian-transpose operation used internally by MuJoCo (the same path as ``xfrc_applied``). Routing through ``xfrc_applied`` ensures the wrench is interpreted at the COM in world coordinates and then mapped to generalized forces consistently with MuJoCo's own dynamics. Quaternion Ordering Conventions -------------------------------- Different physics engines and graphics frameworks use different conventions for storing quaternion components. This can cause significant confusion when transferring data between systems or when interfacing with external libraries. The quaternion :math:`q = w + xi + yj + zk` where :math:`w` is the scalar (real) part and :math:`(x, y, z)` is the vector (imaginary) part, can be stored in memory using different orderings: .. list-table:: Quaternion Component Ordering :header-rows: 1 :widths: 30 35 35 * - **System** - **Storage Order** - **Description** * - **Newton / Warp** - ``(x, y, z, w)`` - Vector part first, scalar last * - **Isaac Lab / Isaac Sim** - ``(w, x, y, z)`` - Scalar first, vector part last * - **MuJoCo** - ``(w, x, y, z)`` - Scalar first, vector part last * - **USD (Universal Scene Description)** - ``(x, y, z, w)`` - Vector part first, scalar last **Important Notes:** * **Mathematical notation** typically writes quaternions as :math:`q = w + xi + yj + zk` or :math:`q = (w, x, y, z)`, but this doesn't dictate storage order. * **Conversion between systems** requires careful attention to component ordering. For example, converting from Isaac Lab to Newton requires reordering: ``newton_quat = (isaac_quat[1], isaac_quat[2], isaac_quat[3], isaac_quat[0])`` * **Rotation semantics** remain the same regardless of storage order—only the memory layout differs. * **Warp's quat type** uses ``(x, y, z, w)`` ordering, accessible via: ``quat[0]`` (x), ``quat[1]`` (y), ``quat[2]`` (z), ``quat[3]`` (w). When working with multiple systems, always verify quaternion ordering in your data pipeline to avoid unexpected rotations or orientations. Coordinate System and Up Axis Conventions ------------------------------------------ Different physics engines, graphics frameworks, and content creation tools use different conventions for coordinate systems and up axis orientation. This can cause significant confusion when transferring assets between systems or when setting up physics simulations from existing content. The **up axis** determines which coordinate axis points "upward" in the world, affecting gravity direction, object placement, and overall scene orientation. .. list-table:: Coordinate System and Up Axis Conventions :header-rows: 1 :widths: 30 20 25 25 * - **System** - **Up Axis** - **Handedness** - **Notes** * - **Newton** - ``Z`` (default) - Right-handed - Configurable via ``Axis.X/Y/Z`` * - **MuJoCo** - ``Z`` (default) - Right-handed - Standard robotics convention * - **USD** - ``Y`` (default) - Right-handed - Configurable as ``Y`` or ``Z`` * - **Isaac Lab / Isaac Sim** - ``Z`` (default) - Right-handed - Follows robotics conventions **Important Design Principle:** Newton itself is **coordinate system agnostic** and can work with any choice of up axis. The physics calculations and algorithms do not depend on a specific coordinate system orientation. However, it becomes essential to track the conventions used by various assets and data sources to enable proper conversion and integration at runtime. **Common Integration Scenarios:** * **USD to Newton**: Convert from USD's Y-up (or Z-up) to Newton's configured up axis * **MuJoCo to Newton**: Convert from MuJoCo's Z-up to Newton's configured up axis * **Mixed asset pipelines**: Track up axis per asset and apply appropriate transforms **Conversion Between Systems:** When converting assets between coordinate systems with different up axes, apply the appropriate rotation transforms: * **Y-up ↔ Z-up**: 90° rotation around the X-axis * **Maintain right-handedness**: Ensure coordinate system handedness is preserved **Example Configuration:** .. code-block:: python import newton # Configure Newton for Z-up coordinate system (robotics convention) builder = newton.ModelBuilder(up_axis=newton.Axis.Z, gravity=-9.81) # Or use Y-up (graphics/animation convention) builder = newton.ModelBuilder(up_axis=newton.Axis.Y, gravity=-9.81) # Gravity vector will automatically align with the chosen up axis: # - Y-up: gravity = (0, -9.81, 0) # - Z-up: gravity = (0, 0, -9.81) Collision Primitive Conventions ------------------------------- This section documents the conventions used for collision primitive shapes in Newton and compares them with other physics engines and formats. Understanding these conventions is essential when: * Creating collision geometry programmatically with ModelBuilder * Debugging unexpected collision behavior after asset import * Understanding center of mass calculations for asymmetric shapes Newton Collision Primitives ~~~~~~~~~~~~~~~~~~~~~~~~~~~ Newton defines collision primitives with consistent conventions across all shape types. The following table summarizes the key parameters and properties for each primitive: .. list-table:: Newton Collision Primitive Specifications :header-rows: 1 :widths: 15 20 35 30 * - **Shape** - **Origin** - **Parameters** - **Notes** * - **Box** - Geometric center - ``hx``, ``hy``, ``hz`` (half-extents) - Edges aligned with local axes * - **Sphere** - Center - ``radius`` - Uniform in all directions * - **Capsule** - Geometric center - ``radius``, ``half_height`` - Extends along Z-axis; half_height excludes hemispherical caps * - **Cylinder** - Geometric center - ``radius``, ``half_height`` - Extends along Z-axis * - **Cone** - Geometric center - ``radius`` (base), ``half_height`` - Extends along Z-axis; base at -half_height, apex at +half_height * - **Plane** - Shape frame origin - ``width``, ``length`` (or 0,0 for infinite) - Normal along +Z of shape frame * - **Mesh** - User-defined - Vertex and triangle arrays - General triangle mesh (can be non-convex) **Shape Orientation and Alignment** All Newton primitives that have a primary axis (capsule, cylinder, cone) are aligned along the Z-axis in their local coordinate frame. The shape's transform determines its final position and orientation in the world or parent body frame. **Center of Mass Considerations** For most primitives, the center of mass coincides with the geometric origin. The cone is a notable exception: * **Cone COM**: Located at ``(0, 0, -half_height/2)`` in the shape's local frame, which is 1/4 of the total height from the base toward the apex. Collision Primitive Conventions Across Engines ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ The following tables compare how different engines and formats define common collision primitives: **Sphere Primitives** .. list-table:: :header-rows: 1 :widths: 25 35 40 * - **System** - **Parameter Convention** - **Notes** * - **Newton** - ``radius`` - Origin at center * - **MuJoCo** - ``size[0]`` = radius - Origin at center * - **USD (UsdGeomSphere)** - ``radius`` attribute - Origin at center * - **USD Physics** - ``radius`` attribute - Origin at center **Box Primitives** .. list-table:: :header-rows: 1 :widths: 25 35 40 * - **System** - **Parameter Convention** - **Notes** * - **Newton** - Half-extents (``hx``, ``hy``, ``hz``) - Distance from center to face * - **MuJoCo** - Half-sizes in ``size`` attribute - Can use ``fromto`` (Newton importer doesn't support) * - **USD (UsdGeomCube)** - ``size`` attribute (full dimensions) - Edge length, not half-extent * - **USD Physics** - ``halfExtents`` attribute - Matches Newton convention **Capsule Primitives** .. list-table:: :header-rows: 1 :widths: 25 35 40 * - **System** - **Parameter Convention** - **Notes** * - **Newton** - ``radius``, ``half_height`` (excludes caps) - Total length = 2*(radius + half_height) * - **MuJoCo** - ``size[0]`` = radius, ``size[1]`` = half-length (excludes caps) - Can also use ``fromto`` for endpoints * - **USD (UsdGeomCapsule)** - ``radius``, ``height`` (excludes caps) - Full height of cylindrical portion * - **USD Physics** - ``radius``, ``halfHeight`` (excludes caps) - Similar to Newton **Cylinder Primitives** .. list-table:: :header-rows: 1 :widths: 25 35 40 * - **System** - **Parameter Convention** - **Notes** * - **Newton** - ``radius``, ``half_height`` - Extends along Z-axis * - **MuJoCo** - ``size[0]`` = radius, ``size[1]`` = half-length - Can use ``fromto``; Newton's MJCF importer maps to capsule * - **USD (UsdGeomCylinder)** - ``radius``, ``height`` (full height) - Visual shape * - **USD Physics** - ``radius``, ``halfHeight`` - Newton's USD importer creates actual cylinders **Cone Primitives** .. list-table:: :header-rows: 1 :widths: 25 35 40 * - **System** - **Parameter Convention** - **Notes** * - **Newton** - ``radius`` (base), ``half_height`` - COM offset at -half_height/2 * - **MuJoCo** - Not supported - N/A * - **USD (UsdGeomCone)** - ``radius``, ``height`` (full height) - Visual representation * - **USD Physics** - ``radius``, ``halfHeight`` - Physics representation **Plane Primitives** .. list-table:: :header-rows: 1 :widths: 25 35 40 * - **System** - **Definition Method** - **Normal Direction** * - **Newton** - Transform-based or plane equation - +Z of shape frame * - **MuJoCo** - Size and orientation in body frame - +Z of geom frame * - **USD** - No standard plane primitive - Implementation-specific **Mesh Primitives** .. list-table:: :header-rows: 1 :widths: 25 35 40 * - **System** - **Mesh Type** - **Notes** * - **Newton** - General triangle mesh - Can be non-convex * - **MuJoCo** - Convex hull only for collision - Visual mesh can be non-convex * - **USD (UsdGeomMesh)** - General polygon mesh - Visual representation * - **USD Physics** - Implementation-dependent - May use convex approximation Import Handling ~~~~~~~~~~~~~~~ Newton's importers automatically handle convention differences when loading assets. No manual conversion is required when using these importers—they automatically transform shapes to Newton's conventions. ================================================ FILE: docs/concepts/custom_attributes.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 .. currentmodule:: newton .. _custom_attributes: Custom Attributes ================= Newton's simulation model uses flat buffer arrays to represent physical properties and simulation state. These arrays can be extended with user-defined custom attributes to store application-specific data alongside the standard physics quantities. Use Cases --------- Custom attributes enable a wide range of simulation extensions: * **Per-body properties**: Store thermal properties, material composition, sensor IDs, or hardware specifications * **Advanced control**: Store PD gains, velocity limits, control modes, or actuator parameters per-joint or per-DOF * **Visualization**: Attach colors, labels, rendering properties, or UI metadata to simulation entities * **Multi-physics coupling**: Store quantities like surface stress, temperature fields, or electromagnetic properties * **Reinforcement learning**: Store observation buffers, reward weights, optimization parameters, or policy-specific data directly on entities * **Solver-specific data**: Store contact pair parameters, tendon properties, or other solver-specific entity types Custom attributes follow Newton's flat array indexing scheme, enabling efficient GPU-parallel access while maintaining flexibility for domain-specific extensions. Overview -------- Newton organizes simulation data into four primary objects, each containing flat arrays indexed by simulation entities: * **Model Object** (:class:`~newton.Model`) - Static configuration and physical properties that remain constant during simulation * **State Object** (:class:`~newton.State`) - Dynamic quantities that evolve during simulation * **Control Object** (:class:`~newton.Control`) - Control inputs and actuator commands * **Contact Object** (:class:`~newton.Contacts`) - Contact-specific properties Custom attributes extend these objects with user-defined arrays that follow the same indexing scheme as Newton's built-in attributes. The ``CONTACT`` assignment attaches attributes to the :class:`~newton.Contacts` object created during collision detection. Declaring Custom Attributes ---------------------------- Custom attributes must be declared before use via the :meth:`newton.ModelBuilder.add_custom_attribute` method. Each declaration specifies: * **name**: Attribute name * **frequency**: Determines array size and indexing—either a :class:`~newton.Model.AttributeFrequency` enum value (e.g., ``BODY``, ``SHAPE``, ``JOINT``, ``JOINT_DOF``, ``JOINT_COORD``, ``ARTICULATION``, ``ONCE``) or a string for custom frequencies * **dtype**: Warp data type (``wp.float32``, ``wp.vec3``, ``wp.quat``, etc.) or ``str`` for string attributes stored as Python lists * **assignment**: Which simulation object owns the attribute (``MODEL``, ``STATE``, ``CONTROL``, ``CONTACT``) * **default** (optional): Default value for unspecified entities. When omitted, a sensible zero-value is derived from the dtype (``0`` for scalars, identity for quaternions, ``False`` for booleans, ``""`` for strings) * **namespace** (optional): Hierarchical organization for grouping related attributes * **references** (optional): For multi-world merging, specifies how values are transformed (e.g., ``"body"``, ``"shape"``, ``"world"``, or a custom frequency key) * **values** (optional): Pre-populated values — ``dict[int, Any]`` for enum frequencies or ``list[Any]`` for custom string frequencies When **no namespace** is specified, attributes are added directly to their assignment object (e.g., ``model.temperature``). When a **namespace** is provided, Newton creates a namespace container (e.g., ``model.mujoco.damping``). .. testcode:: from newton import Model, ModelBuilder import warp as wp builder = ModelBuilder() # Default namespace attributes - added directly to assignment objects builder.add_custom_attribute( ModelBuilder.CustomAttribute( name="temperature", frequency=Model.AttributeFrequency.BODY, dtype=wp.float32, default=20.0, # Explicit default value assignment=Model.AttributeAssignment.MODEL ) ) # → Accessible as: model.temperature builder.add_custom_attribute( ModelBuilder.CustomAttribute( name="velocity_limit", frequency=Model.AttributeFrequency.BODY, dtype=wp.vec3, default=(1.0, 1.0, 1.0), # Default vector value assignment=Model.AttributeAssignment.STATE ) ) # → Accessible as: state.velocity_limit # Namespaced attributes - organized under namespace containers builder.add_custom_attribute( ModelBuilder.CustomAttribute( name="float_attr", frequency=Model.AttributeFrequency.BODY, dtype=wp.float32, default=0.5, assignment=Model.AttributeAssignment.MODEL, namespace="namespace_a" ) ) # → Accessible as: model.namespace_a.float_attr builder.add_custom_attribute( ModelBuilder.CustomAttribute( name="bool_attr", frequency=Model.AttributeFrequency.SHAPE, dtype=wp.bool, default=False, assignment=Model.AttributeAssignment.MODEL, namespace="namespace_a" ) ) # → Accessible as: model.namespace_a.bool_attr # Articulation frequency attributes - one value per articulation builder.add_custom_attribute( ModelBuilder.CustomAttribute( name="articulation_stiffness", frequency=Model.AttributeFrequency.ARTICULATION, dtype=wp.float32, default=100.0, assignment=Model.AttributeAssignment.MODEL ) ) # → Accessible as: model.articulation_stiffness # ONCE frequency attributes - a single global value builder.add_custom_attribute( ModelBuilder.CustomAttribute( name="gravity_scale", frequency=Model.AttributeFrequency.ONCE, dtype=wp.float32, default=1.0, assignment=Model.AttributeAssignment.MODEL ) ) # → Accessible as: model.gravity_scale (array of length 1) # String dtype attributes - stored as Python lists, not Warp arrays builder.add_custom_attribute( ModelBuilder.CustomAttribute( name="body_description", frequency=Model.AttributeFrequency.BODY, dtype=str, default="unnamed", assignment=Model.AttributeAssignment.MODEL ) ) # → Accessible as: model.body_description (Python list[str]) **Default Value Behavior:** When entities don't explicitly specify custom attribute values, the default value is used: .. testcode:: # First body uses the default value (20.0) body1 = builder.add_body(mass=1.0) # Second body overrides with explicit value body2 = builder.add_body( mass=1.0, custom_attributes={"temperature": 37.5} ) # Articulation attributes: create articulations with custom values # Each add_articulation creates one articulation at the next index for i in range(3): base = builder.add_link(mass=1.0) joint = builder.add_joint_free(child=base) builder.add_articulation( joints=[joint], custom_attributes={ "articulation_stiffness": 100.0 + float(i) * 50.0 # 100, 150, 200 } ) # After finalization, access attributes model = builder.finalize() temps = model.temperature.numpy() arctic_stiff = model.articulation_stiffness.numpy() print(f"Body 1: {temps[body1]}") # 20.0 (default) print(f"Body 2: {temps[body2]}") # 37.5 (authored) # Articulation indices reflect all articulations in the model # (including any implicit ones from add_body) print(f"Articulations: {len(arctic_stiff)}") print(f"Last articulation stiffness: {arctic_stiff[-1]}") # 200.0 .. testoutput:: Body 1: 20.0 Body 2: 37.5 Articulations: 5 Last articulation stiffness: 200.0 .. note:: Uniqueness is determined by the full identifier (namespace + name): - ``model.float_attr`` (key: ``"float_attr"``) and ``model.namespace_a.float_attr`` (key: ``"namespace_a:float_attr"``) can coexist - ``model.float_attr`` (key: ``"float_attr"``) and ``state.namespace_a.float_attr`` (key: ``"namespace_a:float_attr"``) can coexist - ``model.float_attr`` (key: ``"float_attr"``) and ``state.float_attr`` (key: ``"float_attr"``) cannot coexist - same key - ``model.namespace_a.float_attr`` and ``state.namespace_a.float_attr`` cannot coexist - same key ``"namespace_a:float_attr"`` **Registering Solver Attributes:** Before loading assets, register solver-specific attributes: .. testcode:: custom-attrs-solver from newton import ModelBuilder from newton.solvers import SolverMuJoCo builder_mujoco = ModelBuilder() SolverMuJoCo.register_custom_attributes(builder_mujoco) # Now build your scene... body = builder_mujoco.add_link() joint = builder_mujoco.add_joint_free(body) builder_mujoco.add_articulation([joint]) shape = builder_mujoco.add_shape_box(body=body, hx=0.1, hy=0.1, hz=0.1) model_mujoco = builder_mujoco.finalize() assert hasattr(model_mujoco, "mujoco") assert hasattr(model_mujoco.mujoco, "condim") MuJoCo boolean custom attributes use a ``parse_bool`` transformer (registered by :meth:`~newton.solvers.SolverMuJoCo.register_custom_attributes`) that handles strings (``"true"``/``"false"``), integers, and native booleans. Authoring Custom Attributes ---------------------------- After declaration, values are assigned through the standard entity creation API (``add_body``, ``add_shape``, ``add_joint``). For default namespace attributes, use the attribute name directly. For namespaced attributes, use the format ``"namespace:attr_name"``. .. testcode:: # Create a body with both default and namespaced attributes body_id = builder.add_body( mass=1.0, custom_attributes={ "temperature": 37.5, # default → model.temperature "velocity_limit": [2.0, 2.0, 2.0], # default → state.velocity_limit "namespace_a:float_attr": 0.5, # namespaced → model.namespace_a.float_attr } ) # Create a shape with a namespaced attribute shape_id = builder.add_shape_box( body=body_id, hx=0.1, hy=0.1, hz=0.1, custom_attributes={ "namespace_a:bool_attr": True, # → model.namespace_a.bool_attr } ) **Joint Frequency Types:** For joints, Newton provides three frequency types to store different granularities of data: * **JOINT frequency** → One value per joint * **JOINT_DOF frequency** → Values per degree of freedom (list, dict, or scalar for single-DOF joints) * **JOINT_COORD frequency** → Values per position coordinate (list, dict, or scalar for single-coordinate joints) For ``JOINT_DOF`` and ``JOINT_COORD`` frequencies, values can be provided in three formats: 1. **List format**: Explicit values for all DOFs/coordinates (e.g., ``[100.0, 200.0]`` for 2-DOF joint) 2. **Dict format**: Sparse specification mapping indices to values (e.g., ``{0: 100.0, 2: 300.0}`` sets only DOF 0 and 2) 3. **Scalar format**: Single value for single-DOF/single-coordinate joints, automatically expanded to a list .. testcode:: # Declare joint attributes with different frequencies builder.add_custom_attribute( ModelBuilder.CustomAttribute( name="int_attr", frequency=Model.AttributeFrequency.JOINT, dtype=wp.int32 ) ) builder.add_custom_attribute( ModelBuilder.CustomAttribute( name="float_attr_dof", frequency=Model.AttributeFrequency.JOINT_DOF, dtype=wp.float32 ) ) builder.add_custom_attribute( ModelBuilder.CustomAttribute( name="float_attr_coord", frequency=Model.AttributeFrequency.JOINT_COORD, dtype=wp.float32 ) ) # Create a D6 joint with 2 DOFs (1 linear + 1 angular) and 2 coordinates parent = builder.add_link(mass=1.0) child = builder.add_link(mass=1.0) cfg = ModelBuilder.JointDofConfig joint_id = builder.add_joint_d6( parent=parent, child=child, linear_axes=[cfg(axis=[1, 0, 0])], # 1 linear DOF angular_axes=[cfg(axis=[0, 0, 1])], # 1 angular DOF custom_attributes={ "int_attr": 5, # JOINT frequency: single value "float_attr_dof": [100.0, 200.0], # JOINT_DOF frequency: list with 2 values (one per DOF) "float_attr_coord": [0.5, 0.7], # JOINT_COORD frequency: list with 2 values (one per coordinate) } ) builder.add_articulation([joint_id]) # Scalar format for single-DOF joints (automatically expanded to list) parent2 = builder.add_link(mass=1.0) child2 = builder.add_link(mass=1.0) revolute_joint = builder.add_joint_revolute( parent=parent2, child=child2, axis=[0, 0, 1], custom_attributes={ "float_attr_dof": 150.0, # Scalar for 1-DOF joint (expanded to [150.0]) "float_attr_coord": 0.8, # Scalar for 1-coord joint (expanded to [0.8]) } ) builder.add_articulation([revolute_joint]) # Dict format for sparse specification (only set specific DOF/coord indices) parent3 = builder.add_link(mass=1.0) child3 = builder.add_link(mass=1.0) d6_joint = builder.add_joint_d6( parent=parent3, child=child3, linear_axes=[cfg(axis=[1, 0, 0]), cfg(axis=[0, 1, 0])], # 2 linear DOFs angular_axes=[cfg(axis=[0, 0, 1])], # 1 angular DOF custom_attributes={ "float_attr_dof": {0: 100.0, 2: 300.0}, # Dict: only DOF 0 and 2 specified } ) builder.add_articulation([d6_joint]) Accessing Custom Attributes ---------------------------- After finalization, custom attributes become accessible as Warp arrays. Default namespace attributes are accessed directly on their assignment object, while namespaced attributes are accessed through their namespace container. .. testcode:: # Finalize the model model = builder.finalize() state = model.state() # Access default namespace attributes (direct access on assignment objects) temperatures = model.temperature.numpy() velocity_limits = state.velocity_limit.numpy() print(f"Temperature: {temperatures[body_id]}") print(f"Velocity limit: {velocity_limits[body_id]}") # Access namespaced attributes (via namespace containers) namespace_a_body_floats = model.namespace_a.float_attr.numpy() namespace_a_shape_bools = model.namespace_a.bool_attr.numpy() print(f"Namespace A body float: {namespace_a_body_floats[body_id]}") print(f"Namespace A shape bool: {bool(namespace_a_shape_bools[shape_id])}") .. testoutput:: Temperature: 37.5 Velocity limit: [2. 2. 2.] Namespace A body float: 0.5 Namespace A shape bool: True Custom attributes follow the same GPU/CPU synchronization rules as built-in attributes and can be modified during simulation. USD Integration --------------- Custom attributes can be authored in USD files using a declaration-first pattern, similar to the Python API. Declarations are placed on the PhysicsScene prim, and individual prims can then assign values to these attributes. **Declaration Format (on PhysicsScene prim):** .. code-block:: usda def PhysicsScene "physicsScene" { # Default namespace attributes custom float newton:float_attr = 0.0 ( customData = { string assignment = "model" string frequency = "body" } ) custom float3 newton:vec3_attr = (0.0, 0.0, 0.0) ( customData = { string assignment = "state" string frequency = "body" } ) # ARTICULATION frequency attribute custom float newton:articulation_stiffness = 100.0 ( customData = { string assignment = "model" string frequency = "articulation" } ) # Custom namespace attributes custom float newton:namespace_a:some_attrib = 150.0 ( customData = { string assignment = "control" string frequency = "joint_dof" } ) custom bool newton:namespace_a:bool_attr = false ( customData = { string assignment = "model" string frequency = "shape" } ) } **Assignment Format (on individual prims):** .. code-block:: usda def Xform "robot_arm" ( prepend apiSchemas = ["PhysicsRigidBodyAPI"] ) { # Override declared attributes with custom values custom float newton:float_attr = 850.0 custom float3 newton:vec3_attr = (1.0, 0.5, 0.3) custom float newton:namespace_a:some_attrib = 250.0 } def Mesh "gripper" ( prepend apiSchemas = ["PhysicsRigidBodyAPI", "PhysicsCollisionAPI"] ) { custom bool newton:namespace_a:bool_attr = true } After importing the USD file, attributes are accessible following the same patterns as programmatically declared attributes: .. testcode:: :skipif: True from newton import ModelBuilder builder_usd = ModelBuilder() builder_usd.add_usd("robot_arm.usda") model = builder_usd.finalize() state = model.state() control = model.control() # Access default namespace attributes float_values = model.float_attr.numpy() vec3_values = state.vec3_attr.numpy() # Access namespaced attributes namespace_a_floats = control.namespace_a.some_attrib.numpy() namespace_a_bools = model.namespace_a.bool_attr.numpy() For more information about USD integration and the schema resolver system, see :doc:`usd_parsing`. MJCF and URDF Integration -------------------------- Custom attributes can also be parsed from MJCF and URDF files. Each :class:`~newton.ModelBuilder.CustomAttribute` has optional fields for controlling how values are extracted from these formats: * :attr:`~newton.ModelBuilder.CustomAttribute.mjcf_attribute_name` — name of the XML attribute to read (defaults to the attribute ``name``) * :attr:`~newton.ModelBuilder.CustomAttribute.mjcf_value_transformer` — callable that converts the XML string value to the target dtype * :attr:`~newton.ModelBuilder.CustomAttribute.urdf_attribute_name` — name of the XML attribute to read (defaults to the attribute ``name``) * :attr:`~newton.ModelBuilder.CustomAttribute.urdf_value_transformer` — callable that converts the XML string value to the target dtype These are primarily used by solver integrations (e.g., :meth:`~newton.solvers.SolverMuJoCo.register_custom_attributes` registers MJCF transformers for MuJoCo-specific attributes like ``condim``, ``priority``, and ``solref``). When no transformer is provided, values are parsed using a generic string-to-Warp converter. .. code-block:: python # Example: register an attribute that reads "damping" from MJCF joint elements builder.add_custom_attribute( ModelBuilder.CustomAttribute( name="custom_damping", frequency=Model.AttributeFrequency.JOINT_DOF, dtype=wp.float32, default=0.0, namespace="myns", mjcf_attribute_name="damping", # reads ) ) Validation and Constraints --------------------------- The custom attribute system enforces several constraints to ensure correctness: * Attributes must be declared via ``add_custom_attribute()`` before use (raises ``AttributeError`` otherwise) * Each attribute must be used with entities matching its declared frequency (raises ``ValueError`` otherwise) * Each full attribute identifier (namespace + name) can only be declared once with a specific assignment, frequency, and dtype * The same attribute name can exist in different namespaces because they create different full identifiers Custom Frequencies ================== While enum frequencies (``BODY``, ``SHAPE``, ``JOINT``, etc.) cover most use cases, some data structures have counts independent of built-in entity types. Custom frequencies address this by allowing a string instead of an enum for the :attr:`~newton.ModelBuilder.CustomAttribute.frequency` parameter. **Example use case:** MuJoCo's ```` elements define contact pairs between geometries. These pairs have their own count independent of bodies or shapes, and their indices must be remapped when merging worlds. Registering Custom Frequencies ------------------------------ Custom frequencies must be **registered before use** via :meth:`~newton.ModelBuilder.add_custom_frequency` using a :class:`~newton.ModelBuilder.CustomFrequency` object. This explicit registration ensures clarity about which entity types exist and enables optional USD parsing support. .. testsetup:: custom-freqs from newton import Model, ModelBuilder builder = ModelBuilder() .. testcode:: custom-freqs # Register a custom frequency builder.add_custom_frequency( ModelBuilder.CustomFrequency( name="item", namespace="myns", ) ) The frequency key follows the same namespace rules as attribute keys: if a namespace is provided, it is prepended to the name (e.g., ``"mujoco:pair"``). When declaring a custom attribute, the :attr:`~newton.ModelBuilder.CustomAttribute.frequency` string must match this full key. Declaring Custom Frequency Attributes ------------------------------------- Once a custom frequency is registered, pass a string instead of an enum for the :attr:`~newton.ModelBuilder.CustomAttribute.frequency` parameter when adding attributes: .. testcode:: custom-freqs # First register the custom frequency builder.add_custom_frequency( ModelBuilder.CustomFrequency(name="pair", namespace="mujoco") ) # Then add attributes using that frequency builder.add_custom_attribute( ModelBuilder.CustomAttribute( name="pair_geom1", frequency="mujoco:pair", # Custom frequency (string) dtype=wp.int32, namespace="mujoco", ) ) .. note:: Attempting to add an attribute with an unregistered custom frequency will raise a ``ValueError``. Adding Values ------------- Custom frequency values are appended using :meth:`~newton.ModelBuilder.add_custom_values`: .. testcode:: custom-freqs # Declare attributes sharing the "myns:item" frequency builder.add_custom_attribute( ModelBuilder.CustomAttribute(name="item_id", frequency="myns:item", dtype=wp.int32, namespace="myns") ) builder.add_custom_attribute( ModelBuilder.CustomAttribute(name="item_value", frequency="myns:item", dtype=wp.float32, namespace="myns") ) # Append values together builder.add_custom_values(**{ "myns:item_id": 100, "myns:item_value": 2.5, }) builder.add_custom_values(**{ "myns:item_id": 101, "myns:item_value": 3.0, }) # Finalize (requires at least one articulation) _body = builder.add_link() _joint = builder.add_joint_free(_body) builder.add_articulation([_joint]) model = builder.finalize() print(model.myns.item_id.numpy()) print(model.myns.item_value.numpy()) .. testoutput:: custom-freqs [100 101] [2.5 3. ] For convenience, :meth:`~newton.ModelBuilder.add_custom_values_batch` appends multiple rows in a single call: .. code-block:: python builder.add_custom_values_batch([ {"myns:item_id": 100, "myns:item_value": 2.5}, {"myns:item_id": 101, "myns:item_value": 3.0}, ]) **Validation:** All attributes sharing a custom frequency must have the same count at ``finalize()`` time. This catches synchronization bugs early. USD Parsing Support ------------------- Custom frequencies can support automatic USD parsing: In this section, a *row* means one appended set of values for a custom frequency (that is, one index entry across all attributes in that frequency, equivalent to one call to :meth:`~newton.ModelBuilder.add_custom_values`). * :attr:`~newton.ModelBuilder.CustomFrequency.usd_prim_filter` selects which prims should emit rows. * :attr:`~newton.ModelBuilder.CustomFrequency.usd_entry_expander` (optional) expands one prim into multiple rows. .. code-block:: python def is_actuator_prim(prim, context): """Return True for prims with type name ``MjcActuator``.""" return prim.GetTypeName() == "MjcActuator" builder.add_custom_frequency( ModelBuilder.CustomFrequency( name="actuator", namespace="mujoco", usd_prim_filter=is_actuator_prim, ) ) For one-to-many mappings (one prim -> many rows): .. code-block:: python def is_tendon_prim(prim, context): return prim.GetTypeName() == "MjcTendon" def expand_joint_rows(prim, context): return [ {"mujoco:tendon_joint": 4, "mujoco:tendon_coef": 0.5}, {"mujoco:tendon_joint": 8, "mujoco:tendon_coef": 0.5}, ] builder.add_custom_frequency( ModelBuilder.CustomFrequency( name="tendon_joint", namespace="mujoco", usd_prim_filter=is_tendon_prim, usd_entry_expander=expand_joint_rows, ) ) When :meth:`~newton.ModelBuilder.add_usd` runs: 1. Parses standard entities (bodies, shapes, joints, etc.). 2. Collects custom frequencies that define :attr:`~newton.ModelBuilder.CustomFrequency.usd_prim_filter`. 3. Traverses prims once (including instance proxies via ``Usd.TraverseInstanceProxies()``). 4. For each prim, evaluate matching frequencies in registration order: - If :attr:`~newton.ModelBuilder.CustomFrequency.usd_entry_expander` is set, one row is appended per emitted dictionary, and default per-attribute USD extraction for that frequency is skipped for that prim. - Otherwise, one row is appended from the frequency's declared attributes. Callback inputs: * ``usd_prim_filter(prim, context)`` and ``usd_entry_expander(prim, context)`` receive the same context shape. * ``context`` is a small dictionary: - ``prim``: current USD prim (same object as the ``prim`` argument) - ``builder``: current :class:`~newton.ModelBuilder` instance - ``result``: dictionary returned by :meth:`~newton.ModelBuilder.add_usd` .. note:: Important behavior: - Frequency callbacks are evaluated in deterministic registration order for each visited prim. - If a frequency defines :attr:`~newton.ModelBuilder.CustomFrequency.usd_entry_expander`, then for every matched prim in that frequency, the expander output is the only source of row values. - In that expander code path, the normal :class:`~newton.ModelBuilder.CustomAttribute` USD parsing path is skipped for that frequency/prim. In other words, :attr:`~newton.ModelBuilder.CustomAttribute.usd_attribute_name` and :attr:`~newton.ModelBuilder.CustomAttribute.usd_value_transformer` are not evaluated for those rows. - Example: if frequency ``"mujoco:tendon_joint"`` has an expander and attribute ``CustomAttribute(name="tendon_coef", frequency="mujoco:tendon_joint", ...)``, then ``tendon_coef`` is populated only from keys returned by the expander rows. If a row omits ``"mujoco:tendon_coef"``, the value is treated as ``None`` and the attribute default is applied at finalize time. This mechanism lets solvers such as MuJoCo define USD-native schemas and parse them automatically during model import. Deriving Values from Prim Data (Wildcard Attribute) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ By default, each custom attribute reads its value from a specific USD attribute on the prim (e.g., ``newton:myns:my_attr``). Sometimes, however, you want to **compute** an attribute value from arbitrary prim data rather than reading a single named attribute. This is what setting :attr:`~newton.ModelBuilder.CustomAttribute.usd_attribute_name` to ``"*"`` is for. When :attr:`~newton.ModelBuilder.CustomAttribute.usd_attribute_name` is set to ``"*"``, the attribute's :attr:`~newton.ModelBuilder.CustomAttribute.usd_value_transformer` is called for **every prim** matching the attribute's frequency — regardless of which USD attributes exist on that prim. The transformer receives ``None`` as the value (since there is no specific attribute to read) and a context dictionary containing the prim and the attribute definition. A :attr:`~newton.ModelBuilder.CustomAttribute.usd_value_transformer` **must** be provided when using ``"*"``; omitting it raises a :class:`ValueError`. **Example:** Suppose your USD stage contains "sensor" prims, each with an arbitrary ``sensor:position`` attribute. You want to store the distance from the origin as a custom attribute, computed at parse time: .. code-block:: python import warp as wp import numpy as np # 1. Register the custom frequency with a filter that selects sensor prims def is_sensor(prim, context): return prim.GetName().startswith("Sensor") builder.add_custom_frequency( ModelBuilder.CustomFrequency( name="sensor", namespace="myns", usd_prim_filter=is_sensor, ) ) # 2. Define a transformer that computes the distance from prim data def compute_distance(value, context): pos = context["prim"].GetAttribute("sensor:position").Get() return wp.float32(float(np.linalg.norm(pos))) # 3. Register the attribute with usd_attribute_name="*" builder.add_custom_attribute( ModelBuilder.CustomAttribute( name="distance", frequency="myns:sensor", dtype=wp.float32, default=0.0, namespace="myns", usd_attribute_name="*", usd_value_transformer=compute_distance, ) ) # 4. Parse the USD stage (assuming `stage` is an existing Usd.Stage) builder.add_usd(stage) model = builder.finalize() # Access the computed values distances = model.myns.distance.numpy() The transformer context dictionary contains: * ``"prim"``: The current USD prim. * ``"attr"``: The :class:`~newton.ModelBuilder.CustomAttribute` being evaluated. * When called from :meth:`~newton.ModelBuilder.add_usd` custom-frequency parsing, context also includes ``"result"`` (the ``add_usd`` return dictionary) and ``"builder"`` (the current :class:`~newton.ModelBuilder`). This pattern is useful when: * The value you need doesn't exist as a single USD attribute (it must be derived from multiple attributes, prim metadata, or relationships). * You want to run the same computation for every prim of a given frequency without requiring an authored attribute on each prim. * You need to look up related entities (for example, resolving a prim relationship to a body index through ``context["result"]["path_body_map"]``). Multi-World Merging ------------------- When using ``add_builder()``, ``add_world()``, or ``replicate()`` in multi-world simulations, the :attr:`~newton.ModelBuilder.CustomAttribute.references` field specifies how attribute values should be transformed: .. testcode:: custom-merge from newton import Model, ModelBuilder builder = ModelBuilder() builder.add_custom_frequency( ModelBuilder.CustomFrequency(name="pair", namespace="mujoco") ) builder.add_custom_attribute( ModelBuilder.CustomAttribute( name="pair_world", frequency="mujoco:pair", dtype=wp.int32, namespace="mujoco", references="world", # Replaced with the builder-managed current world during merge ) ) builder.add_custom_attribute( ModelBuilder.CustomAttribute( name="pair_geom1", frequency="mujoco:pair", dtype=wp.int32, namespace="mujoco", references="shape", # Offset by shape count during merge ) ) Supported reference types: * Any built-in entity type (e.g., ``"body"``, ``"shape"``, ``"joint"``, ``"joint_dof"``, ``"joint_coord"``, ``"articulation"``) — offset by entity count * ``"world"`` — replaced with the builder-managed ``current_world`` for the active merge context * Custom frequency keys (e.g., ``"mujoco:pair"``) — offset by that frequency's count Querying Counts --------------- Use :meth:`~newton.Model.get_custom_frequency_count` to get the count for a custom frequency (raises ``KeyError`` if unknown): .. testcode:: custom-merge # Finalize (requires at least one articulation) _body = builder.add_link() _joint = builder.add_joint_free(_body) builder.add_articulation([_joint]) model = builder.finalize() pair_count = model.get_custom_frequency_count("mujoco:pair") # Or check directly without raising: pair_count = model.custom_frequency_counts.get("mujoco:pair", 0) .. note:: When querying, use the full frequency key with namespace prefix (e.g., ``"mujoco:pair"``). This matches how attribute keys work: ``model.get_attribute_frequency("mujoco:condim")`` for a namespaced attribute. ArticulationView Limitations ---------------------------- Custom frequency attributes are generally not accessible via :class:`~newton.selection.ArticulationView` because they represent entity types that aren't tied to articulation structure. The one exception is the ``mujoco:tendon`` frequency, which is supported. For per-articulation data, use enum frequencies like ``ARTICULATION``, ``JOINT``, or ``BODY``. ================================================ FILE: docs/concepts/extended_attributes.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 .. currentmodule:: newton .. _extended_attributes: Extended Attributes =================== Newton's :class:`~newton.State` and :class:`~newton.Contacts` objects can optionally carry extra arrays that are not always needed. These *extended attributes* are allocated on demand when explicitly requested, reducing memory usage for simulations that don't need them. .. _extended_contact_attributes: Extended Contact Attributes --------------------------- Extended contact attributes are optional arrays on :class:`~newton.Contacts` (e.g., contact forces for sensors). Request them via :meth:`Model.request_contact_attributes ` or :meth:`ModelBuilder.request_contact_attributes ` before creating a :class:`~newton.Contacts` object. .. testcode:: import newton builder = newton.ModelBuilder() body = builder.add_body(mass=1.0) builder.add_shape_sphere(body, radius=0.1) model = builder.finalize() # Request the "force" extended attribute directly model.request_contact_attributes("force") contacts = model.contacts() print(contacts.force is not None) .. testoutput:: True Some components request attributes transparently. For example, :class:`~newton.sensors.SensorContact` requests ``"force"`` at init time, so creating the sensor before allocating contacts is sufficient: .. testcode:: import warp as wp import newton from newton.sensors import SensorContact builder = newton.ModelBuilder() builder.add_ground_plane() body = builder.add_body(xform=wp.transform((0, 0, 0.1), wp.quat_identity())) builder.add_shape_sphere(body, radius=0.1, label="ball") model = builder.finalize() sensor = SensorContact(model, sensing_obj_shapes="ball") contacts = model.contacts() print(contacts.force is not None) .. testoutput:: True The canonical list is :attr:`Contacts.EXTENDED_ATTRIBUTES `: .. list-table:: :header-rows: 1 :widths: 22 78 * - Attribute - Description * - :attr:`~newton.Contacts.force` - Contact spatial forces (used by :class:`~newton.sensors.SensorContact`) .. _extended_state_attributes: Extended State Attributes ------------------------- Extended state attributes are optional arrays on :class:`~newton.State` (e.g., accelerations for sensors). Request them via :meth:`Model.request_state_attributes ` or :meth:`ModelBuilder.request_state_attributes ` before calling :meth:`Model.state() `. .. testcode:: import newton builder = newton.ModelBuilder() body = builder.add_body(mass=1.0) builder.request_state_attributes("body_qdd") model = builder.finalize() state = model.state() print(state.body_qdd is not None) .. testoutput:: True The canonical list is :attr:`State.EXTENDED_ATTRIBUTES `: .. list-table:: :header-rows: 1 :widths: 22 78 * - Attribute - Description * - :attr:`~newton.State.body_qdd` - Rigid-body spatial accelerations (used by :class:`~newton.sensors.SensorIMU`) * - :attr:`~newton.State.body_parent_f` - Rigid-body parent interaction wrenches * - ``State.mujoco.qfrc_actuator`` - Actuator forces in generalized (joint DOF) coordinates, namespaced under ``state.mujoco.qfrc_actuator``. Only populated by :class:`~newton.solvers.SolverMuJoCo`. Notes ----- - Some components transparently request attributes they need. For example, :class:`~newton.sensors.SensorIMU` requests ``body_qdd`` and :class:`~newton.sensors.SensorContact` requests ``force``. Create sensors before allocating State/Contacts for this to work automatically. - Solvers populate extended attributes they support. Currently, :class:`~newton.solvers.SolverMuJoCo` populates ``body_qdd``, ``body_parent_f``, ``mujoco:qfrc_actuator``, and ``force``. ================================================ FILE: docs/concepts/mass_inertia.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2026 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 .. _Mass and Inertia: Mass and Inertia ================ Every dynamic rigid body in Newton needs positive mass and a physically meaningful inertia tensor for stable simulation. Newton provides three ways to assign these properties: 1. **Direct specification** on the body via :meth:`~newton.ModelBuilder.add_link`. 2. **Density-based inference** from collision shapes added with :class:`~newton.ModelBuilder.ShapeConfig`. 3. **File import** (USD, MJCF, URDF), where mass properties are parsed from the source format and mapped to Newton's internal representation. For the distinction between static, kinematic, and dynamic bodies see :ref:`Articulations`. Best practices -------------- .. tip:: **Dynamic bodies should have positive mass.** If a body has no shapes with density, set ``mass`` and ``inertia`` explicitly on :meth:`~newton.ModelBuilder.add_link`. .. tip:: **Use** ``is_kinematic=True`` **for prescribed motion** — do not rely on zero mass to make a body immovable. See :ref:`Articulations` for details. .. tip:: **Prefer density-based inference** when possible. Letting Newton compute mass and inertia from shape geometry keeps mass properties consistent with collision geometry and avoids manual bookkeeping. .. tip:: **Use** ``lock_inertia=True`` **to protect hand-specified mass properties** from subsequent shape additions. This is the mechanism the MJCF importer uses when an ```` element is present. .. tip:: **Check finalize warnings.** Set ``validate_inertia_detailed=True`` on :class:`~newton.ModelBuilder` during development to get per-body warnings for any mass or inertia values that were corrected. .. _Specifying mass and inertia: Specifying mass and inertia --------------------------- Direct specification on the body ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ :meth:`~newton.ModelBuilder.add_link` accepts the following inertial parameters: - ``mass`` — body mass [kg]. Defaults to ``0.0``. - ``inertia`` — 3x3 inertia tensor [kg m\ :sup:`2`] relative to the center of mass. Defaults to the zero matrix. - ``com`` — center-of-mass offset [m] from the body origin. Defaults to the origin. - ``armature`` — artificial scalar inertia [kg m\ :sup:`2`] added to the diagonal of the inertia tensor. Useful for regularization. These values serve as the initial mass properties of the body. If shapes with positive density are subsequently added, their contributions are accumulated on top of these initial values (see below). Automatic inference from shape density ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ When a shape is added via one of the ``add_shape_*()`` methods with :attr:`ShapeConfig.density ` > 0, Newton automatically computes mass, center of mass, and inertia tensor from the shape geometry and accumulates the result onto the parent body. The accumulation follows three steps: 1. **Mass**: the shape's mass is added to the body's total mass. 2. **Center of mass**: the body COM is recomputed as the mass-weighted average of the existing body COM and the shape's COM (transformed to body frame). 3. **Inertia**: both the existing body inertia and the shape inertia are shifted to the new COM using the parallel-axis theorem (Steiner's theorem), then summed. This means multiple shapes on the same body compose additively. .. testcode:: mass-accumulation import numpy as np import warp as wp import newton builder = newton.ModelBuilder() # Body with initial mass 2.0 kg body = builder.add_link(mass=2.0) # Shape adds mass from density: a 1m-radius sphere at 1000 kg/m^3 builder.add_shape_sphere(body, radius=1.0, cfg=builder.ShapeConfig(density=1000.0)) sphere_mass = 4.0 / 3.0 * np.pi * 1000.0 # ~4189 kg assert abs(builder.body_mass[body] - (2.0 + sphere_mass)) < 1.0 Special cases: - **Planes and heightfields** never contribute mass, regardless of density. - **Sites** enforce ``density=0`` and never contribute mass. - ``lock_inertia=True`` on :meth:`~newton.ModelBuilder.add_link` prevents subsequent shape additions from modifying the body's mass, COM, or inertia. - **Hollow shapes** (``ShapeConfig.is_solid=False``) compute shell inertia by subtracting the inner volume's contribution from the outer, using :attr:`ShapeConfig.margin ` as shell thickness. .. _Mass resolution during file import: Mass resolution during file import ----------------------------------- When importing from USD, MJCF, or URDF, each format has its own rules for how mass properties are authored, inferred, or overridden. Regardless of format, shape-derived contributions all flow through the same accumulation logic described above. The common pattern across formats is: - **Explicit inertial data takes precedence** when present (``UsdPhysics.MassAPI`` for USD, ```` for MJCF/URDF). - **Shape-based inference** is the fallback when explicit data is missing — mass and inertia are computed from collision geometry and density. - Both MJCF and URDF importers accept ``ignore_inertial_definitions=True`` to skip explicit inertial data and always infer from shapes. For format-specific details, see: - **USD**: :ref:`usd_parsing` — covers the ``MassAPI`` precedence cascade, ``ComputeMassProperties`` callback, and collider density priority. - **MJCF**: :meth:`~newton.ModelBuilder.add_mjcf` — follows MuJoCo semantics where ```` fully overrides geom-derived mass (via ``lock_inertia``), and geoms contribute via density when ```` is absent. - **URDF**: :meth:`~newton.ModelBuilder.add_urdf` — uses ```` directly when present; falls back to collision geometry with default density otherwise. By default visual shapes do not contribute mass; however, ``parse_visuals_as_colliders=True`` promotes visual geometry into the collider set, making it mass-contributing at ``default_shape_density``. .. _Validation and correction at finalize: Validation and correction at finalize -------------------------------------- During :meth:`~newton.ModelBuilder.finalize`, Newton validates and optionally corrects mass and inertia properties for all bodies. Compiler settings ^^^^^^^^^^^^^^^^^ The following attributes on :class:`~newton.ModelBuilder` control validation behavior: .. list-table:: :header-rows: 1 :widths: 30 15 55 * - Setting - Default - Description * - :attr:`~newton.ModelBuilder.balance_inertia` - ``True`` - Fix triangle-inequality violations on principal moments by shifting eigenvalues uniformly. * - :attr:`~newton.ModelBuilder.bound_mass` - ``None`` - Minimum mass value. If set, clamps small masses up to this value. * - :attr:`~newton.ModelBuilder.bound_inertia` - ``None`` - Minimum inertia eigenvalue. If set, ensures all principal moments are at least this value. * - :attr:`~newton.ModelBuilder.validate_inertia_detailed` - ``False`` - When ``True``, uses CPU validation with per-body warnings. When ``False``, uses a fast GPU kernel that returns only the count of corrected bodies. Checks performed ^^^^^^^^^^^^^^^^ The detailed (``validate_inertia_detailed=True``) and fast (default) validation paths apply the same conceptual checks, but the detailed path emits per-body warnings. Work is underway to unify the two implementations. The following checks are applied in order: 1. **Negative mass** — set to zero. 2. **Small positive mass** below ``bound_mass`` — clamped (if ``bound_mass`` is set). 3. **Zero mass with non-zero inertia** — inertia zeroed. 4. **Inertia symmetry** — enforced via :math:`(I + I^T) / 2`. 5. **Positive definiteness** — negative eigenvalues adjusted. 6. **Eigenvalue bounds** — all eigenvalues clamped to at least ``bound_inertia`` (if set). 7. **Triangle inequality** — principal moments must satisfy :math:`I_1 + I_2 \geq I_3`. If violated and ``balance_inertia`` is ``True``, eigenvalues are shifted uniformly to satisfy the inequality. .. note:: :meth:`~newton.ModelBuilder.collapse_fixed_joints` merges mass and inertia across collapsed bodies *before* validation runs. .. _Shape inertia reference: Shape inertia reference ----------------------- The table below summarizes the mass formula for each shape type when density is positive. For the full inertia tensor expressions, see :func:`~newton.geometry.compute_inertia_shape`. .. list-table:: :header-rows: 1 :widths: 18 35 47 * - Shape - Mass - Notes * - Sphere - :math:`\tfrac{4}{3} \pi r^3 \rho` - Hollow: shell inertia (outer minus inner). * - Box - :math:`8\, h_x h_y h_z\, \rho` - Half-extents. * - Capsule - hemisphere caps + cylinder - :math:`(\tfrac{4}{3}\pi r^3 + 2\pi r^2 h)\,\rho` * - Cylinder - :math:`\pi r^2 h\, \rho` - * - Cone - :math:`\tfrac{1}{3} \pi r^2 h\, \rho` - Center of mass offset from base. * - Ellipsoid - :math:`\tfrac{4}{3} \pi a\,b\,c\, \rho` - Semi-axes. * - Mesh - Integrated from triangles - Cached on :class:`~newton.Mesh` when available; recomputed from vertices otherwise. Supports solid and hollow. * - Plane - Always 0 - Regardless of density. * - Heightfield - Always 0 - Regardless of density. Hollow shapes (``ShapeConfig.is_solid=False``) compute shell inertia by subtracting the inner volume's contribution, using :attr:`ShapeConfig.margin ` as shell thickness. ================================================ FILE: docs/concepts/sensors.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 Sensors ======= Sensors in Newton provide a way to extract measurements and observations from the simulation. They compute derived quantities that are commonly needed for control, reinforcement learning, robotics applications, and analysis. Overview -------- Most Newton sensors follow a common pattern: 1. **Initialization**: Configure the sensor with the model and specify what to measure 2. **Update**: Call ``sensor.update(state, ...)`` during the simulation loop to compute measurements 3. **Access**: Read results from sensor attributes (typically as Warp arrays) .. note:: Sensors automatically request any :doc:`extended attributes ` they need (e.g. ``body_qdd``, ``Contacts.force``) at init, so ``State`` and ``Contacts`` objects created afterwards will include them. ``SensorContact`` additionally requires a call to ``solver.update_contacts()`` before ``sensor.update()``. ``SensorTiledCamera`` writes results to output arrays passed into ``update()`` rather than storing them as sensor attributes. .. testcode:: import warp as wp import newton from newton.sensors import SensorIMU # Build the model builder = newton.ModelBuilder() builder.add_ground_plane() body = builder.add_body(xform=wp.transform((0, 0, 1), wp.quat_identity())) builder.add_shape_sphere(body, radius=0.1) builder.add_site(body, label="imu_0") model = builder.finalize() # 1. Create sensor and specify what to measure imu = SensorIMU(model, sites="imu_*") # Create solver and state solver = newton.solvers.SolverMuJoCo(model) state = model.state() # Simulation loop for _ in range(100): state.clear_forces() solver.step(state, state, None, None, dt=1.0 / 60.0) # 2. Compute measurements from the current state imu.update(state) # 3. Results stored on sensor attributes acc = imu.accelerometer.numpy() # (n_sensors, 3) linear acceleration gyro = imu.gyroscope.numpy() # (n_sensors, 3) angular velocity print("accelerometer shape:", acc.shape) print("gyroscope shape:", gyro.shape) .. testoutput:: accelerometer shape: (1, 3) gyroscope shape: (1, 3) .. _label-matching: Label Matching -------------- Several Newton APIs accept **label patterns** to select bodies, shapes, joints, sites, etc. by name. Parameters that support label matching accept one of the following: - A **list of integer indices** -- selects directly by index. - A **single string pattern** -- selects all entries whose label matches the pattern via :func:`fnmatch.fnmatch` (supports ``*`` and ``?`` wildcards). - A **list of string patterns** -- selects all entries whose label matches at least one of the patterns. Examples:: # single pattern: all shapes whose label starts with "foot_" SensorIMU(model, sites="foot_*") # list of patterns: union of two groups SensorContact(model, sensing_obj_shapes=["*Plate*", "*Flap*"]) # list of indices: explicit selection SensorFrameTransform(model, shapes=[0, 3, 7], reference_sites=[1]) Available Sensors ----------------- Newton provides five sensor types. See the :doc:`API reference <../api/newton_sensors>` for constructor arguments, attributes, and usage examples. * :class:`~newton.sensors.SensorContact` -- contact forces between bodies or shapes, including friction decomposition, with optional per-counterpart breakdown. * :class:`~newton.sensors.SensorFrameTransform` -- relative transforms of shapes/sites with respect to reference sites. * :class:`~newton.sensors.SensorIMU` -- linear acceleration and angular velocity at site frames. * :class:`~newton.sensors.SensorRaycast` -- ray-based depth images from a virtual camera. * :class:`~newton.sensors.SensorTiledCamera` -- raytraced color and depth rendering across multiple worlds. Extended Attributes ------------------- Some sensors depend on extended attributes that are not allocated by default: - ``SensorIMU`` requires ``State.body_qdd`` (rigid-body accelerations). By default it requests this from the model at construction, so subsequent ``model.state()`` calls allocate it automatically. - ``SensorContact`` requires ``Contacts.force`` (per-contact spatial force wrenches). By default it requests this from the model at construction, so subsequent ``model.contacts()`` calls allocate it automatically. The solver must also support populating contact forces. Performance Considerations -------------------------- Sensors are designed to be efficient and GPU-friendly, computing results in parallel where possible. Create each sensor once during setup and reuse it every step -- this lets Newton pre-allocate output arrays and avoid per-frame overhead. Sensors that depend on extended attributes (e.g. ``body_qdd``, ``Contacts.force``) may add nontrivial cost to the solver step itself, since the solver must compute and store these additional quantities regardless of whether the sensor is evaluated after each step. See Also -------- * :doc:`sites` -- using sites as sensor attachment points and reference frames * :doc:`../api/newton_sensors` -- full sensor API reference * :doc:`extended_attributes` -- optional ``State``/``Contacts`` arrays required by some sensors * ``newton.examples.sensors.example_sensor_contact`` -- SensorContact example * ``newton.examples.sensors.example_sensor_imu`` -- SensorIMU example * ``newton.examples.sensors.example_sensor_tiled_camera`` -- SensorTiledCamera example ================================================ FILE: docs/concepts/sites.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 Sites (Abstract Markers) ======================== **Sites** are abstract reference points that don't participate in physics simulation or collision detection. They are lightweight markers used for: * Sensor attachment points (IMU, camera, raycast origins) * Frame of reference definitions for measurements * Debugging and visualization reference points * Spatial tendon attachment points and routing Overview -------- Sites in Newton are implemented as a special type of shape with the following properties: * **No collision**: Sites never collide with any objects (shapes or particles) * **No mass contribution**: Sites have zero density and don't affect body inertia * **Transform-based**: Sites have position and orientation relative to their parent body * **Shape types**: Sites can use any geometric primitive (sphere, box, capsule, etc.) for visualization * **Visibility**: Sites can be visible (for debugging) or invisible (for runtime use) Creating Sites -------------- Sites are created using the ``add_site()`` method on ModelBuilder: .. testcode:: sites-basic builder = newton.ModelBuilder() # Create a body body = builder.add_body(mass=1.0) # Add a site at body origin imu_site = builder.add_site( body=body, label="imu" ) # Add a site with offset and rotation camera_site = builder.add_site( body=body, xform=wp.transform( wp.vec3(0.5, 0, 0.2), # Position wp.quat_from_axis_angle(wp.vec3(0, 1, 0), 3.14159/4) # Orientation ), type=newton.GeoType.BOX, scale=(0.05, 0.05, 0.02), visible=True, label="camera" ) Sites can also be attached to the world frame (body=-1) to create fixed reference points: .. testcode:: sites-world builder = newton.ModelBuilder() # World-frame reference site world_origin = builder.add_site( body=-1, xform=wp.transform(wp.vec3(0, 0, 0), wp.quat_identity()), label="world_origin" ) Alternative: Using Shape Methods with ``as_site=True`` ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ Sites can also be created using shape creation methods (``add_shape_sphere``, ``add_shape_box``, ``add_shape_capsule``, ``add_shape_cylinder``, ``add_shape_ellipsoid``, ``add_shape_cone``) by passing ``as_site=True``. This is particularly useful when programmatically generating shapes or conditionally creating sites: .. testcode:: sites-shape-methods builder = newton.ModelBuilder() body = builder.add_body(mass=1.0) # Create sites using shape methods sphere_site = builder.add_shape_sphere( body=body, radius=0.05, as_site=True, label="sphere_marker" ) box_site = builder.add_shape_box( body=body, hx=0.1, hy=0.1, hz=0.1, as_site=True, label="box_marker" ) # Useful for conditional creation is_sensor_point = True shape_idx = builder.add_shape_sphere( body=body, radius=0.05, as_site=is_sensor_point, # Conditionally a site label="measurement_point" ) When ``as_site=True``, the shape is automatically configured with all site invariants (no collision, zero density, collision_group=0), regardless of any custom configuration passed. Importing Sites --------------- Sites are automatically imported from MJCF and USD files, with optional control over what gets loaded. MJCF Import ~~~~~~~~~~~ MuJoCo sites are directly mapped to Newton sites, preserving type, position, orientation, and size: .. code-block:: xml By default, sites are loaded along with collision and visual shapes. You can control this behavior with the ``parse_sites`` and ``parse_visuals`` parameters: .. code-block:: python builder = newton.ModelBuilder() # Load only collision shapes and sites (no visual shapes) builder.add_mjcf("robot.xml", parse_sites=True, parse_visuals=False) # Load only collision shapes (no sites or visual shapes) builder.add_mjcf("robot.xml", parse_sites=False, parse_visuals=False) USD Import ~~~~~~~~~~ Sites in USD are identified by the ``MjcSiteAPI`` schema applied to geometric primitives: .. code-block:: usda def Xform "robot" ( prepend apiSchemas = ["PhysicsRigidBodyAPI"] ) { def Sphere "imu_site" ( prepend apiSchemas = ["MjcSiteAPI"] ) { double radius = 0.02 double3 xformOp:translate = (0.1, 0, 0) uniform token[] xformOpOrder = ["xformOp:translate"] } } Similar to MJCF import, you can control whether sites and visual shapes are loaded using the ``load_sites`` and ``load_visual_shapes`` parameters: .. code-block:: python builder = newton.ModelBuilder() # Load only collision shapes and sites (no visual shapes) builder.add_usd("robot.usda", load_sites=True, load_visual_shapes=False) # Load only collision shapes (no sites or visual shapes) builder.add_usd("robot.usda", load_sites=False, load_visual_shapes=False) By default, both ``load_sites`` and ``load_visual_shapes`` are set to ``True``. Using Sites with Sensors ------------------------ Sites are commonly used as reference frames for sensors, particularly :class:`~newton.sensors.SensorFrameTransform` which computes relative poses between objects and reference frames. For detailed information on using sites with sensors, see :doc:`sensors`. MuJoCo Interoperability ----------------------- When using ``SolverMuJoCo``, Newton sites are automatically exported to MuJoCo's native site representation: .. testcode:: sites-mujoco from newton.solvers import SolverMuJoCo # Create a simple model with a site builder = newton.ModelBuilder() body = builder.add_body(mass=1.0, inertia=wp.mat33(np.eye(3))) site = builder.add_site(body=body, label="sensor") model = builder.finalize() # Create MuJoCo solver (sites are exported by default) solver = SolverMuJoCo(model) Sites are exported with their visual properties (color, size) and can be used with MuJoCo's native sensors and actuators. To disable site export, pass ``include_sites=False`` to :class:`~newton.solvers.SolverMuJoCo`. Implementation Details ---------------------- Sites are internally represented as shapes with the :attr:`~newton.ShapeFlags.SITE` flag set. This allows them to leverage Newton's existing shape infrastructure while maintaining distinct behavior: * Sites are filtered out from collision detection pipelines * Site density is automatically set to zero during creation * Sites can be identified at runtime by checking the :attr:`~newton.ShapeFlags.SITE` flag on ``model.shape_flags`` This implementation approach provides maximum flexibility while keeping the codebase maintainable and avoiding duplication. See Also -------- * :doc:`sensors` — Using sites with sensors for measurements * :doc:`custom_attributes` — Attaching custom data to sites and other entities * :doc:`../api/newton_sensors` — Full sensor API reference * :doc:`usd_parsing` — Details on USD schema handling ================================================ FILE: docs/concepts/usd_parsing.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 .. _usd_parsing: USD Parsing and Schema Resolver System ======================================== Newton provides USD (Universal Scene Description) ingestion and schema resolver pipelines that enable integration of physics assets authored for different simulation solvers. Understanding USD and UsdPhysics -------------------------------- USD (Universal Scene Description) is Pixar's open-source framework for interchange of 3D computer graphics data. It provides an ecosystem for describing 3D scenes with hierarchical composition, animation, and metadata. UsdPhysics is the standard USD schema for physics simulation, defining for instance: * Rigid bodies (``UsdPhysics.RigidBodyAPI``) * Collision shapes (``UsdPhysics.CollisionAPI``) * Joints and constraints (``UsdPhysics.Joint``) * Materials and contact properties (``UsdPhysics.MaterialAPI``) * Scene-level physics settings (``UsdPhysics.Scene``) However, UsdPhysics provides only a basic foundation. Different physics solvers like PhysX and MuJoCo often require additional attributes not covered by these standard schemas. PhysX and MuJoCo have their own schemas for describing physics assets. While some of these attributes are *conceptually* common between many solvers, many are solver-specific. Even among the common attributes, the names and semantics may differ and they are only conceptually similar. Therefore, some transformation is needed to make these attributes usable by Newton. Newton's schema resolver system automatically handles these differences, allowing assets authored for any solver to work with Newton's simulation. See :ref:`schema_resolvers` for more details. Newton's USD Import System -------------------------- Newton's :meth:`newton.ModelBuilder.add_usd` method provides a USD import pipeline that: * Parses standard UsdPhysics schema for basic rigid body simulation setup * Resolves common solver attributes that are conceptually similar between different solvers through configurable schema resolvers * Handles priority-based attribute resolution when multiple solvers define conflicting values for conceptually similar properties * Collects solver-specific attributes preserving solver-native attributes for potential use in the solver * Supports parsing of custom Newton model/state/control attributes for specialized simulation requirements Mass and Inertia Precedence --------------------------- .. seealso:: :ref:`Mass and Inertia` for general concepts: the programmatic API, density-based inference, and finalize-time validation. For rigid bodies with ``UsdPhysics.MassAPI`` applied, Newton resolves each inertial property (mass, inertia, center of mass) independently. Authored attributes take precedence; ``UsdPhysics.RigidBodyAPI.ComputeMassProperties(...)`` provides baseline values for the rest. 1. Authored ``physics:mass``, ``physics:diagonalInertia``, and ``physics:centerOfMass`` are applied directly when present. If ``physics:principalAxes`` is missing, identity rotation is used. 2. When ``physics:mass`` is authored but ``physics:diagonalInertia`` is not, the inertia accumulated from collision shapes is scaled by ``authored_mass / accumulated_mass``. 3. For any remaining unresolved properties, Newton falls back to ``UsdPhysics.RigidBodyAPI.ComputeMassProperties(...)``. In this fallback path, collider contributions use a two-level precedence: a. If collider ``UsdPhysics.MassAPI`` has authored ``mass`` and ``diagonalInertia``, those authored values are converted to unit-density collider mass information. b. Otherwise, Newton derives unit-density collider mass information from collider geometry. A collider is skipped (with warning) only if neither path provides usable collider mass information. .. note:: The callback payload provided by Newton in this path is unit-density collider shape information (volume/COM/inertia basis). Collider density authored via ``UsdPhysics.MassAPI`` (for example, ``physics:density``) or via bound ``UsdPhysics.MaterialAPI`` is still applied by USD during ``ComputeMassProperties(...)``. In other words, unit-density callback data does not mean authored densities are ignored. If resolved mass is non-positive, inverse mass is set to ``0``. .. tip:: For the most predictable results, fully author ``physics:mass``, ``physics:diagonalInertia``, ``physics:principalAxes``, and ``physics:centerOfMass`` on each rigid body. This avoids any fallback heuristics and is also the fastest import path since ``ComputeMassProperties(...)`` can be skipped entirely. .. _schema_resolvers: Schema Resolvers ---------------- Schema resolvers bridge the gap between solver-specific USD schemas and Newton's internal representation. They remap attributes authored for PhysX, MuJoCo, or other solvers to the equivalent Newton properties, handle priority-based resolution when multiple solvers define the same attribute, and collect solver-native attributes for inspection or custom pipelines. .. note:: The ``schema_resolvers`` argument in :meth:`newton.ModelBuilder.add_usd` is an experimental feature that may be removed or changed significantly in the future. Solver Attribute Remapping ~~~~~~~~~~~~~~~~~~~~~~~~~~ When working with USD assets authored for other physics solvers like PhysX or MuJoCo, Newton's schema resolver system can automatically remap various solver attributes to Newton's internal representation. This enables Newton to use physics properties from assets originally designed for other simulators without manual conversion. The following tables show examples of how solver-specific attributes are mapped to Newton's internal representation. Some attributes map directly while others require mathematical transformations. **PhysX Attribute Remapping Examples:** The table below shows PhysX attribute remapping examples: .. list-table:: PhysX Attribute Remapping :header-rows: 1 :widths: 30 30 40 * - **PhysX Attribute** - **Newton Equivalent** - **Transformation** * - ``physxJoint:armature`` - ``armature`` - Direct mapping * - ``physxArticulation:enabledSelfCollisions`` - ``self_collision_enabled`` (per articulation) - Direct mapping **Newton articulation remapping:** On articulation root prims (with ``PhysicsArticulationRootAPI`` or ``NewtonArticulationRootAPI``), the following is resolved: .. list-table:: Newton Articulation Remapping :header-rows: 1 :widths: 30 30 40 * - **Newton Attribute** - **Resolved key** - **Transformation** * - ``newton:selfCollisionEnabled`` - ``self_collision_enabled`` - Direct mapping The parser resolves ``self_collision_enabled`` from either ``newton:selfCollisionEnabled`` or ``physxArticulation:enabledSelfCollisions`` (in resolver priority order). The ``enable_self_collisions`` argument to :meth:`newton.ModelBuilder.add_usd` is used as the default when neither attribute is authored. **MuJoCo Attribute Remapping Examples:** The table below shows MuJoCo attribute remapping examples, including both direct mappings and transformations: .. list-table:: MuJoCo Attribute Remapping :header-rows: 1 :widths: 30 30 40 * - **MuJoCo Attribute** - **Newton Equivalent** - **Transformation** * - ``mjc:armature`` - ``armature`` - Direct mapping * - ``mjc:margin``, ``mjc:gap`` - ``margin`` - ``margin = mjc:margin - mjc:gap`` **Example USD with remapped attributes:** The following USD example demonstrates how PhysX attributes are authored in a USD file. The schema resolver automatically applies the transformations shown in the table above during import: .. code-block:: usda #usda 1.0 def PhysicsScene "Scene" ( prepend apiSchemas = ["PhysxSceneAPI"] ) { # PhysX scene settings that Newton can understand uint physxScene:maxVelocityIterationCount = 16 # → max_solver_iterations = 16 } def RevoluteJoint "elbow_joint" ( prepend apiSchemas = ["PhysxJointAPI", "PhysxLimitAPI:angular"] ) { # PhysX joint attributes remapped to Newton float physxJoint:armature = 0.1 # → armature = 0.1 # PhysX limit attributes (applied via PhysxLimitAPI:angular) float physxLimit:angular:stiffness = 1000.0 # → limit_angular_ke = 1000.0 float physxLimit:angular:damping = 10.0 # → limit_angular_kd = 10.0 # Initial joint state float state:angular:physics:position = 1.57 # → joint_q = 1.57 rad } def Mesh "collision_shape" ( prepend apiSchemas = ["PhysicsCollisionAPI", "PhysxCollisionAPI"] ) { # PhysX collision settings (gap = contactOffset - restOffset) float physxCollision:contactOffset = 0.05 float physxCollision:restOffset = 0.01 # → gap = 0.04 } Priority-Based Resolution ~~~~~~~~~~~~~~~~~~~~~~~~~ When multiple physics solvers define conflicting attributes for the same property, the user can define which solver attributes should be preferred by configuring the resolver order. **Resolution Hierarchy:** The attribute resolution process follows a three-layer fallback hierarchy to determine which value to use: 1. **Authored Values**: Resolvers are queried in priority order; the first resolver that finds an authored value on the prim returns it and remaining resolvers are not consulted. 2. **Importer Defaults**: If no authored value is found, Newton's importer uses a property-specific fallback (e.g. ``builder.default_joint_cfg.armature`` for joint armature). This takes precedence over schema-level defaults. 3. **Approximated Schema Defaults**: If neither an authored value nor an importer default is available, Newton falls back to a hardcoded approximation of each solver's schema default, defined in Newton's resolver mapping. These approximations will be replaced by actual USD schema defaults in a future release. **Configuring Resolver Priority:** The order of resolvers in the ``schema_resolvers`` list determines priority, with earlier entries taking precedence. To demonstrate this, consider a USD asset where the same joint has conflicting armature values authored for different solvers: .. code-block:: usda def RevoluteJoint "shoulder_joint" { float newton:armature = 0.01 float physxJoint:armature = 0.02 float mjc:armature = 0.03 } By changing the order of resolvers in the ``schema_resolvers`` list, different attribute values will be selected from the same USD file. The following examples show how the same asset produces different results based on resolver priority: .. testcode:: :skipif: True from newton import ModelBuilder from newton.usd import SchemaResolverMjc, SchemaResolverNewton, SchemaResolverPhysx builder = ModelBuilder() # Configuration 1: Newton priority result_newton = builder.add_usd( source="conflicting_asset.usda", schema_resolvers=[SchemaResolverNewton(), SchemaResolverPhysx(), SchemaResolverMjc()] ) # Result: Uses newton:armature = 0.01 # Configuration 2: PhysX priority builder2 = ModelBuilder() result_physx = builder2.add_usd( source="conflicting_asset.usda", schema_resolvers=[SchemaResolverPhysx(), SchemaResolverNewton(), SchemaResolverMjc()] ) # Result: Uses physxJoint:armature = 0.02 # Configuration 3: MuJoCo priority builder3 = ModelBuilder() result_mjc = builder3.add_usd( source="conflicting_asset.usda", schema_resolvers=[SchemaResolverMjc(), SchemaResolverNewton(), SchemaResolverPhysx()] ) # Result: Uses mjc:armature = 0.03 Solver-Specific Attribute Collection ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ Some attributes are solver-specific and cannot be directly used by Newton's simulation. The schema resolver system preserves these solver-specific attributes during import, making them accessible as part of the parsing results. This is useful for: * Debugging and inspection of solver-specific properties * Future compatibility when Newton adds support for additional attributes * Custom pipelines that need to access solver-native properties * Sim-to-sim transfer where you might need to rebuild assets for other solvers **Solver-Specific Attribute Namespaces:** Each solver has its own namespace prefixes for solver-specific attributes. The table below shows the namespace conventions and provides examples of attributes that would be collected from each solver: .. list-table:: Solver-Specific Namespaces :header-rows: 1 :widths: 20 40 40 * - **Engine** - **Namespace Prefixes** - **Example Attributes** * - **PhysX** - ``physx``, ``physxScene``, ``physxRigidBody``, ``physxCollision``, ``physxArticulation`` - ``physxArticulation:enabledSelfCollisions``, ``physxSDFMeshCollision:meshScale`` * - **MuJoCo** - ``mjc`` - ``mjc:model:joint:testMjcJointScalar``, ``mjc:state:joint:testMjcJointVec3`` * - **Newton** - ``newton`` - ``newton:maxHullVertices``, ``newton:contactGap`` **Accessing Collected Solver-Specific Attributes:** The collected attributes are returned in the result dictionary and can be accessed by solver namespace: .. testcode:: :skipif: True from newton import ModelBuilder from newton.usd import SchemaResolverNewton, SchemaResolverPhysx builder = ModelBuilder() result = builder.add_usd( source="physx_humanoid.usda", schema_resolvers=[SchemaResolverPhysx(), SchemaResolverNewton()], ) # Access collected solver-specific attributes solver_attrs = result.get("schema_attrs", {}) if "physx" in solver_attrs: physx_attrs = solver_attrs["physx"] for prim_path, attrs in physx_attrs.items(): if "physxJoint:armature" in attrs: armature_value = attrs["physxJoint:armature"] print(f"PhysX joint {prim_path} has armature: {armature_value}") Custom Attributes from USD -------------------------- USD assets can define custom attributes that become part of the model/state/control attributes, see :ref:`custom_attributes` for more information. Besides the programmatic way of defining custom attributes through the :meth:`newton.ModelBuilder.add_custom_attribute` method, Newton's USD importer also supports declaring custom attributes from within a USD stage. **Overview:** Custom attributes enable users to: * Extend Newton's data model with application-specific properties * Store per-body/joint/dof/shape data directly in USD assets * Implement custom simulation behaviors driven by USD-authored data * Organize related attributes using namespaces **Declaration-First Pattern:** Custom attributes must be declared on the ``PhysicsScene`` prim with metadata before being used on individual prims: 1. **Declare on PhysicsScene**: Define attributes with ``customData`` metadata specifying assignment and frequency 2. **Assign on individual prims**: Override default values using shortened attribute names **Declaration Format:** .. code-block:: usda custom newton:namespace:attr_name = default_value ( customData = { string assignment = "model|state|control|contact" string frequency = "body|shape|joint|joint_dof|joint_coord|articulation" } ) Where: * **namespace** (optional): Custom namespace for organizing related attributes (omit for default namespace) * **attr_name**: User-defined attribute name * **assignment**: Storage location (``model``, ``state``, ``control``, ``contact``) * **frequency**: Per-entity granularity (``body``, ``shape``, ``joint``, ``joint_dof``, ``joint_coord``, ``articulation``) **Supported Data Types:** The system automatically infers data types from authored USD values. The following table shows the mapping between USD types and Warp types used internally by Newton: .. list-table:: Custom Attribute Data Types :header-rows: 1 :widths: 25 25 50 * - **USD Type** - **Warp Type** - **Example** * - ``float`` - ``wp.float32`` - Scalar values * - ``bool`` - ``wp.bool`` - Boolean flags * - ``int`` - ``wp.int32`` - Integer values * - ``float2`` - ``wp.vec2`` - 2D vectors * - ``float3`` - ``wp.vec3`` - 3D vectors, positions * - ``float4`` - ``wp.vec4`` - 4D vectors * - ``quatf``/``quatd`` - ``wp.quat`` - Quaternions (with automatic reordering) **Assignment Types:** The ``assignment`` field in the declaration determines where the custom attribute data will be stored. The following table describes each assignment type and its typical use cases: .. list-table:: Custom Attribute Assignments :header-rows: 1 :widths: 15 25 60 * - **Assignment** - **Storage Location** - **Use Cases** * - ``model`` - ``Model`` object - Static configuration, physical properties, metadata * - ``state`` - ``State`` object - Dynamic quantities, targets, sensor readings * - ``control`` - ``Control`` object - Control parameters, actuator settings, gains * - ``contact`` - Contact container - Contact-specific properties (future use) **USD Authoring with Custom Attributes:** The following USD example demonstrates the complete workflow for authoring custom attributes. Note how attributes are first declared on the ``PhysicsScene`` with their metadata, then assigned with specific values on individual prims: .. code-block:: usda # robot_with_custom_attrs.usda #usda 1.0 def PhysicsScene "physicsScene" { # Declare custom attributes with metadata (default namespace) custom float newton:mass_scale = 1.0 ( customData = { string assignment = "model" string frequency = "body" } ) custom float3 newton:local_marker = (0.0, 0.0, 0.0) ( customData = { string assignment = "model" string frequency = "body" } ) custom bool newton:is_sensor = false ( customData = { string assignment = "model" string frequency = "body" } ) custom float3 newton:target_position = (0.0, 0.0, 0.0) ( customData = { string assignment = "state" string frequency = "body" } ) # Declare namespaced custom attributes (namespace_a) custom float newton:namespace_a:mass_scale = 1.0 ( customData = { string assignment = "state" string frequency = "body" } ) custom float newton:namespace_a:gear_ratio = 1.0 ( customData = { string assignment = "model" string frequency = "joint" } ) custom float2 newton:namespace_a:pid_gains = (0.0, 0.0) ( customData = { string assignment = "control" string frequency = "joint" } ) # Articulation frequency attribute custom float newton:articulation_stiffness = 100.0 ( customData = { string assignment = "model" string frequency = "articulation" } ) } def Xform "robot_body" ( prepend apiSchemas = ["PhysicsRigidBodyAPI"] ) { # Assign values to declared attributes (default namespace) custom float newton:mass_scale = 1.5 custom float3 newton:local_marker = (0.1, 0.2, 0.3) custom bool newton:is_sensor = true custom float3 newton:target_position = (1.0, 2.0, 3.0) # Assign values to namespaced attributes (namespace_a) custom float newton:namespace_a:mass_scale = 2.5 } def RevoluteJoint "joint1" { # Assign joint attributes (namespace_a) custom float newton:namespace_a:gear_ratio = 2.25 custom float2 newton:namespace_a:pid_gains = (100.0, 10.0) } # Articulation frequency attributes must be defined on the prim with PhysicsArticulationRootAPI def Xform "robot_articulation" ( prepend apiSchemas = ["PhysicsArticulationRootAPI"] ) { # Assign articulation-level attributes custom float newton:articulation_stiffness = 150.0 } .. note:: Attributes with ``frequency = "articulation"`` store per-articulation values and must be authored on USD prims that have the ``PhysicsArticulationRootAPI`` schema applied. **Accessing Custom Attributes in Python:** After importing the USD file with the custom attributes shown above, they become accessible as properties on the appropriate objects (``Model``, ``State``, or ``Control``) based on their assignment. The following example shows how to import and access these attributes: .. code-block:: python from newton import ModelBuilder builder = ModelBuilder() # Import the USD file with custom attributes (from example above) result = builder.add_usd( source="robot_with_custom_attrs.usda", ) model = builder.finalize() state = model.state() control = model.control() # Access default namespace model-assigned attributes body_mass_scale = model.mass_scale.numpy() # Per-body scalar local_markers = model.local_marker.numpy() # Per-body vec3 sensor_flags = model.is_sensor.numpy() # Per-body bool # Access default namespace state-assigned attributes target_positions = state.target_position.numpy() # Per-body vec3 # Access namespaced attributes (namespace_a) # Note: Same attribute name can exist in different namespaces with different assignments namespaced_mass = state.namespace_a.mass_scale.numpy() # Per-body scalar (state assignment) gear_ratios = model.namespace_a.gear_ratio.numpy() # Per-joint scalar pid_gains = control.namespace_a.pid_gains.numpy() # Per-joint vec2 arctic_stiff = model.articulation_stiffness.numpy() # Per-articulation scalar **Namespace Isolation:** Attributes with the same name in different namespaces are completely independent and stored separately. This allows the same attribute name to be used for different purposes across namespaces. In the example above, ``mass_scale`` appears in both the default namespace (as a model attribute) and in ``namespace_a`` (as a state attribute). These are treated as completely separate attributes with independent values, assignments, and storage locations. Limitations ----------- Importing USD files where many (> 30) mesh colliders are under the same rigid body can result in a crash in ``UsdPhysics.LoadUsdPhysicsFromRange``. This is a known thread-safety issue in OpenUSD and will be fixed in a future release of ``usd-core``. It can be worked around by setting the work concurrency limit to 1 before ``pxr`` initializes its thread pool. .. note:: Setting the concurrency limit to 1 disables multi-threaded USD processing globally and may degrade performance of other OpenUSD workloads in the same process. Choose **one** of the two approaches below — do not combine them. ``PXR_WORK_THREAD_LIMIT`` is evaluated once when ``pxr`` is first imported and cached for the lifetime of the process; after that point, ``Work.SetConcurrencyLimit()`` cannot override it. Conversely, if the env var *is* set, calling ``Work.SetConcurrencyLimit()`` has no effect. **Option A — environment variable (before any USD import):** .. code-block:: python import os os.environ["PXR_WORK_THREAD_LIMIT"] = "1" # must precede any pxr import from newton import ModelBuilder builder = ModelBuilder() result = builder.add_usd( source="rigid_body_with_many_mesh_colliders.usda", ) **Option B —** ``Work.SetConcurrencyLimit`` **(only when the env var is not set):** .. code-block:: python from pxr import Work import os if "PXR_WORK_THREAD_LIMIT" not in os.environ: Work.SetConcurrencyLimit(1) from newton import ModelBuilder builder = ModelBuilder() result = builder.add_usd( source="rigid_body_with_many_mesh_colliders.usda", ) .. seealso:: `threadLimits.h`_ (API reference) and `threadLimits.cpp`_ (implementation) document the precedence rules between the environment variable and the API. .. _threadLimits.h: https://openusd.org/dev/api/thread_limits_8h.html .. _threadLimits.cpp: https://github.com/PixarAnimationStudios/OpenUSD/blob/release/pxr/base/work/threadLimits.cpp ================================================ FILE: docs/concepts/worlds.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 .. _Worlds: Worlds ====== Newton enables multiple independent simulations, referred to as *worlds*, within a single :class:`~newton.Model` object. Each *world* provides an index-based grouping of all primary simulation entities such as particles, bodies, shapes, joints, articulations and equality constraints. Overview -------- GPU-accelerated operations in Newton often involve parallelizing over an entire set of model entities, e.g. bodies, shapes or joints, without needing to consider which specific world they belong to. However, some operations, such as those part of Collision Detection (CD), can exploit world-based grouping to effectively filter out potential collisions between shapes that belong to different worlds. Moreover, world-based grouping can also facilitate partitioning of thread grids according to both world indices and the number of entities per world. Such operations facilitate support for simulating multiple, and potentially heterogeneous, worlds defined within a :class:`~newton.Model` instance. Lastly, world-based grouping also enables selectively operating on only the entities that belong to a specific world, i.e. masking, as well as partitioning of the :class:`~newton.Model` and :class:`~newton.State` data. .. note:: Support for fully heterogeneous simulations is still under active development and quite experimental. At present time, although the :class:`~newton.ModelBuilder` and :class:`~newton.Model` objects support instantiating worlds with different disparate entities, not all solvers are able to simulate them. Moreover, the selection API still operates under the assumption of model homogeneity, but this is expected to also support heterogeneous simulations in the near future. .. _World assignment: World Assignment ---------------- World assignment is managed by :class:`~newton.ModelBuilder` when entities are added through methods such as :meth:`~newton.ModelBuilder.add_body`, :meth:`~newton.ModelBuilder.add_joint`, and :meth:`~newton.ModelBuilder.add_shape`. Assignment can either be global (world index ``-1``) or specific to a particular world (indices ``0, 1, 2, ...``). The supported workflows are: * Add entities before the first call to :meth:`~newton.ModelBuilder.begin_world` or after the last call to :meth:`~newton.ModelBuilder.end_world` to place them in the global world (index ``-1``), or between those calls to place them in a specific world. * Create worlds from a sub-builder with :meth:`~newton.ModelBuilder.add_world` or :meth:`~newton.ModelBuilder.replicate`. Within a world scope, each entity is assigned the current world index. The :attr:`~newton.ModelBuilder.current_world` attribute is a read-only property that reflects the active builder context and should not be set directly. The following example creates two different worlds within a single model: .. testcode:: import warp as wp import newton builder = newton.ModelBuilder() # Global entity at front (world -1) builder.add_ground_plane() # World 0: two free-floating spheres builder.begin_world() b0 = builder.add_body(mass=1.0) b1 = builder.add_body(mass=1.0) builder.add_shape_sphere(body=b0, radius=0.1) builder.add_shape_sphere(body=b1, radius=0.1) builder.end_world() # World 1: fixed-base revolute articulation with boxes builder.begin_world() link0 = builder.add_link(mass=1.0) j0 = builder.add_joint_fixed(parent=-1, child=link0) link1 = builder.add_link(mass=2.0) j1 = builder.add_joint_revolute(parent=link0, child=link1) builder.add_articulation(joints=[j0, j1]) builder.add_shape_box(body=link0, hx=0.1, hy=0.1, hz=0.1) builder.add_shape_box(body=link1, hx=0.1, hy=0.1, hz=0.1) builder.end_world() # Global entity at back (world -1) builder.add_shape_box(body=-1, hx=0.5, hy=0.5, hz=0.05) model = builder.finalize() In this example, we create a model with two worlds (world ``0`` and world ``1``) containing different bodies, shapes and joints, as well as two global entities (the ground plane at the front and a static box at the back, both with world index ``-1``). For homogeneous multi-world scenes, prefer :meth:`~newton.ModelBuilder.add_world` or :meth:`~newton.ModelBuilder.replicate` instead of manually repeating world scopes for each copy. .. _World grouping: World Grouping -------------- The :class:`~newton.ModelBuilder` maintains internal lists that track the world assignment of each entity added to it. When :meth:`~newton.ModelBuilder.finalize` is called, the :class:`~newton.Model` object generated will contain arrays that store the world indices for each entity type. Specifically, the entity types that currently support world grouping include: - Particles: :attr:`~newton.Model.particle_world` - Bodies: :attr:`~newton.Model.body_world` - Shapes: :attr:`~newton.Model.shape_world` - Joints: :attr:`~newton.Model.joint_world` - Articulations: :attr:`~newton.Model.articulation_world` - Equality Constraints: :attr:`~newton.Model.equality_constraint_world` The corresponding world grouping arrays for the example above are: .. testcode:: print("Body worlds:", model.body_world.numpy().tolist()) print("Shape worlds:", model.shape_world.numpy().tolist()) print("Joint worlds:", model.joint_world.numpy().tolist()) .. testoutput:: Body worlds: [0, 0, 1, 1] Shape worlds: [-1, 0, 0, 1, 1, -1] Joint worlds: [0, 0, 1, 1] .. _World starts: World Start Indices & Dimensions -------------------------------- In addition to the world grouping arrays, the :class:`~newton.Model` object will also contain Warp arrays that store the per-world starting indices for each entity type. These arrays include: - Particles: :attr:`~newton.Model.particle_world_start` - Bodies: :attr:`~newton.Model.body_world_start` - Shapes: :attr:`~newton.Model.shape_world_start` - Joints: :attr:`~newton.Model.joint_world_start` - Articulations: :attr:`~newton.Model.articulation_world_start` - Equality Constraints: :attr:`~newton.Model.equality_constraint_world_start` To handle the special case of joint entities, that vary in the number of DOFs, coordinates and constraints, the model also provides arrays that store the per-world starting indices in these specific dimensions: - Joint DOFs: :attr:`~newton.Model.joint_dof_world_start` - Joint Coordinates: :attr:`~newton.Model.joint_coord_world_start` - Joint Constraints: :attr:`~newton.Model.joint_constraint_world_start` All ``*_world_start`` arrays adopt a special format that facilitates accounting of the total number of entities in each world as well as the global world (index ``-1``) at the front and back of each per-entity array such as :attr:`~newton.Model.body_world`. Specifically, each ``*_world_start`` array contains ``world_count + 2`` entries, with the first ``world_count`` entries corresponding to starting indices of each ``world >= 0`` world, the second-to-last entry corresponding to the starting index of the global entities at the back (world index ``-1``), and the last entry corresponding to total number of entities or dimensions in the model. With this format, we can easily compute the number of entities per world by computing the difference between consecutive entries in these arrays (since they are essentially cumulative sums), as well as the total number of global entities by summing the first entry with the difference of the last two. Continuing the same example, we can compute the per-world shape counts as follows: .. testcode:: print("world_count:", model.world_count) # Shape start indices per world # Entries: [start_world_0, start_world_1, start_global_back, total_shapes] shape_start = model.shape_world_start.numpy() print("Shape starts:", shape_start.tolist()) # Compute per-world shape counts world_shape_counts = [ int(shape_start[i + 1] - shape_start[i]) for i in range(model.world_count) ] # Global shapes: those at the front (before start_world_0) plus at the back global_shape_count = int(shape_start[0]) + int(shape_start[-1] - shape_start[-2]) print("Shape counts per world:", world_shape_counts) print("Global shape count:", global_shape_count) .. testoutput:: world_count: 2 Shape starts: [1, 3, 5, 6] Shape counts per world: [2, 2] Global shape count: 2 .. _Convenience methods: Convenience Methods: ``add_world`` and ``replicate`` ---------------------------------------------------- While :meth:`~newton.ModelBuilder.begin_world` and :meth:`~newton.ModelBuilder.end_world` give full control, Newton provides two convenience methods for the most common multi-world patterns: **add_world**: adds a pre-built :class:`~newton.ModelBuilder` as a new world in a single call (combines ``begin_world`` / :meth:`~newton.ModelBuilder.add_builder` / ``end_world``): .. testcode:: import newton # Build a simple two-link arm arm = newton.ModelBuilder() link0 = arm.add_link(mass=1.0) j0 = arm.add_joint_fixed(parent=-1, child=link0) link1 = arm.add_link(mass=1.0) j1 = arm.add_joint_revolute(parent=link0, child=link1) arm.add_articulation(joints=[j0, j1]) arm.add_shape_box(body=link0, hx=0.1, hy=0.1, hz=0.1) arm.add_shape_box(body=link1, hx=0.1, hy=0.1, hz=0.1) # Create a scene with two instances of the same arm scene = newton.ModelBuilder() scene.add_ground_plane() scene.add_world(arm) scene.add_world(arm) multi_arm_model = scene.finalize() print("world_count:", multi_arm_model.world_count) .. testoutput:: world_count: 2 **replicate**: creates ``N`` copies of a builder, each as its own world, with optional spatial offsets. .. tip:: Using physical ``spacing`` to separate replicated worlds moves bodies away from the origin, which can reduce numerical stability. For visual separation, prefer using viewer-level world offsets (e.g. ``viewer.set_world_offsets()``) while keeping ``spacing=(0, 0, 0)`` so that all worlds remain at the origin in the physics simulation. .. testcode:: import newton arm = newton.ModelBuilder() link0 = arm.add_link(mass=1.0) j0 = arm.add_joint_fixed(parent=-1, child=link0) link1 = arm.add_link(mass=1.0) j1 = arm.add_joint_revolute(parent=link0, child=link1) arm.add_articulation(joints=[j0, j1]) scene = newton.ModelBuilder() scene.add_ground_plane() scene.replicate(arm, world_count=4, spacing=(2.0, 0.0, 0.0)) replicated_model = scene.finalize() print("world_count:", replicated_model.world_count) print("body_count:", replicated_model.body_count) .. testoutput:: world_count: 4 body_count: 8 .. _Per-world gravity: Per-World Gravity ----------------- Each world can have its own gravity vector, which is useful for simulating different environments (e.g., Earth gravity in one world, lunar gravity in another). Per-world gravity can be configured at build time via the ``gravity`` argument of :meth:`~newton.ModelBuilder.begin_world`, or modified at runtime via :meth:`~newton.Model.set_gravity`: .. note:: Global entities (world index ``-1``) use the gravity of world ``0``. Keep this in mind when mixing global and world-specific entities with different gravity vectors. .. testcode:: import warp as wp import newton robot_builder = newton.ModelBuilder() robot_builder.add_body(mass=1.0) scene = newton.ModelBuilder() scene.add_world(robot_builder) scene.add_world(robot_builder) model = scene.finalize() # Set different gravity for each world model.set_gravity((0.0, 0.0, -9.81), world=0) # Earth model.set_gravity((0.0, 0.0, -1.62), world=1) # Moon print("Gravity shape:", model.gravity.numpy().shape) .. testoutput:: Gravity shape: (2, 3) .. _World-entity partitioning: World-Entity GPU Thread Partitioning ------------------------------------ Another important use of world grouping is to facilitate partitioning of GPU thread grids according to both world indices and the number of entities per world, i.e. into 2D world-entity grids. For example: .. code-block:: python import warp as wp import newton @wp.kernel def world_body_2d_kernel( body_world_start: wp.array(dtype=wp.int32), body_qd: wp.array(dtype=wp.spatial_vectorf), ): world_id, body_world_id = wp.tid() world_start = body_world_start[world_id] num_bodies_in_world = body_world_start[world_id + 1] - world_start if body_world_id < num_bodies_in_world: global_body_id = world_start + body_world_id twist = body_qd[global_body_id] # ... perform computations on twist ... # Create model with multiple worlds builder = newton.ModelBuilder() # ... add entities to multiple worlds ... model = builder.finalize() # Define number of entities per world (e.g., bodies) body_world_start = model.body_world_start.numpy() num_bodies_per_world = [ body_world_start[i + 1] - body_world_start[i] for i in range(model.world_count) ] # Launch kernel with 2D grid: (world_count, max_entities_per_world) state = model.state() wp.launch( world_body_2d_kernel, dim=(model.world_count, max(num_bodies_per_world)), inputs=[model.body_world_start, state.body_qd], ) This kernel thread partitioning allows each thread to uniquely identify both the world it is operating on (via ``world_id``) and the relative entity index w.r.t that world (via ``body_world_id``). The world-relative index is useful in certain operations such as accessing the body-specific column of constraint Jacobian matrices in maximal-coordinate formulations, which are stored in contiguous blocks per world. This relative index can then be mapped to the global entity index within the model by adding the corresponding starting index from the ``*_world_start`` arrays. Note that in the simpler case of a homogeneous model consisting of identical worlds, the ``max(num_bodies_per_world)`` reduces to a constant value, and this effectively becomes a *batched* operation. For the more general heterogeneous case, the kernel needs to account for the varying number of entities per world, and an important pattern arises w.r.t 2D thread indexing and memory allocations that applies to all per-entity and per-world arrays. Essentially, ``sum(num_bodies_per_world)`` equals the total number of *world-local* bodies (i.e. ``body_world_start[-2] - body_world_start[0]``), which excludes any global entities (world index ``-1``). Note that ``model.body_count`` may be larger than this sum when global bodies are present, since it includes both world-local and global entities (see :attr:`~newton.Model.body_world_start` for the explicit distinction). The maximum ``max(num_bodies_per_world)`` determines the second dimension of the 2D thread grid used to launch the kernel. However, since different worlds may have different numbers of bodies, some threads in the 2D grid will be inactive for worlds with fewer bodies than the maximum. Therefore, kernels need to check whether the relative entity index is within bounds for the current world before performing any operations, as shown in the example above. This pattern of computing ``sum`` and ``max`` of per-world entity counts provides a consistent way to handle memory allocations and thread grid dimensions for heterogeneous multi-world simulations in Newton. See Also -------- * :class:`~newton.ModelBuilder` * :class:`~newton.Model` * :meth:`~newton.ModelBuilder.begin_world` * :meth:`~newton.ModelBuilder.end_world` * :meth:`~newton.ModelBuilder.add_world` * :meth:`~newton.ModelBuilder.replicate` * :meth:`~newton.Model.set_gravity` ================================================ FILE: docs/conf.py ================================================ # SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers # SPDX-License-Identifier: Apache-2.0 # Configuration file for the Sphinx documentation builder. # # For the full list of built-in configuration values, see the documentation: # https://www.sphinx-doc.org/en/master/usage/configuration.html import datetime import importlib import inspect import os import re import shutil import sys from pathlib import Path from typing import Any # Set environment variable to indicate we're in a Sphinx build. # This is inherited by subprocesses (e.g., Jupyter kernels run by nbsphinx). os.environ["NEWTON_SPHINX_BUILD"] = "1" # Determine the Git version/tag from CI environment variables. # 1. Check for GitHub Actions' variable. # 2. Check for GitLab CI's variable. # 3. Fallback to 'main' for local builds. github_version = os.environ.get("GITHUB_REF_NAME") or os.environ.get("CI_COMMIT_REF_NAME") or "main" # -- Project information ----------------------------------------------------- # https://www.sphinx-doc.org/en/master/usage/configuration.html#project-information project = "Newton Physics" copyright = f"{datetime.date.today().year}, The Newton Developers. Documentation licensed under CC-BY-4.0" author = "The Newton Developers" # Read version from pyproject.toml # TODO: When minimum Python version is >=3.11, replace with: # import tomllib # with open(project_root / "pyproject.toml", "rb") as f: # project_version = tomllib.load(f)["project"]["version"] project_root = Path(__file__).parent.parent try: with open(project_root / "pyproject.toml", encoding="utf-8") as f: content = f.read() project_section = re.search(r"^\[project\]\s*\n(.*?)(?=^\[|\Z)", content, re.MULTILINE | re.DOTALL) if not project_section: raise ValueError("Could not find [project] section in pyproject.toml") match = re.search(r'^version\s*=\s*"([^"]+)"', project_section.group(1), re.MULTILINE) if not match: raise ValueError("Could not find version in [project] section of pyproject.toml") project_version = match.group(1) except Exception as e: print(f"Error reading version from pyproject.toml: {e}", file=sys.stderr) sys.exit(1) release = project_version # -- Nitpicky mode ----------------------------------------------------------- # Set nitpicky = True to warn about all broken cross-references (e.g. missing # intersphinx targets, typos in :class:/:func:/:attr: roles, etc.). Useful for # auditing docs but noisy during regular development. nitpicky = False # -- General configuration --------------------------------------------------- # https://www.sphinx-doc.org/en/master/usage/configuration.html#general-configuration # Add docs/ and docs/_ext to Python import path so custom extensions and # sibling scripts (e.g. generate_api) can be imported. _docs_path = str(Path(__file__).parent) if _docs_path not in sys.path: sys.path.append(_docs_path) _ext_path = Path(__file__).parent / "_ext" if str(_ext_path) not in sys.path: sys.path.append(str(_ext_path)) extensions = [ "myst_parser", # Parse markdown files "nbsphinx", # Process Jupyter notebooks "sphinx.ext.autodoc", "sphinx.ext.napoleon", # Convert docstrings to reStructuredText "sphinx.ext.intersphinx", "sphinx.ext.autosummary", "sphinx.ext.extlinks", # Markup to shorten external links "sphinx.ext.githubpages", "sphinx.ext.doctest", # Test code snippets in docs "sphinx.ext.mathjax", # Math rendering support "sphinx.ext.linkcode", # Add GitHub source links to documentation "sphinxcontrib.mermaid", "sphinx_copybutton", "sphinx_design", "sphinx_tabs.tabs", "autodoc_filter", "autodoc_wpfunc", ] # -- nbsphinx configuration --------------------------------------------------- # Configure notebook execution mode for nbsphinx nbsphinx_execute = "auto" # Timeout for notebook execution (in seconds) nbsphinx_timeout = 600 # Allow errors in notebook execution (useful for development) nbsphinx_allow_errors = False templates_path = ["_templates"] exclude_patterns = [ "_build", "Thumbs.db", ".DS_Store", "sphinx-env/**", "sphinx-env", "**/site-packages/**", "**/lib/**", ] # nbsphinx requires pandoc to convert Jupyter notebooks. When pandoc is not # installed we exclude the notebook tutorials so the rest of the docs can still # be built locally without a hard error. CI workflows install pandoc explicitly # so published docs always include the tutorials. # # Set NEWTON_REQUIRE_PANDOC=1 to turn the missing-pandoc warning into an error # (used in CI to guarantee tutorials are never silently skipped). if shutil.which("pandoc") is None: if os.environ.get("NEWTON_REQUIRE_PANDOC", "") == "1": raise RuntimeError( "pandoc is required but not found. Install pandoc " "(https://pandoc.org/installing.html) or unset NEWTON_REQUIRE_PANDOC." ) exclude_patterns.append("tutorials/**") print( "WARNING: pandoc not found - Jupyter notebook tutorials will be " "skipped. Install pandoc (https://pandoc.org/installing.html) to " "build the complete documentation." ) intersphinx_mapping = { "python": ("https://docs.python.org/3", None), "numpy": ("https://numpy.org/doc/stable", None), "jax": ("https://docs.jax.dev/en/latest", None), "pytorch": ("https://docs.pytorch.org/docs/stable", None), "warp": ("https://nvidia.github.io/warp", None), "usd": ("https://docs.omniverse.nvidia.com/kit/docs/pxr-usd-api/latest", None), } # Map short USD type names (from ``from pxr import Usd``) to their fully-qualified # ``pxr.*`` paths so intersphinx can resolve them against the USD inventory. # Note: this only affects annotations processed by autodoc, not autosummary stubs. autodoc_type_aliases = { "Usd.Prim": "pxr.Usd.Prim", "Usd.Stage": "pxr.Usd.Stage", "UsdGeom.XformCache": "pxr.UsdGeom.XformCache", "UsdGeom.Mesh": "pxr.UsdGeom.Mesh", "UsdShade.Material": "pxr.UsdShade.Material", "UsdShade.Shader": "pxr.UsdShade.Shader", } source_suffix = { ".rst": "restructuredtext", ".md": "markdown", } extlinks = { "github": (f"https://github.com/newton-physics/newton/blob/{github_version}/%s", "%s"), } doctest_global_setup = """ from typing import Any import numpy as np import warp as wp import newton # Suppress warnings by setting warp_showwarning to an empty function def empty_warning(*args, **kwargs): pass wp.utils.warp_showwarning = empty_warning wp.config.quiet = True wp.init() """ # -- Autodoc configuration --------------------------------------------------- # put type hints inside the description instead of the signature (easier to read) autodoc_typehints = "description" # default argument values of functions will be not evaluated on generating document autodoc_preserve_defaults = True autodoc_typehints_description_target = "documented" toc_object_entries_show_parents = "hide" autodoc_default_options = { "members": True, "member-order": "groupwise", "special-members": "__init__", "undoc-members": False, "exclude-members": "__weakref__", "imported-members": True, "autosummary": True, } # fixes errors with Enum docstrings autodoc_inherit_docstrings = False # Mock imports for modules that are not installed by default autodoc_mock_imports = ["jax", "torch", "paddle"] autosummary_generate = True autosummary_ignore_module_all = False autosummary_imported_members = True # -- Options for HTML output ------------------------------------------------- # https://www.sphinx-doc.org/en/master/usage/configuration.html#options-for-html-output html_title = "Newton Physics" html_theme = "pydata_sphinx_theme" html_static_path = ["_static"] html_css_files = ["custom.css"] html_show_sourcelink = False # PyData theme configuration html_theme_options = { # Remove navigation from the top navbar # "navbar_start": ["navbar-logo"], # "navbar_center": [], # "navbar_end": ["search-button"], # Navigation configuration # "font_size": "14px", # or smaller "navigation_depth": 1, "show_nav_level": 1, "show_toc_level": 2, "collapse_navigation": False, # Show the indices in the sidebar "show_prev_next": False, "use_edit_page_button": False, "logo": { "image_light": "_static/newton-logo-light.png", "image_dark": "_static/newton-logo-dark.png", "text": f"Newton Physics ({release})", "alt_text": "Newton Physics Logo", }, # Keep the right-hand page TOC on by default, but remove it on the # solver API page where several wide comparison tables benefit from the # extra content width. "secondary_sidebar_items": { "**": ["page-toc", "edit-this-page", "sourcelink"], "api/newton_solvers": [], }, # "primary_sidebar_end": ["indices.html", "sidebar-ethical-ads.html"], } html_sidebars = {"**": ["sidebar-nav-bs.html"], "index": ["sidebar-nav-bs.html"]} # Version switcher configuration for multi-version docs on GitHub Pages # See: https://pydata-sphinx-theme.readthedocs.io/en/stable/user_guide/version-dropdown.html # Determine if we're in a CI build and which version _is_ci = os.environ.get("GITHUB_ACTIONS") == "true" _is_release = os.environ.get("GITHUB_REF", "").startswith("refs/tags/v") # Configure version switcher html_theme_options["switcher"] = { "json_url": "https://newton-physics.github.io/newton/switcher.json", "version_match": release if _is_release else "dev", } # Add version switcher to navbar html_theme_options["navbar_end"] = ["theme-switcher", "version-switcher", "navbar-icon-links"] # Footer configuration — show copyright (includes CC-BY-4.0 notice) html_theme_options["footer_start"] = ["copyright"] html_theme_options["footer_end"] = ["theme-version"] # Disable switcher JSON validation during local builds (file not accessible locally) if not _is_ci: html_theme_options["check_switcher"] = False # -- Math configuration ------------------------------------------------------- # MathJax configuration for proper LaTeX rendering mathjax3_config = { "tex": { "packages": {"[+]": ["amsmath", "amssymb", "amsfonts"]}, "inlineMath": [["$", "$"], ["\\(", "\\)"]], "displayMath": [["$$", "$$"], ["\\[", "\\]"]], "processEscapes": True, "processEnvironments": True, "tags": "ams", "macros": { "RR": "{\\mathbb{R}}", "bold": ["{\\mathbf{#1}}", 1], "vec": ["{\\mathbf{#1}}", 1], }, }, "options": { "processHtmlClass": ("tex2jax_process|mathjax_process|math|output_area"), "ignoreHtmlClass": "annotation", }, } # -- Linkcode configuration -------------------------------------------------- # create back links to the Github Python source file # called automatically by sphinx.ext.linkcode def linkcode_resolve(domain: str, info: dict[str, str]) -> str | None: """ Determine the URL corresponding to Python object using introspection """ if domain != "py": return None if not info["module"]: return None module_name = info["module"] # Only handle newton modules if not module_name.startswith("newton"): return None try: # Import the module and get the object module = importlib.import_module(module_name) if "fullname" in info: # Get the specific object (function, class, etc.) obj_name = info["fullname"] if hasattr(module, obj_name): obj = getattr(module, obj_name) else: return None else: # No specific object, link to the module itself obj = module # Get the file where the object is actually defined source_file = None line_number = None try: source_file = inspect.getfile(obj) # Get line number if possible try: _, line_number = inspect.getsourcelines(obj) except (TypeError, OSError): pass except (TypeError, OSError): # Check if it's a Warp function with wrapped original function if hasattr(obj, "func") and callable(obj.func): try: original_func = obj.func source_file = inspect.getfile(original_func) try: _, line_number = inspect.getsourcelines(original_func) except (TypeError, OSError): pass except (TypeError, OSError): pass # If still no source file, fall back to the module file if not source_file: try: source_file = inspect.getfile(module) except (TypeError, OSError): return None if not source_file: return None # Convert absolute path to relative path from project root project_root = os.path.dirname(os.path.dirname(__file__)) rel_path = os.path.relpath(source_file, project_root) # Normalize path separators for URLs rel_path = rel_path.replace("\\", "/") # Add line fragment if we have a line number line_fragment = f"#L{line_number}" if line_number else "" # Construct GitHub URL github_base = "https://github.com/newton-physics/newton" return f"{github_base}/blob/{github_version}/{rel_path}{line_fragment}" except (ImportError, AttributeError, TypeError): return None def _copy_viser_client_into_output_static(*, outdir: Path) -> None: """Ensure the Viser web client assets are available at `{outdir}/_static/viser/`. This avoids relying on repo-relative `html_static_path` entries (which can break under `uv`), and avoids writing generated assets into `docs/_static` in the working tree. """ dest_dir = outdir / "_static" / "viser" src_candidates: list[Path] = [] # Repo checkout layout (most common for local builds). src_candidates.append(project_root / "newton" / "_src" / "viewer" / "viser" / "static") # Installed package layout (e.g. building docs from an environment where `newton` is installed). try: import newton # noqa: PLC0415 src_candidates.append(Path(newton.__file__).resolve().parent / "_src" / "viewer" / "viser" / "static") except Exception: pass src_dir = next((p for p in src_candidates if (p / "index.html").is_file()), None) if src_dir is None: # Don't hard-fail doc builds; the viewer docs can still build without the embedded client. expected = ", ".join(str(p) for p in src_candidates) print( f"Warning: could not find Viser client assets to copy. Expected `index.html` under one of: {expected}", file=sys.stderr, ) return dest_dir.mkdir(parents=True, exist_ok=True) shutil.copytree(src_dir, dest_dir, dirs_exist_ok=True) def _on_builder_inited(_app: Any) -> None: outdir = Path(_app.builder.outdir) _copy_viser_client_into_output_static(outdir=outdir) def setup(app: Any) -> None: # Regenerate API .rst files so builds always reflect the current public API. from generate_api import generate_all # noqa: PLC0415 generate_all() app.connect("builder-inited", _on_builder_inited) ================================================ FILE: docs/faq.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 Frequently Asked Questions (FAQ) ================================ This FAQ addresses general questions about Newton. For technical questions and answers, please refer to `GitHub Discussions `_. What is Newton? --------------- Newton is an open-source, GPU-accelerated, extensible, and differentiable physics engine for robotics built on `NVIDIA Warp `_, initially focused on high-performance robot learning and `MuJoCo Warp `_ integration. Newton supports OpenUSD, URDF, and MJCF asset formats and provides multiple solver backends within a unified architecture for simulation, learning, and extensibility. Newton is a `Linux Foundation `_ project initiated by `Disney Research `_, `Google DeepMind `_, and `NVIDIA `_. The project is community-built and maintained under the permissive `Apache-2.0 license `_. What is the difference between Warp and Newton? ----------------------------------------------- `Warp `_ is a Python framework for writing high-performance, differentiable GPU kernels for physics simulation and spatial computing. Newton is a full physics engine built on Warp that adds high-level simulation APIs, interchangeable solvers, and asset I/O for robotics. What is the difference between ``warp.sim`` and Newton? ------------------------------------------------------- ``warp.sim`` was the predecessor to Newton, developed by NVIDIA as a module in Warp. It was deprecated in Warp 1.8 and removed in Warp 1.10. See the :doc:`migration` to Newton. Does Newton support coupling of solvers for multiphysics or co-simulation? -------------------------------------------------------------------------- Yes, Newton is explicitly designed to be extensible with multiple solver implementations for rich multiphysics scenarios. Newton provides APIs for users to implement coupling between solvers, and we have successfully demonstrated one-way coupling in examples such as cloth manipulation by a robotic arm and a quadruped walking through non-rigid terrain. Two-way coupling and implicit coupling between select solvers are on the Newton roadmap. Does Newton support MuJoCo simulation? -------------------------------------- Newton leverages `MuJoCo Warp `_ as a key solver, which is a reimplementation of MuJoCo in Warp for GPU acceleration, developed and maintained by Google DeepMind and NVIDIA. Newton can import assets in MJCF, URDF, and OpenUSD formats, making it compatible with MuJoCo at both asset and solver levels. Is Newton exposed and accessible in Isaac Lab and Isaac Sim? ------------------------------------------------------------ Yes, an experimental Newton integration is available in Isaac Lab and under active development. Initial training environments include quadruped and biped locomotion, and basic manipulation. Read more on `the integration `_. Newton integration with Isaac Sim as a physics backend is under development. Is Newton a standalone framework? --------------------------------- Yes, Newton and its modern Python API can be used as a standalone simulation framework. See the :doc:`api/newton` or the `Quickstart Guide `_ for more information. Does Newton provide visualization capabilities? ----------------------------------------------- Newton provides basic visualization for debugging purposes. Read more in the :doc:`guide/visualization` Guide. For rich real-time graphics, users commonly pair Newton with Isaac Lab, which provides advanced rendering. Users can also export simulation outputs to a time-sampled USD that can be visualized, for example, in `NVIDIA Omniverse `_ or `Isaac Sim `_. How can I contribute to Newton? ------------------------------- Newton welcomes community contributions. Please see the `Contribution Guide `_ and :doc:`guide/development` Guide for more information. Can I use Newton to develop my own custom solver? ------------------------------------------------- Yes, Newton is designed to be highly extensible, supporting custom solvers, integrators, and numerical methods within its modular architecture. What is PhysX? -------------- `PhysX `_ is an open-source, multi-physics SDK that provides scalable simulation across CPUs and GPUs, widely used for industrial digital-twin simulation in Omniverse, and robotics simulation in Isaac Sim and Isaac Lab. It features a unified simulation framework for reduced-coordinate articulations and rigid bodies, deformable bodies and cloth (FEM), fluids/particles (PBD), vehicle dynamics, and character controllers. Will Newton replace PhysX? -------------------------- No, the two engines serve different primary goals: Newton targets robot learning and extensible multiphysics with differentiability, while PhysX focuses on industrial digital-twin simulation as a mature, multi-platform real-time physics SDK that is actively maintained and updated. Isaac Lab's experimental Newton integration does not support PhysX, but Isaac Lab plans to continue supporting PhysX as a simulation backend. Can PhysX work in Newton? ------------------------- No. However, different approaches for supporting PhysX as a Newton solver option are under consideration. ================================================ FILE: docs/generate_api.py ================================================ # SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers # SPDX-License-Identifier: Apache-2.0 """Generate concise API .rst files for selected modules. This helper scans a list of *top-level* modules, reads their ``__all__`` lists (and falls back to public attributes if ``__all__`` is missing), and writes one reStructuredText file per module with an ``autosummary`` directive. When Sphinx later builds the documentation (with ``autosummary_generate = True``), individual stub pages will be created automatically for every listed symbol. The generated files live in ``docs/api/`` (git-ignored by default). Usage (from the repository root): python docs/generate_api.py Adjust ``MODULES`` below to fit your project. """ from __future__ import annotations import importlib import inspect import pkgutil import shutil import sys from pathlib import Path from types import ModuleType import warp as wp # type: ignore # ----------------------------------------------------------------------------- # Configuration # ----------------------------------------------------------------------------- # Add project root to import path so that `import newton` works when the script # is executed from the repository root without installing the package. REPO_ROOT = Path(__file__).resolve().parent.parent sys.path.insert(0, str(REPO_ROOT)) # Modules for which we want API pages. Feel free to modify. MODULES: list[str] = [ "newton", "newton.geometry", "newton.ik", "newton.math", "newton.selection", "newton.sensors", "newton.solvers", "newton.usd", "newton.utils", "newton.viewer", ] # Output directory (relative to repo root) OUTPUT_DIR = REPO_ROOT / "docs" / "api" # Where autosummary should place generated stub pages (relative to each .rst # file). Keeping them alongside the .rst files avoids clutter elsewhere. TOCTREE_DIR = "_generated" # sub-folder inside OUTPUT_DIR # ----------------------------------------------------------------------------- # Helpers # ----------------------------------------------------------------------------- def public_symbols(mod: ModuleType) -> list[str]: """Return the list of public names for *mod* (honours ``__all__``).""" if hasattr(mod, "__all__") and isinstance(mod.__all__, list | tuple): return list(mod.__all__) def is_public(name: str) -> bool: if name.startswith("_"): return False return not inspect.ismodule(getattr(mod, name)) return sorted(filter(is_public, dir(mod))) def _is_solver_only_module(mod: ModuleType) -> bool: """Return True when the module only exposes its solver class.""" names = getattr(mod, "__all__", None) public = list(names) if isinstance(names, (list, tuple)) else public_symbols(mod) return len(public) == 1 and public[0].startswith("Solver") def solver_submodule_pages() -> list[str]: """Return solver submodules that expose more than the solver class.""" modules: list[str] = [] solvers_pkg = importlib.import_module("newton._src.solvers") public_solvers = importlib.import_module("newton.solvers") for info in pkgutil.iter_modules(solvers_pkg.__path__): if not info.ispkg: continue if not hasattr(public_solvers, info.name): continue internal_name = f"{solvers_pkg.__name__}.{info.name}" try: mod = importlib.import_module(internal_name) except Exception: # Optional dependency missing; skip doc generation for this solver. continue if _is_solver_only_module(mod): continue public_name = f"newton.solvers.{info.name}" modules.append(public_name) return modules def write_module_page(mod_name: str) -> None: """Create an .rst file for *mod_name* under *OUTPUT_DIR*.""" is_solver_submodule = mod_name.startswith("newton.solvers.") and mod_name != "newton.solvers" if is_solver_submodule: sub_name = mod_name.split(".", 2)[2] module = importlib.import_module(f"newton._src.solvers.{sub_name}") else: module = importlib.import_module(mod_name) symbols = public_symbols(module) if is_solver_submodule: # Keep solver classes centralized in newton.solvers. symbols = [name for name in symbols if not name.startswith("Solver")] classes: list[str] = [] functions: list[str] = [] constants: list[str] = [] modules: list[str] = [] for name in symbols: attr = getattr(module, name) # ------------------------------------------------------------------ # Class-like objects # ------------------------------------------------------------------ if inspect.isclass(attr) or wp.types.type_is_struct(attr): classes.append(name) continue # ------------------------------------------------------------------ # Constants / simple values # ------------------------------------------------------------------ if wp.types.type_is_value(type(attr)) or isinstance(attr, str): constants.append(name) continue # ------------------------------------------------------------------ # Submodules # ------------------------------------------------------------------ if inspect.ismodule(attr): modules.append(name) continue # ------------------------------------------------------------------ # Everything else → functions section # ------------------------------------------------------------------ functions.append(name) title = mod_name underline = "=" * len(title) lines: list[str] = [ ".. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers", ".. SPDX-License-Identifier: CC-BY-4.0", "", title, underline, "", ] # Module docstring if available doc = (module.__doc__ or "").strip() if doc: lines.extend([doc, ""]) lines.extend([f".. py:module:: {mod_name}", f".. currentmodule:: {mod_name}", ""]) # Render a simple bullet list of submodules (no autosummary/toctree) to # avoid generating stub pages that can cause duplicate descriptions. if modules and not is_solver_submodule: modules.sort() lines.extend( [ ".. toctree::", " :hidden:", "", ] ) for sub in modules: modname = f"{mod_name}.{sub}" docname = modname.replace(".", "_") lines.append(f" {docname}") lines.append("") lines.extend([".. rubric:: Submodules", ""]) # Link to sibling generated module pages without creating autosummary stubs. for sub in modules: modname = f"{mod_name}.{sub}" docname = modname.replace(".", "_") lines.append(f"- :doc:`{modname} <{docname}>`") lines.append("") if classes: classes.sort() lines.extend([".. rubric:: Classes", ""]) if is_solver_submodule: for cls in classes: lines.extend([f".. autoclass:: {cls}", ""]) else: lines.extend( [ ".. autosummary::", f" :toctree: {TOCTREE_DIR}", " :nosignatures:", "", ] ) lines.extend([f" {cls}" for cls in classes]) lines.append("") if functions: functions.sort() lines.extend([".. rubric:: Functions", ""]) if is_solver_submodule: for fn in functions: lines.extend([f".. autofunction:: {fn}", ""]) else: lines.extend( [ ".. autosummary::", f" :toctree: {TOCTREE_DIR}", " :signatures: long", "", ] ) lines.extend([f" {fn}" for fn in functions]) lines.append("") if constants: constants.sort() lines.extend( [ ".. rubric:: Constants", "", ".. list-table::", " :header-rows: 1", "", " * - Name", " - Value", ] ) for const in constants: value = getattr(module, const, "?") # unpack the warp scalar value, we can remove this # when the warp.types.scalar_base supports __str__() if type(value) in wp.types.scalar_types: value = getattr(value, "value", value) lines.extend( [ f" * - ``{const}``", f" - ``{value}``", ] ) lines.append("") outfile = OUTPUT_DIR / f"{mod_name.replace('.', '_')}.rst" outfile.parent.mkdir(parents=True, exist_ok=True) outfile.write_text("\n".join(lines), encoding="utf-8") print(f"Wrote {outfile.relative_to(REPO_ROOT)} ({len(symbols)} symbols)") # ----------------------------------------------------------------------------- # Public entry point # ----------------------------------------------------------------------------- def generate_all() -> None: """Regenerate all API ``.rst`` files under :data:`OUTPUT_DIR`.""" # delete previously generated files shutil.rmtree(OUTPUT_DIR, ignore_errors=True) extra_solver_modules = solver_submodule_pages() all_modules = MODULES + [mod for mod in extra_solver_modules if mod not in MODULES] for mod in all_modules: write_module_page(mod) # ----------------------------------------------------------------------------- # Script entry # ----------------------------------------------------------------------------- if __name__ == "__main__": generate_all() print("\nDone. Add docs/api/index.rst to your TOC or glob it in.") ================================================ FILE: docs/guide/development.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 Development =========== This document is a guide for developers who want to contribute to the project or understand its internal workings in more detail. Please refer to `CONTRIBUTING.md `_ for how to best contribute to Newton and relevant legal information (CLA). Installation ------------ For regular end-user installation, see the :doc:`installation` guide. To install Newton from source for development or contribution, first clone the repository: .. code-block:: console git clone https://github.com/newton-physics/newton.git cd newton Method 1: Using uv (Recommended) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Install `uv `_ if you don't have it already: .. tab-set:: :sync-group: os .. tab-item:: macOS / Linux :sync: linux .. code-block:: console curl -LsSf https://astral.sh/uv/install.sh | sh .. tab-item:: Windows :sync: windows .. code-block:: console powershell -ExecutionPolicy ByPass -c "irm https://astral.sh/uv/install.ps1 | iex" Then create a local project environment with the ``dev`` dependency extras: .. code-block:: console uv sync --extra dev After syncing, the ``dev`` extras are available to all ``uv run`` commands without needing to pass ``--extra dev`` each time. For example, to list all available examples: .. code-block:: console uv run -m newton.examples See the :ref:`extra-dependencies` section of the installation guide for a description of all available extras. Method 2: Using pip in a Virtual Environment ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ To manually manage a virtual environment, create and activate one first: .. tab-set:: :sync-group: os .. tab-item:: macOS / Linux :sync: linux .. code-block:: console python -m venv .venv source .venv/bin/activate .. tab-item:: Windows (console) :sync: windows .. code-block:: console python -m venv .venv .venv\Scripts\activate.bat .. tab-item:: Windows (PowerShell) :sync: windows-ps .. code-block:: console python -m venv .venv .venv\Scripts\Activate.ps1 Then locally install Newton in editable mode with its development dependencies: .. code-block:: console pip install -e ".[dev]" --extra-index-url https://pypi.nvidia.com/ The ``--extra-index-url`` flag points pip to the NVIDIA package index, which is required to find ``warp-lang`` versions newer than those available on PyPI. Python Dependency Management ---------------------------- uv lockfile management ^^^^^^^^^^^^^^^^^^^^^^ When using uv, the `lockfile `__ (``uv.lock``) is used to resolve project dependencies into exact versions for reproducibility among different machines. We maintain a lockfile in the root of the repository that pins exact versions of all dependencies and their transitive dependencies. Sometimes, a dependency in the lockfile needs to be updated to a newer version. This can be done by running ``uv lock -P ``: .. code-block:: console uv lock -P warp-lang --prerelease allow uv lock -P mujoco-warp The ``--prerelease allow`` flag is needed for dependencies that use pre-release versions (e.g. ``warp-lang``). uv also provides a command to update all dependencies in the lockfile: .. code-block:: console uv lock -U Remember to commit ``uv.lock`` after running a command that updates the lockfile. Running the tests ----------------- The Newton test suite supports both ``uv`` and standard ``venv`` workflows, and by default runs in up to eight parallel processes. The tests can be run in a serial manner with ``--serial-fallback``. Pass ``--help`` to either run method below to see all available flags. .. tab-set:: :sync-group: env .. tab-item:: uv :sync: uv .. code-block:: console # install development extras and run tests uv run --extra dev -m newton.tests .. tab-item:: venv :sync: venv .. code-block:: console # install dev extras (including testing & coverage deps) python -m pip install -e ".[dev]" # run tests python -m newton.tests Most tests run when the ``dev`` extras are installed. The tests using PyTorch to run inference on an RL policy are skipped if the ``torch`` dependency is not installed. In order to run these tests, include the ``torch-cu12`` or ``torch-cu13`` extras matching your NVIDIA driver's CUDA support: .. tab-set:: :sync-group: env .. tab-item:: uv :sync: uv .. code-block:: console # install development extras and run tests uv run --extra dev --extra torch-cu12 -m newton.tests .. tab-item:: venv :sync: venv .. code-block:: console # install both dev and torch-cu12 extras (need to pull from PyTorch CUDA 12.8 wheel index) python -m pip install --extra-index-url https://download.pytorch.org/whl/cu128 -e ".[dev,torch-cu12]" # run tests python -m newton.tests Specific Newton examples can be tested in isolation via the ``-k`` argument: .. tab-set:: :sync-group: env .. tab-item:: uv :sync: uv .. code-block:: console # test the basic_shapes example uv run --extra dev -m newton.tests.test_examples -k test_basic.example_basic_shapes .. tab-item:: venv :sync: venv .. code-block:: console # test the basic_shapes example python -m newton.tests.test_examples -k test_basic.example_basic_shapes To generate a coverage report: .. tab-set:: :sync-group: env .. tab-item:: uv :sync: uv .. code-block:: console # append the coverage flags: uv run --extra dev -m newton.tests --coverage --coverage-html htmlcov .. tab-item:: venv :sync: venv .. code-block:: console # append the coverage flags and make sure `coverage[toml]` is installed (it comes in `[dev]`) python -m newton.tests --coverage --coverage-html htmlcov The file ``htmlcov/index.html`` can be opened with a web browser to view the coverage report. Code formatting and linting --------------------------- `Ruff `_ is used for Python linting and code formatting. `pre-commit `_ can be used to ensure that local code complies with Newton's checks. From the top of the repository, run: .. tab-set:: :sync-group: env .. tab-item:: uv :sync: uv .. code-block:: console uvx pre-commit run -a .. tab-item:: venv :sync: venv .. code-block:: console python -m pip install pre-commit pre-commit run -a To automatically run pre-commit hooks with ``git commit``: .. tab-set:: :sync-group: env .. tab-item:: uv :sync: uv .. code-block:: console uvx pre-commit install .. tab-item:: venv :sync: venv .. code-block:: console pre-commit install The hooks can be uninstalled with ``pre-commit uninstall``. Typos ----- To proactively catch spelling mistakes, Newton uses the `typos `_ tool. Typos scans source files for common misspellings and is integrated into our pre-commit hooks, so spelling errors in both code and documentation are flagged when you run or install pre-commit (see above). You can also run ``typos`` manually if needed. Refer to the `typos documentation `_ for more details on usage and configuration options. Dealing with false positives ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Typos may occasionally flag legitimate project-specific terminology, domain terms, or variable names as misspellings (false positives). To handle these, the Newton codebase configures typos in ``pyproject.toml`` at the repository root. False positives are managed as follows: - **File exclusions:** The ``[tool.typos]`` section includes ``files.extend-exclude`` to ignore matching files and directories, such as ``examples/assets`` and specific model or asset file types (e.g., ``*.urdf``, ``*.usd``). - **Word allowlist:** Words or acronyms that would otherwise be flagged can be listed in ``[tool.typos.default.extend-words]`` (e.g., ``ba``, ``HAA``). - **Identifier allowlist:** Specific identifiers, such as variable or constant names, can be declared in ``[tool.typos.default.extend-identifiers]`` (e.g., ``PNGs``). When typos reports a word that is valid within the Newton codebase, you can add it to the appropriate section in ``pyproject.toml`` to suppress future warnings. After updating, re-run typos (or pre-commit) to confirm that the word is ignored. Use these options to keep the codebase clean while ensuring needed flexibility for accepted project-specific words and identifiers. License headers --------------- Every source file in the repository must carry a 2-line `SPDX `_ license header. The project's Apache-2.0 license is in ``LICENSE.md`` at the repository root, and additional and third-party license texts are available in the ``newton/licenses`` directory, so no further boilerplate is required in individual files. The required headers depend on the file type: - **Python files** (``.py``): .. code-block:: python # SPDX-FileCopyrightText: Copyright (c) The Newton Developers # SPDX-License-Identifier: Apache-2.0 - **Documentation files** (``.rst``) — CC-BY-4.0: .. code-block:: rst .. SPDX-FileCopyrightText: Copyright (c) The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 - **Jupyter notebooks** (``.ipynb``) — CC-BY-4.0 (plain text in the first cell, no comment prefix): .. code-block:: text SPDX-FileCopyrightText: Copyright (c) The Newton Developers SPDX-License-Identifier: CC-BY-4.0 Use the year the file was **first created**. Do not update the year when modifying an existing file, and do not use year ranges — git history is the authoritative record of when changes were made. A CI check (``pr_license_check.yml``) enforces headers on every pull request using `Apache SkyWalking Eyes `_. To run the license checks locally with Docker before pushing: .. code-block:: console # Check Python source headers (Apache-2.0) docker run -it --rm -v $(pwd):/github/workspace apache/skywalking-eyes header check # Check documentation headers (CC-BY-4.0) docker run -it --rm -v $(pwd):/github/workspace apache/skywalking-eyes -c .licenserc-docs.yaml header check Using a local Warp installation with uv --------------------------------------- Use the following steps to run Newton with a local build of Warp: .. code-block:: console uv venv source .venv/bin/activate uv sync --extra dev uv pip install -e "warp-lang @ ../warp" The Warp initialization message should then properly reflect the local Warp installation instead of the locked version, e.g. when running ``python -m newton.examples basic_pendulum``. .. _building-the-documentation: Building the documentation -------------------------- To build the documentation locally, ensure you have the documentation dependencies installed. .. tab-set:: :sync-group: env .. tab-item:: uv :sync: uv .. code-block:: console rm -rf docs/_build uv run --extra docs --extra sim sphinx-build -j auto -W -b html docs docs/_build/html .. tab-item:: venv :sync: venv .. code-block:: console python -m pip install -e ".[docs]" cd path/to/newton/docs && make html The built documentation will be available in ``docs/_build/html``. .. note:: The documentation build requires `pandoc `_ for converting Jupyter notebooks. While ``pypandoc_binary`` is included in the ``[docs]`` dependencies, some systems may require pandoc to be installed separately: - **Ubuntu/Debian:** ``sudo apt-get install pandoc`` - **macOS:** ``brew install pandoc`` - **Windows:** Download from https://pandoc.org/installing.html or ``choco install pandoc`` Serving the documentation locally ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ After building the documentation, you can serve it locally using the ``docs/serve.py`` script. This is particularly useful for testing interactive features like the Viser 3D visualizations in the tutorial notebooks, which require proper MIME types for WebAssembly and JavaScript modules. .. tab-set:: :sync-group: env .. tab-item:: uv :sync: uv .. code-block:: console uv run docs/serve.py .. tab-item:: venv :sync: venv .. code-block:: console python docs/serve.py Then open http://localhost:8000 in your browser. You can specify a custom port with ``--port``: .. tab-set:: :sync-group: env .. tab-item:: uv :sync: uv .. code-block:: console uv run docs/serve.py --port 8080 .. tab-item:: venv :sync: venv .. code-block:: console python docs/serve.py --port 8080 .. note:: Using Python's built-in ``http.server`` or simply opening the HTML files directly will not work correctly for the interactive Viser visualizations, as they require specific CORS headers and MIME types that ``serve.py`` provides. Documentation Versioning ------------------------ Newton's documentation is versioned and hosted on GitHub Pages. Multiple versions are available simultaneously, with a version switcher dropdown in the navigation bar. How It Works ^^^^^^^^^^^^ The ``gh-pages`` branch contains versioned documentation in subdirectories: .. code-block:: text / ├── index.html # Redirects to /stable/ ├── switcher.json # Version manifest for dropdown ├── stable/ # Copy of latest release ├── latest/ # Dev docs from main branch ├── 1.1.0/ # Release versions └── 1.0.0/ Two GitHub Actions workflows manage deployment: - **docs-dev.yml**: Deploys to ``/latest/`` on every push to ``main`` - **docs-release.yml**: Deploys to ``/X.Y.Z/`` and updates ``/stable/`` on version tags Deploying Documentation ^^^^^^^^^^^^^^^^^^^^^^^ **Dev docs** are deployed automatically when changes are pushed to ``main``. **Release docs** are deployed when a version tag is pushed: .. code-block:: bash git tag v1.0.0 git push origin v1.0.0 Only strict semver tags (``vX.Y.Z``) trigger release deployments. Pre-release tags like ``v1.0.0-rc.1`` are ignored. Manual Operations ^^^^^^^^^^^^^^^^^ **Removing a version** (rare): 1. Check out the ``gh-pages`` branch 2. Delete the version directory (e.g., ``rm -rf 1.0.0``) 3. Edit ``switcher.json`` to remove the entry 4. Commit and push **Rebuilding all docs** (disaster recovery): Check out each version tag, build its docs with Sphinx, and deploy to the corresponding directory on ``gh-pages``. Update ``switcher.json`` after each version using ``scripts/ci/update_docs_switcher.py``. API documentation ----------------- Newton's API reference is auto-generated from the ``__all__`` lists of its public modules. The script ``docs/generate_api.py`` produces reStructuredText files under ``docs/api/`` (git-ignored) that Sphinx processes via ``autosummary`` to create individual pages for every public symbol. Whenever you add, remove, or rename a public symbol in one of the public modules (``newton``, ``newton.geometry``, ``newton.solvers``, ``newton.sensors``, etc.), regenerate the API pages: .. tab-set:: :sync-group: env .. tab-item:: uv :sync: uv .. code-block:: console uv run python docs/generate_api.py .. tab-item:: venv :sync: venv .. code-block:: console python docs/generate_api.py After running the script, rebuild the documentation to verify the result (see :ref:`building-the-documentation` above). .. note:: Only symbols listed in a module's ``__all__`` (or, as a fallback, its public attributes) are included. If a new class or function in ``newton/_src/`` should be visible to users, re-export it through the appropriate public module first. Testing documentation code snippets ----------------------------------- The ``doctest`` Sphinx builder is used to ensure that code snippets in the documentation remain up-to-date. The doctests can be run with: .. tab-set:: :sync-group: env .. tab-item:: uv :sync: uv .. code-block:: console uv run --extra docs --extra sim sphinx-build -j auto -W -b doctest docs docs/_build/doctest .. tab-item:: venv :sync: venv .. code-block:: console python -m sphinx -j auto -W -b doctest docs docs/_build/doctest For more information, see the `sphinx.ext.doctest `__ documentation. Changelog --------- Newton maintains a ``CHANGELOG.md`` at the repository root. When a pull request modifies user-facing behavior, add an entry under the ``[Unreleased]`` section in the appropriate category: - **Added** — new features - **Changed** — changes to existing functionality (include migration guidance) - **Deprecated** — features that will be removed (include migration guidance, e.g. "Deprecate ``Model.geo_meshes`` in favor of ``Model.shapes``") - **Removed** — removed features (include migration guidance) - **Fixed** — bug fixes Use imperative present tense ("Add X", not "Added X") and keep entries concise. Internal implementation details (refactors, CI tweaks) that do not affect users should **not** be listed. Style Guide ----------- - Follow PEP 8 for Python code. - Use Google-style docstrings (compatible with Napoleon extension). - Write clear, concise commit messages. - Keep pull requests focused on a single feature or bug fix. - Use kebab-case instead of snake_case for command line arguments, e.g. ``--use-cuda-graph`` instead of ``--use_cuda_graph``. Writing examples ---------------- Examples live in ``newton/examples//example__.py`` (e.g. ``newton/examples/basic/example_basic_pendulum.py``). Each file defines an ``Example`` class with the following interface: .. code-block:: python class Example: def __init__(self, viewer, args): """Build the model, create solver/state/control, and set up the viewer.""" ... def step(self): """Advance the simulation by one frame (typically with substeps).""" ... def render(self): """Update the viewer with the current state.""" ... def test_final(self): """Validate the final simulation state. Required for CI.""" ... def test_post_step(self): """Optional per-step validation, called after every step() in test mode.""" ... Every example **must** implement ``test_final()`` (or ``test_post_step()``, or both). The test harness runs examples with ``--viewer null --test`` and calls these methods to verify simulation correctness. An example that implements neither will raise ``NotImplementedError`` in CI. Discovery and registration ^^^^^^^^^^^^^^^^^^^^^^^^^^ Examples are discovered automatically: any file matching ``newton/examples//example_*.py`` is picked up by ``newton.examples.get_examples()``. The short name used on the command line is the filename without the ``example_`` prefix and ``.py`` extension (e.g. ``basic_pendulum``). New examples must also be registered in the examples ``README.md`` with a ``python -m newton.examples `` command and a 320x320 jpg screenshot. .. tab-set:: :sync-group: env .. tab-item:: uv :sync: uv .. code-block:: console # list all available examples uv run -m newton.examples # run an example by short name uv run -m newton.examples basic_pendulum # run in headless test mode (used by CI) uv run -m newton.examples basic_pendulum --viewer null --test .. tab-item:: venv :sync: venv .. code-block:: console # list all available examples python -m newton.examples # run an example by short name python -m newton.examples basic_pendulum # run in headless test mode (used by CI) python -m newton.examples basic_pendulum --viewer null --test Asset version pinning --------------------- Several Newton tests and examples rely on external assets hosted in separate Git repositories. To ensure that any given Newton commit always downloads the same asset versions, each repository is pinned to a specific commit SHA. The pinned revisions are defined as constants in ``newton/_src/utils/download_assets.py``: - ``NEWTON_ASSETS_REF`` — pinned SHA for the ``newton-assets`` repository - ``MENAGERIE_REF`` — pinned SHA for the ``mujoco_menagerie`` repository Updating pinned revisions ^^^^^^^^^^^^^^^^^^^^^^^^^ When upstream assets change and the new versions need to be adopted: 1. Look up the new commit SHA from the asset repository. 2. Update the corresponding ``*_REF`` constant in ``download_assets.py``. 3. Run the full test suite to verify that no tests break with the new assets. 4. Commit the SHA update together with any test adjustments. Overriding the pinned revision ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ The ``download_asset()`` function accepts a ``ref`` parameter that overrides the default pinned SHA. Roadmap and Future Work ----------------------- (Placeholder for future roadmap and planned features) - Advanced solver coupling - More comprehensive sensor models - Expanded robotics examples See the `GitHub Discussions `__ and `GitHub Roadmap `__ for ongoing feature planning. Benchmarking with airspeed velocity ----------------------------------- The Newton repository contains a benchmarking suite implemented using the `airspeed velocity `__ framework. The full set of benchmarks is intended to be run on a machine with a CUDA-capable GPU. To get started, install airspeed velocity from PyPI: .. code-block:: console python -m pip install asv .. tip:: With ``uv``, airspeed velocity can be run without installing it into the project environment by using ``uvx``: .. code-block:: console uvx --with virtualenv asv run --launch-method spawn ... If airspeed velocity has not been previously run on the machine, it will need to be initialized with: .. code-block:: console asv machine --yes To run the benchmarks, run the following command from the root of the repository: .. tab-set:: :sync-group: shell .. tab-item:: Unix :sync: unix .. code-block:: console asv run --launch-method spawn main^! .. tab-item:: Windows :sync: windows .. code-block:: console asv run --launch-method spawn main^^! .. note:: On Windows CMD, the ``^`` character is an escape character, so it must be doubled (``^^``) to be interpreted literally. The benchmarks discovered by airspeed velocity are in the ``asv/benchmarks`` directory. This command runs the benchmark code from the ``asv/benchmarks`` directory against the code state of the ``main`` branch. Note that the benchmark definitions themselves are not checked out from different branches—only the code being benchmarked is. Benchmarks can also be run against a range of commits using the ``commit1..commit2`` syntax. This is useful for comparing performance across several recent changes: .. tab-set:: :sync-group: shell .. tab-item:: Unix :sync: unix .. code-block:: console asv run --launch-method spawn HEAD~4..HEAD .. tab-item:: Windows :sync: windows .. code-block:: console asv run --launch-method spawn HEAD~4..HEAD Note that the older commit has to come first. Commit hashes can be used instead of relative references: .. tab-set:: :sync-group: shell .. tab-item:: Unix :sync: unix .. code-block:: console asv run --launch-method spawn abc1234..def5678 .. tab-item:: Windows :sync: windows .. code-block:: console asv run --launch-method spawn abc1234..def5678 Running benchmarks standalone ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Benchmark files can also be run directly as Python scripts, without the airspeed velocity harness. This is useful for quick iteration during development since it skips the environment setup that airspeed velocity performs. Each benchmark file under ``asv/benchmarks/`` supports a ``--bench`` flag to select specific benchmark classes: .. tab-set:: :sync-group: env .. tab-item:: uv :sync: uv .. code-block:: console uv run python asv/benchmarks/simulation/bench_mujoco.py --bench FastAllegro .. tab-item:: venv :sync: venv .. code-block:: console python asv/benchmarks/simulation/bench_mujoco.py --bench FastAllegro When ``--bench`` is omitted, all benchmarks in the file are run. The ``--bench`` flag can be repeated to select multiple benchmarks: .. tab-set:: :sync-group: env .. tab-item:: uv :sync: uv .. code-block:: console uv run python asv/benchmarks/simulation/bench_mujoco.py --bench FastAllegro --bench FastG1 .. tab-item:: venv :sync: venv .. code-block:: console python asv/benchmarks/simulation/bench_mujoco.py --bench FastAllegro --bench FastG1 Tips for writing benchmarks ^^^^^^^^^^^^^^^^^^^^^^^^^^^ Rather than running the entire benchmark suite, use the ``--bench BENCH, -b BENCH`` flag to filter the benchmarks to just the ones under development: .. tab-set:: :sync-group: shell .. tab-item:: Unix :sync: unix .. code-block:: console asv run --launch-method spawn main^! --bench FastG1 .. tab-item:: Windows :sync: windows .. code-block:: console asv run --launch-method spawn main^^! --bench FastG1 The most time-consuming benchmarks are those that measure the time it takes to load and run one frame of the example starting from an empty kernel cache. These benchmarks have names ending with ``time_load``. It is sometimes convenient to exclude these benchmarks from running by using the following command: .. tab-set:: :sync-group: shell .. tab-item:: Unix :sync: unix .. code-block:: console asv run --launch-method spawn main^! -b '^(?!.*time_load$).*' .. tab-item:: Windows :sync: windows .. code-block:: console asv run --launch-method spawn main^^! -b "^^(?!.*time_load$).*" While airspeed velocity has built-in mechanisms to determine automatically how to collect measurements, it is often useful to manually specify benchmark attributes like ``repeat`` and ``number`` to control the number of times a benchmark is run and the number of times a benchmark is repeated. .. code-block:: python class PretrainedSimulate: repeat = 3 number = 1 As the airspeed documentation on `benchmark attributes `__ notes, the ``setup`` and ``teardown`` methods are not run between the ``number`` iterations that make up a sample. These benchmark attributes should be tuned to ensure that the benchmark runs in a reasonable amount of time while also ensuring that the benchmark is run a sufficient number of times to get a statistically meaningful result. The ``--durations all`` flag can be passed to the ``asv run`` command to show the durations of all benchmarks, which is helpful for ensuring that a single benchmark is not requiring an abnormally long amount of time compared to the other benchmarks. Release process --------------- See :doc:`release` for the full release workflow, including versioning, branching strategy, testing criteria, and publication steps. .. toctree:: :hidden: release ================================================ FILE: docs/guide/installation.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 .. currentmodule:: newton Installation ============ This guide covers the recommended way to install Newton from PyPI. For installing from source or using ``uv``, see the :doc:`development` guide. .. _system-requirements: System Requirements ------------------- Minimum Requirements ^^^^^^^^^^^^^^^^^^^^ .. list-table:: :widths: 25 30 45 :header-rows: 1 * - Requirement - Minimum - Notes * - Python - 3.10 - 3.11+ recommended * - OS - Linux (x86-64, aarch64), Windows (x86-64), or macOS (CPU only) - macOS has no GPU acceleration; see :ref:`cpu-limitations` below * - NVIDIA GPU - Compute capability 5.0+ (Maxwell) - Any GeForce GTX 9xx or newer * - NVIDIA Driver - 545 or newer (CUDA 12) - 550 or newer (CUDA 12.4) recommended for best performance * - CUDA - 12, 13 - No local CUDA Toolkit required; `Warp `__ bundles its own runtime CUDA Compatibility ^^^^^^^^^^^^^^^^^^ .. list-table:: :widths: 25 75 :header-rows: 1 * - CUDA Version - Notes * - 12.3+ - Required for reliable CUDA graph capture * - 12.4+ - Recommended for best performance * - 13 - Supported Tested Configurations ^^^^^^^^^^^^^^^^^^^^^ Newton releases are tested on the following configurations: .. list-table:: :widths: 25 75 :header-rows: 1 * - Component - Configuration * - OS - Ubuntu 22.04/24.04 (x86-64 + ARM64), Windows, macOS (CPU only) * - GPU - NVIDIA Ada Lovelace, Blackwell * - Python - 3.10, 3.12, 3.14 (import-only) * - CUDA - 12, 13 Platform-Specific Requirements ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ **Linux aarch64 (ARM64)** On ARM64 Linux systems (such as NVIDIA Jetson Thor and DGX Spark), installing the ``examples`` extras currently requires X11 development libraries to build ``imgui_bundle`` from source: .. code-block:: console sudo apt-get update sudo apt-get install -y libx11-dev libxrandr-dev libxinerama-dev libxcursor-dev libxi-dev libgl1-mesa-dev .. _cpu-limitations: CPU-Only Limitations ^^^^^^^^^^^^^^^^^^^^ Newton can run on CPU (including macOS), but the following features require an NVIDIA GPU and are unavailable in CPU-only mode: - **SDF collision** — signed-distance-field computation requires CUDA (``wp.Volume`` is GPU-only). - **Mesh-mesh contacts** — SDF-based mesh-mesh collision is silently skipped on CPU. - **Hydroelastic contacts** — depends on the SDF system. - **Tiled camera sensor** — GPU-accelerated raytraced rendering. - **Implicit MPM solver** — designed for GPU execution with CUDA graph support. - **Tile-based VBD solve** — uses GPU tile API; gracefully disabled on CPU. Installing Newton ----------------- Basic installation: .. code-block:: console pip install newton Install with the ``examples`` extra to run the built-in examples (includes simulation and visualization dependencies): .. code-block:: console pip install "newton[examples]" We recommend installing Newton inside a virtual environment to avoid conflicts with other packages: .. tab-set:: :sync-group: os .. tab-item:: macOS / Linux :sync: linux .. code-block:: console python -m venv .venv source .venv/bin/activate pip install "newton[examples]" .. tab-item:: Windows (console) :sync: windows .. code-block:: console python -m venv .venv .venv\Scripts\activate.bat pip install "newton[examples]" .. tab-item:: Windows (PowerShell) :sync: windows-ps .. code-block:: console python -m venv .venv .venv\Scripts\Activate.ps1 pip install "newton[examples]" .. note:: Users on Python 3.10 may experience issues when installing ``imgui_bundle`` (a dependency of the ``examples`` extra). If you encounter installation errors, we recommend upgrading to a later Python version, or follow the :doc:`development` guide to install Newton using ``uv``. Running Examples ^^^^^^^^^^^^^^^^ After installing Newton with the ``examples`` extra, run an example with: .. code-block:: console python -m newton.examples basic_pendulum Run an example that runs RL policy inference. Choose the extra matching your NVIDIA driver's CUDA support (``torch-cu12`` for CUDA 12.x, ``torch-cu13`` for CUDA 13.x) and the corresponding pytorch wheel (e.g, ``128`` for CUDA 12.8); run ``nvidia-smi`` to check the supported CUDA version (shown in the top-right corner of the output): .. code-block:: console pip install newton[torch-cu12] --extra-index-url https://download.pytorch.org/whl/cu128 python -m newton.examples robot_anymal_c_walk See a list of all available examples: .. code-block:: console python -m newton.examples Quick Start ^^^^^^^^^^^ After installing Newton, you can build models, create solvers, and run simulations directly from Python. A typical workflow looks like this: .. code-block:: python import warp as wp import newton # Build a model builder = newton.ModelBuilder() builder.add_mjcf("robot.xml") # or add_urdf() / add_usd() builder.add_ground_plane() model = builder.finalize() # Create a solver and allocate state solver = newton.solvers.SolverMuJoCo(model) state_0 = model.state() state_1 = model.state() control = model.control() contacts = model.contacts() newton.eval_fk(model, model.joint_q, model.joint_qd, state_0) # Step the simulation for step in range(1000): state_0.clear_forces() model.collide(state_0, contacts) solver.step(state_0, state_1, control, contacts, 1.0 / 60.0 / 4.0) state_0, state_1 = state_1, state_0 For robot-learning workflows with parallel environments (as used by `Isaac Lab `_), you can replicate a robot template across many worlds and step them all simultaneously on the GPU: .. code-block:: python # Build a single robot template template = newton.ModelBuilder() template.add_mjcf("humanoid.xml") # Replicate into parallel worlds builder = newton.ModelBuilder() builder.replicate(template, world_count=1024) builder.add_ground_plane() model = builder.finalize() # The solver steps all 1024 worlds in parallel solver = newton.solvers.SolverMuJoCo(model) See the :doc:`/guide/overview` guide and :doc:`/integrations/isaac-lab` for more details. .. _extra-dependencies: Extra Dependencies ------------------ Newton's only mandatory dependency is `NVIDIA Warp `_. Additional optional dependency sets are defined in ``pyproject.toml``: .. list-table:: :widths: 20 80 :header-rows: 1 * - Set - Purpose * - ``sim`` - Simulation dependencies, including MuJoCo * - ``importers`` - Asset import and mesh processing dependencies * - ``remesh`` - Remeshing dependencies (Open3D, pyfqmr) for :func:`newton.utils.remesh_mesh` * - ``examples`` - Dependencies for running examples, including visualization (includes ``sim`` + ``importers``) * - ``torch-cu12`` - PyTorch (CUDA 12) for running RL policy examples (includes ``examples``) * - ``torch-cu13`` - PyTorch (CUDA 13) for running RL policy examples (includes ``examples``) * - ``notebook`` - Jupyter notebook support with Rerun visualization (includes ``examples``) * - ``dev`` - Dependencies for development and testing (includes ``examples``) * - ``docs`` - Dependencies for building the documentation Some extras transitively include others. For example, ``examples`` pulls in both ``sim`` and ``importers``, and ``dev`` pulls in ``examples``. You only need to install the most specific set for your use case. .. _versioning: Versioning ---------- Newton currently uses the following versioning scheme. This may evolve depending on the needs of the project and its users. Newton uses a **major.minor.micro** versioning scheme, similar to `Python itself `__: * New **major** versions are reserved for major reworks of Newton causing disruptive incompatibility (or reaching the 1.0 milestone). * New **minor** versions are feature releases with a new set of features. May contain deprecations, breaking changes, and removals. * New **micro** versions are bug-fix releases. In principle, there are no new features. The first release of a new minor version always includes the micro version (e.g., ``1.1.0``), though informal references may shorten it (e.g., "Newton 1.1"). Prerelease Versions ^^^^^^^^^^^^^^^^^^^ In addition to stable releases, Newton uses the following prerelease version formats: * **Development builds** (``major.minor.micro.dev0``): The version string used in the source code on the main branch between stable releases (e.g., ``1.1.0.dev0``). * **Release candidates** (``major.minor.microrcN``): Pre-release versions for QA testing before a stable release, starting with ``rc1`` and incrementing (e.g., ``1.1.0rc1``). Usually not published to PyPI. Prerelease versions should be considered unstable and are not subject to the same compatibility guarantees as stable releases. Next Steps ---------- - Run ``python -m newton.examples`` to see all available examples and check out the :doc:`visualization` guide to learn how to interact with the example simulations. - Check out the :doc:`development` guide to learn how to contribute to Newton, or how to use alternative installation methods. ================================================ FILE: docs/guide/overview.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 Newton Physics Documentation ============================ .. image:: /_static/newton-banner.jpg :alt: Newton Physics Engine Banner :align: center :class: newton-banner .. raw:: html
**Newton** is a GPU-accelerated, extensible, and differentiable physics simulation engine designed for robotics, research, and advanced simulation workflows. Built on top of NVIDIA Warp and integrating MuJoCo Warp, Newton provides high-performance simulation, modern Python APIs, and a flexible architecture for both users and developers. Key Features ------------ * **GPU-accelerated**: Leverages NVIDIA Warp for fast, scalable simulation. * **Multiple solver implementations**: XPBD, VBD, MuJoCo, Featherstone, SemiImplicit. * **Modular design**: Easily extendable with new solvers and components. * **Differentiable**: Supports differentiable simulation for machine learning and optimization. * **Rich Import/Export**: Load models from URDF, MJCF, USD, and more. * **Open Source**: Maintained by Disney Research, Google DeepMind, and NVIDIA. .. admonition:: Learn More :class: tip Start with the :doc:`introduction tutorial ` for a hands-on walkthrough. For a deeper conceptual introduction, see the `DeepWiki Newton Physics page `__. .. _guide-core-concepts: Core Concepts ------------- .. mermaid:: :config: {"theme": "forest", "themeVariables": {"lineColor": "#76b900"}} flowchart LR subgraph Authoring["Model Authoring"] direction LR P[Python API] --> A[ModelBuilder] subgraph Imported["Imported assets"] direction TB U[URDF] M[MJCF] S[USD] end U --> G[Importer] M --> G S --> G G --> A end B[Model] subgraph Loop["Simulation Loop"] direction LR C[State] --> D[Solver] J[Control] --> D E[Contacts] --> D D --> C2[Updated state] end subgraph Outputs["Outputs"] direction TB K[Sensors] F[Viewer] end A -->|builds| B B --> C B --> J B --> E C2 --> K E --> K C2 --> F - :class:`~newton.ModelBuilder`: The entry point for constructing simulation models from primitives or imported assets. - :class:`~newton.Model`: Encapsulates the physical structure, parameters, and configuration of the simulation world, including bodies, joints, shapes, and physical properties. - :class:`~newton.State`: Represents the dynamic state at a given time, including positions and velocities that solvers update each step. Optional :doc:`extended attributes <../concepts/extended_attributes>` store derived quantities such as rigid-body accelerations for sensors. - :class:`~newton.Contacts`: Stores the active contact set produced by :meth:`Model.collide `, with optional extended attributes such as contact forces for sensing and analysis. - :class:`~newton.Control`: Encodes control inputs such as joint targets and forces applied during the simulation loop. - :doc:`Solver <../api/newton_solvers>`: Advances the simulation by integrating physics, handling contacts, and enforcing constraints. Newton provides multiple solver backends, including XPBD, VBD, MuJoCo, Featherstone, and SemiImplicit. - :doc:`Sensors <../concepts/sensors>`: Compute observations from :class:`~newton.State`, :class:`~newton.Contacts`, sites, and shapes. Many sensors rely on optional :doc:`extended attributes <../concepts/extended_attributes>` that store derived solver outputs. - **Importer**: Loads models from external formats via :meth:`~newton.ModelBuilder.add_urdf`, :meth:`~newton.ModelBuilder.add_mjcf`, and :meth:`~newton.ModelBuilder.add_usd`. - :doc:`Viewer `: Visualizes the simulation in real time or offline. Simulation Loop --------------- 1. Build or import a model with :class:`~newton.ModelBuilder`. 2. Finalize the builder into a :class:`~newton.Model`. 3. Create any sensors, then allocate one or more :class:`~newton.State` objects plus :class:`~newton.Control` inputs and :class:`~newton.Contacts`. 4. Call :meth:`Model.collide ` to populate the contact set for the current state. 5. Step a :doc:`solver <../api/newton_solvers>` using the current state, control, and contacts. 6. Update sensors, inspect outputs, render, or export the results. Quick Links ----------- - :doc:`installation` — Setup Newton and run a first example in a couple of minutes - :doc:`tutorials` — Browse the guide's tutorial landing page - :doc:`Introduction tutorial ` — Walk through a first hands-on tutorial - :doc:`../faq` — Frequently asked questions - :doc:`development` — For developers and code contributors - :doc:`../api/newton` — Full API reference :ref:`Full Index ` ================================================ FILE: docs/guide/release.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2026 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 Release Process =============== This document describes how to prepare, publish, and follow up on a Newton release. It is intended for release engineers and maintainers. Overview -------- Newton follows PEP 440 versioning as described in the :ref:`versioning ` section of the installation guide. Releases are published to `PyPI `__ and documentation is deployed to `GitHub Pages `__. Version source of truth ^^^^^^^^^^^^^^^^^^^^^^^ The version string lives in the ``[project]`` table of ``pyproject.toml``. All other version references (PyPI metadata, documentation) are derived from this file. At runtime, ``newton/_version.py`` reads the version from installed package metadata via ``importlib.metadata``. Dependency versioning strategy ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ ``pyproject.toml`` specifies **minimum** compatible versions (e.g. ``warp-lang>=1.12.0``). ``uv.lock`` pins the **latest known-good** versions for reproducible installs. Exception: on the **release branch**, ``mujoco`` and ``mujoco-warp`` use **compatible-release** pins (e.g. ``mujoco~=3.5.0``) to allow patch updates while locking the minor version. MuJoCo follows `semantic versioning from 3.5.0 onward `__, so patch releases are safe to pick up automatically. ``main`` uses a version floor like other dependencies. .. _deprecation-timeline: Deprecation timeline ^^^^^^^^^^^^^^^^^^^^ Following `Warp's deprecation policy `__, a deprecated feature is maintained for **two full minor release cycles** after deprecation (e.g. deprecated in 1.2.0 → removed in 1.4.0). Deprecations and removals only happen in minor releases, never in patch releases. Pre-release planning -------------------- .. list-table:: :widths: 5 95 :header-rows: 0 * - ☐ - Determine target version (``X.Y.Z``). * - ☐ - Confirm dependency versions and availability: warp-lang, mujoco, mujoco-warp, newton-usd-schemas, newton-actuators. * - ☐ - Set timeline: code freeze → RC1 → testing window → GA. * - ☐ - Conduct public API audit: - Review all new/changed symbols since the last release for unintended breaking changes. - Verify deprecated symbols carry proper deprecation warnings and migration guidance (see :ref:`deprecation-timeline`). - Confirm new public API has complete docstrings and is included in Sphinx docs (run ``docs/generate_api.py``). * - ☐ - Communicate the timeline to the community. Code freeze and release branch creation --------------------------------------- .. list-table:: :widths: 5 95 :header-rows: 0 * - ☐ - Create ``release-X.Y`` branch from ``main`` and push it. * - ☐ - On **main**: bump the version in ``pyproject.toml`` to ``X.(Y+1).0.dev0`` and run ``docs/generate_api.py``. * - ☐ - On **release-X.Y**: bump the version in ``pyproject.toml`` to ``X.Y.ZrcN`` and run ``docs/generate_api.py``. * - ☐ - On **release-X.Y**: update dependencies in ``pyproject.toml`` from dev to RC versions where applicable, then regenerate ``uv.lock`` (``uv lock``) and commit it. * - ☐ - Push tag ``vX.Y.Zrc1``. This triggers the ``release.yml`` workflow (build wheel → PyPI publish with manual approval). * - ☐ - RC1 published to PyPI (approve in GitHub environment). Release candidate stabilization ------------------------------- Bug fixes merge to ``main`` first, then are cherry-picked to ``release-X.Y``. Cherry-pick relevant commits from ``main`` onto a feature branch and open a pull request targeting ``release-X.Y`` — never push directly to the release branch. For each new RC (``rc2``, ``rc3``, …) bump the version in ``pyproject.toml`` and run ``docs/generate_api.py``, then tag and push. Resolve any cherry-pick conflicts or missing dependent cherry-picks that cause CI failures before tagging. .. _testing-criteria: Testing criteria ^^^^^^^^^^^^^^^^ The release engineer and maintainers decide which issues must be fixed before GA and which can ship as known issues documented in the release notes. Features explicitly marked **experimental** have a lower bar — regressions in experimental APIs do not necessarily block a release. As a guideline, an RC is typically ready for GA when: - All examples run without crashes, excessive warnings, or visual artifacts (``uv run -m newton.examples ``). - Testing covers **Windows and Linux**, **all supported Python versions**, and both **latest and minimum-spec CUDA drivers** (see :ref:`system requirements ` in the installation guide). - PyPI installation of the RC works in a clean environment: ``pip install`` succeeds, ``import newton`` works, and examples and tests can be run from the installed wheel (``pip install newton==X.Y.ZrcN``). - No unexpected regressions compared to the previous release have been identified. .. list-table:: :widths: 5 95 :header-rows: 0 * - ☐ - All release-targeted fixes cherry-picked from ``main``. * - ☐ - :ref:`Testing criteria ` satisfied. * - ☐ - No outstanding release-blocking issues. .. _final-release: Final GA release ---------------- Before proceeding, obtain explicit go/no-go approval from the maintainers. Do not start the final release steps until sign-off is confirmed. All steps below are performed on the **release-X.Y** branch unless noted otherwise. .. list-table:: :widths: 5 95 :header-rows: 0 * - ☐ - Go/no-go approval obtained from maintainers. * - ☐ - Finalize ``CHANGELOG.md``: rename ``[Unreleased]`` → ``[X.Y.Z] - YYYY-MM-DD``. Review the entries for: - **Missing entries** — cross-check merged PRs since the last GA release (or patch) to catch changes that were not recorded in the changelog. - **Redundant entries** — consolidate or remove duplicates for changes within the same release period (e.g. a bug fix for a feature added in the same cycle should not appear as both an "Added" and a "Fixed" entry). * - ☐ - Update ``README.md`` documentation links to point to versioned URLs (e.g. ``/X.Y.Z/guide.html`` instead of ``/latest/``). * - ☐ - Verify all dependency pins in ``pyproject.toml`` use stable (non-pre-release) versions. * - ☐ - Regenerate ``uv.lock`` (``uv lock``) and verify that no pre-release dependencies remain in the lock file. * - ☐ - Bump the version in ``pyproject.toml`` to ``X.Y.Z`` (remove the RC suffix) and run ``docs/generate_api.py``. * - ☐ - Commit and push tag ``vX.Y.Z``. Automated workflows trigger: - ``release.yml``: builds wheel, publishes to PyPI (requires manual approval), creates a draft GitHub Release. - ``docs-release.yml``: deploys docs to ``/X.Y.Z/`` and ``/stable/`` on gh-pages, updates ``switcher.json``. * - ☐ - PyPI publish approved and verified: ``pip install newton==X.Y.Z``. * - ☐ - GitHub Release un-drafted and published. * - ☐ - Docs live at ``/X.Y.Z/`` and ``/stable/``: verify links and version switcher. * - ☐ - Release announcement posted. Post-release ------------ .. list-table:: :widths: 5 95 :header-rows: 0 * - ☐ - Merge back the changelog from ``release-X.Y`` to ``main``: move entries included in the release from ``[Unreleased]`` to a new ``[X.Y.Z]`` section. (``[Unreleased]`` is a permanent header in the changelog that always exists on ``main``.) * - ☐ - Verify PyPI installation works in a clean environment. * - ☐ - Verify published docs render correctly. Patch releases -------------- Patch releases continue cherry-picking fixes to the existing ``release-X.Y`` branch. For example, ``1.0.1`` follows ``1.0.0``. Follow the same :ref:`final-release` flow — bump version, update changelog, tag, and push. There is no need to create a new branch or bump ``main``. ================================================ FILE: docs/guide/tutorials.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 Tutorials ========= This section contains tutorials to help you get started with Newton. You can also explore the examples in the ``newton/examples/`` directory for more use cases. .. toctree:: :maxdepth: 2 :caption: Tutorial Notebooks /tutorials/00_introduction ================================================ FILE: docs/guide/visualization.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 .. currentmodule:: newton Visualization ============= Newton provides multiple viewer backends for different visualization needs, from real-time rendering to offline recording and external integrations. Common Interface ---------------- All viewer backends inherit from :class:`~newton.viewer.ViewerBase` and share a common interface: **Core loop methods** — every viewer uses the same simulation loop pattern: - :meth:`~newton.viewer.ViewerBase.set_model` — assign a :class:`~newton.Model` and optionally limit the number of rendered worlds with ``max_worlds`` - :meth:`~newton.viewer.ViewerBase.begin_frame` — start a new frame with the current simulation time - :meth:`~newton.viewer.ViewerBase.log_state` — update the viewer with the current :class:`~newton.State` (body transforms, particle positions, etc.) - :meth:`~newton.viewer.ViewerBase.end_frame` — finish the frame and present it - :meth:`~newton.viewer.ViewerBase.is_running` — check whether the viewer is still open (useful as a loop condition) - :meth:`~newton.viewer.ViewerBase.is_paused` — check whether the simulation is paused (toggled with ``SPACE`` in :class:`~newton.viewer.ViewerGL`) - :meth:`~newton.viewer.ViewerBase.close` — close the viewer and release resources **Camera and layout:** - :meth:`~newton.viewer.ViewerBase.set_camera` — set camera position, pitch, and yaw - :meth:`~newton.viewer.ViewerBase.set_world_offsets` — arrange multiple worlds in a grid with a given spacing along each axis **Custom visualization** — draw debug overlays on top of the simulation: - :meth:`~newton.viewer.ViewerBase.log_lines` — draw line segments (e.g. rays, normals, force vectors) - :meth:`~newton.viewer.ViewerBase.log_points` — draw a point cloud (e.g. contact locations, particle positions) - :meth:`~newton.viewer.ViewerBase.log_contacts` — visualize :class:`~newton.Contacts` as normal lines at contact points - :meth:`~newton.viewer.ViewerBase.log_gizmo` — display a transform gizmo (position + orientation axes) - :meth:`~newton.viewer.ViewerBase.log_scalar` / :meth:`~newton.viewer.ViewerBase.log_array` — log numeric data for backend-specific visualization (e.g. time-series plots in Rerun) **Limiting rendered worlds**: When training with many parallel environments, rendering all worlds can impact performance. All viewers support the ``max_worlds`` parameter to limit visualization to a subset of environments: .. testcode:: viewer-max-worlds builder = newton.ModelBuilder() body = builder.add_body(mass=1.0) model = builder.finalize() # Only render the first 4 environments viewer = newton.viewer.ViewerNull() viewer.set_model(model, max_worlds=4) Real-time Viewers ----------------- OpenGL Viewer ~~~~~~~~~~~~~ Newton provides :class:`~newton.viewer.ViewerGL`, a simple OpenGL viewer for interactive real-time visualization of simulations. The viewer requires pyglet (version >= 2.1.6) and imgui_bundle (version >= 1.92.0) to be installed. Constructor parameters: - ``width``: Window width in pixels (default: ``1920``) - ``height``: Window height in pixels (default: ``1080``) - ``vsync``: Enable vertical sync (default: ``False``) - ``headless``: Run without a visible window, useful for off-screen rendering (default: ``False``) .. code-block:: python viewer = newton.viewer.ViewerGL() viewer.set_model(model) # at every frame: viewer.begin_frame(sim_time) viewer.log_state(state) viewer.end_frame() # check if the simulation is paused (toggled with SPACE key): if viewer.is_paused(): pass # simulation stepping is paused **Interactive forces and input:** :meth:`~newton.viewer.ViewerGL.apply_forces` applies viewer-driven forces (object picking with right-click, wind) to the simulation state. Call it each frame before stepping the solver: .. code-block:: python viewer.apply_forces(state) solver.step(model, state, ...) :meth:`~newton.viewer.ViewerGL.is_key_down` queries whether a key is currently pressed. Keys can be specified as single-character strings (``'w'``), special key names (``'space'``, ``'escape'``), or pyglet key constants: .. code-block:: python if viewer.is_key_down('r'): state = model.state() # reset **Headless mode and frame capture:** In headless mode (``headless=True``), the viewer renders off-screen without opening a window. Use :meth:`~newton.viewer.ViewerGL.get_frame` to retrieve the rendered image as a GPU array: .. code-block:: python viewer = newton.viewer.ViewerGL(headless=True) viewer.set_model(model) viewer.begin_frame(sim_time) viewer.log_state(state) viewer.end_frame() # Returns a wp.array with shape (height, width, 3), dtype wp.uint8 frame = viewer.get_frame() **Custom UI panels:** :meth:`~newton.viewer.ViewerGL.register_ui_callback` adds custom imgui UI elements to the viewer. The ``position`` parameter controls placement: ``"side"`` (default), ``"stats"``, ``"free"``, or ``"panel"``: .. code-block:: python def my_ui(ui): import imgui_bundle.imgui as imgui imgui.text("Hello from custom UI!") viewer.register_ui_callback(my_ui, position="side") Keyboard shortcuts when working with the OpenGL Viewer: .. list-table:: Keyboard Shortcuts :header-rows: 1 * - Key(s) - Description * - ``W``, ``A``, ``S``, ``D`` (or arrow keys) + mouse drag - Move the camera like in a FPS game * - ``H`` - Toggle Sidebar * - ``SPACE`` - Pause/continue the simulation * - ``Right Click`` - Pick objects **Troubleshooting:** If you encounter an OpenGL context error on Linux with Wayland: .. code-block:: text OpenGL.error.Error: Attempt to retrieve context when no valid context Set the PyOpenGL platform before running: .. code-block:: bash export PYOPENGL_PLATFORM=glx This is a known issue when running OpenGL applications on Wayland display servers. Recording and Offline Viewers ----------------------------- Recording to File (ViewerFile) ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ The :class:`~newton.viewer.ViewerFile` backend records simulation data to JSON or binary files for later replay or analysis. This is useful for capturing simulations for debugging, sharing results, or post-processing. **File formats:** - ``.json``: Human-readable JSON format (no additional dependencies) - ``.bin``: Binary CBOR2 format (more efficient, requires ``cbor2`` package) To use binary format, install the optional dependency: .. code-block:: bash pip install cbor2 **Recording a simulation:** .. testcode:: viewer-file import tempfile, os builder = newton.ModelBuilder() body = builder.add_body(mass=1.0) model = builder.finalize() state = model.state() # Record to JSON format (human-readable, no extra dependencies) output_path = os.path.join(tempfile.mkdtemp(), "simulation.json") viewer = newton.viewer.ViewerFile(output_path) viewer.set_model(model) sim_time = 0.0 for _ in range(5): viewer.begin_frame(sim_time) viewer.log_state(state) viewer.end_frame() sim_time += 1.0 / 60.0 # Close to save the recording viewer.close() .. testoutput:: viewer-file :options: +NORMALIZE_WHITESPACE, +ELLIPSIS ... **Loading and playing back recordings:** Use :class:`~newton.viewer.ViewerFile` to load a recording, then restore the model and state for a given frame. Use :class:`~newton.viewer.ViewerGL` (or another rendering viewer) to visualize. .. testcode:: viewer-file # Load a recording for playback viewer_file = newton.viewer.ViewerFile(output_path) viewer_file.load_recording() # Restore the model and state from the recording model = newton.Model() viewer_file.load_model(model) print(f"Frames: {viewer_file.get_frame_count()}") state = model.state() viewer_file.load_state(state, frame_id=0) # frame index in [0, get_frame_count()) .. testoutput:: viewer-file Frames: 5 For a complete example with UI controls for scrubbing and playback, see ``newton/examples/basic/example_replay_viewer.py``. Key parameters: - ``output_path``: Path to the output file (format determined by extension: .json or .bin) - ``auto_save``: If True, automatically save periodically during recording (default: ``True``) - ``save_interval``: Number of frames between auto-saves when auto_save=True (default: ``100``) - ``max_history_size``: Maximum number of frames to keep in memory (default: ``None`` for unlimited) Rendering to USD ~~~~~~~~~~~~~~~~ Instead of rendering in real-time, you can also render the simulation as a time-sampled USD stage to be visualized in Omniverse or other USD-compatible tools using the :class:`~newton.viewer.ViewerUSD` backend. Constructor parameters: - ``output_path``: Path to the output USD file - ``fps``: Frames per second for time sampling (default: ``60``) - ``up_axis``: USD up axis, ``"Y"`` or ``"Z"`` (default: ``"Z"``) - ``num_frames``: Maximum number of frames to record, or ``None`` for unlimited (default: ``100``) - ``scaling``: Uniform scaling applied to the scene root (default: ``1.0``) .. code-block:: python viewer = newton.viewer.ViewerUSD(output_path="simulation.usd", fps=60, up_axis="Z") viewer.set_model(model) # at every frame: viewer.begin_frame(sim_time) viewer.log_state(state) viewer.end_frame() # Save and close the USD file viewer.close() External Integrations --------------------- Rerun Viewer ~~~~~~~~~~~~ The :class:`~newton.viewer.ViewerRerun` backend integrates with the `rerun `_ visualization library, enabling real-time or offline visualization with advanced features like time scrubbing and data inspection. **Installation**: Requires the rerun-sdk package: .. code-block:: bash pip install rerun-sdk Constructor parameters: - ``app_id``: Application ID for Rerun (default: ``"newton-viewer"``). Use different IDs to differentiate between parallel viewer instances. - ``address``: Optional server address to connect to a remote Rerun server. If provided, connects to the specified server. - ``serve_web_viewer``: Serve a web viewer over HTTP and open it in the browser (default: ``True``). If ``False``, spawns a native Rerun viewer. - ``web_port``: Port for the web viewer (default: ``9090``) - ``grpc_port``: Port for the gRPC server (default: ``9876``) - ``keep_historical_data``: Keep historical state data in the viewer for time scrubbing (default: ``False``) - ``keep_scalar_history``: Keep scalar time-series history (default: ``True``) - ``record_to_rrd``: Optional path to save a ``.rrd`` recording file **Usage**: .. code-block:: python # Default usage: spawns a local viewer viewer = newton.viewer.ViewerRerun( app_id="newton-simulation" ) # Or specify a custom server address for remote viewing viewer = newton.viewer.ViewerRerun( address="rerun+http://127.0.0.1:9876/proxy", app_id="newton-simulation" ) viewer.set_model(model) # at every frame: viewer.begin_frame(sim_time) viewer.log_state(state) viewer.end_frame() By default, the viewer will run without keeping historical state data in the viewer to keep the memory usage constant when sending transform updates via :meth:`~newton.viewer.ViewerBase.log_state`. This is useful for visualizing long and complex simulations that would quickly fill up the web viewer's memory if the historical data was kept. If you want to keep the historical state data in the viewer, you can set the ``keep_historical_data`` flag to ``True``. The rerun viewer provides a web-based interface with features like: - Time scrubbing and playback controls - 3D scene navigation - Data inspection and filtering - Recording and export capabilities **Jupyter notebook support** The ViewerRerun backend automatically detects if it is running inside a Jupyter notebook environment and automatically generates an output widget for the viewer during the construction of :class:`~newton.viewer.ViewerRerun`. The rerun SDK provides a Jupyter notebook extension that allows you to visualize rerun data in a Jupyter notebook. You can use ``uv`` to start Jupyter lab with the required dependencies (or install the extension manually with ``pip install rerun-sdk[notebook]``): .. code-block:: bash uv run --extra notebook jupyter lab Then, you can use the rerun SDK in a Jupyter notebook by importing the ``rerun`` module and creating a viewer instance. .. code-block:: python viewer = newton.viewer.ViewerRerun(keep_historical_data=True) viewer.set_model(model) frame_dt = 1 / 60.0 sim_time = 0.0 for frame in range(500): # simulate, step the solver, etc. solver.step(...) # visualize viewer.begin_frame(sim_time) viewer.log_state(state) viewer.end_frame() sim_time += frame_dt viewer.show_notebook() # or simply `viewer` to display the viewer in the notebook .. image:: /images/rerun_notebook_example.png :width: 1000 :align: left The history of states will be available in the viewer to scrub through the simulation timeline. Viser Viewer ~~~~~~~~~~~~ The :class:`~newton.viewer.ViewerViser` backend integrates with the `viser `_ visualization library, providing web-based 3D visualization that works in any browser and has native Jupyter notebook support. **Installation**: Requires the viser package: .. code-block:: bash pip install viser **Usage**: .. code-block:: python # Default usage: starts a web server on port 8080 viewer = newton.viewer.ViewerViser(port=8080) # Open http://localhost:8080 in your browser to view the simulation viewer.set_model(model) # at every frame: viewer.begin_frame(sim_time) viewer.log_state(state) viewer.end_frame() # Close the viewer when done viewer.close() Key parameters: - ``port``: Port number for the web server (default: ``8080``) - ``label``: Optional label for the browser window title - ``verbose``: If True, print the server URL when starting (default: ``True``) - ``share``: If True, create a publicly accessible URL via viser's share feature - ``record_to_viser``: Path to record the visualization to a ``.viser`` file for later playback **Recording and playback** ViewerViser can record simulations to ``.viser`` files for later playback: .. code-block:: python # Record to a .viser file viewer = newton.viewer.ViewerViser(record_to_viser="my_simulation.viser") viewer.set_model(model) # Run simulation... for frame in range(500): viewer.begin_frame(sim_time) viewer.log_state(state) viewer.end_frame() sim_time += frame_dt # Save the recording viewer.save_recording() The recorded ``.viser`` file can be played back using the viser HTML player. **Jupyter notebook support** ViewerViser has native Jupyter notebook integration. When recording is enabled, calling ``show_notebook()`` will display an embedded player with timeline controls: .. code-block:: python viewer = newton.viewer.ViewerViser(record_to_viser="simulation.viser") viewer.set_model(model) # Run simulation... for frame in range(500): viewer.begin_frame(sim_time) viewer.log_state(state) viewer.end_frame() sim_time += frame_dt # Display in notebook with timeline controls viewer.show_notebook() # or simply `viewer` at the end of a cell When no recording is active, ``show_notebook()`` displays the live server in an IFrame. The viser viewer provides features like: - Real-time 3D visualization in any web browser - Interactive camera controls (pan, zoom, orbit) - GPU-accelerated batched mesh rendering - Recording and playback capabilities - Public URL sharing via viser's share feature Utility Viewers --------------- Null Viewer ~~~~~~~~~~~ The :class:`~newton.viewer.ViewerNull` provides a no-operation viewer for headless environments or automated testing where visualization is not required. It simply counts frames and provides stub implementations for all viewer methods. .. testcode:: viewer-null builder = newton.ModelBuilder() body = builder.add_body(mass=1.0) model = builder.finalize() state = model.state() sim_time = 0.0 viewer = newton.viewer.ViewerNull(num_frames=10) viewer.set_model(model) while viewer.is_running(): viewer.begin_frame(sim_time) viewer.log_state(state) viewer.end_frame() sim_time += 1.0 / 60.0 print(f"Ran {viewer.frame_count} frames") .. testoutput:: viewer-null Ran 10 frames This is particularly useful for: - Performance benchmarking without rendering overhead - Automated testing in CI/CD pipelines - Running simulations on headless servers - Batch processing of simulations Custom Visualization -------------------- In addition to rendering simulation state with :meth:`~newton.viewer.ViewerBase.log_state`, you can draw custom debug overlays using the ``log_*`` methods available on all viewers. **Drawing lines:** Use :meth:`~newton.viewer.ViewerBase.log_lines` to draw line segments — useful for visualizing forces, rays, or normals: .. code-block:: python # Draw force vectors at body positions viewer.log_lines( "/debug/forces", starts=positions, # wp.array(dtype=wp.vec3) ends=positions + forces, # wp.array(dtype=wp.vec3) colors=(1.0, 0.0, 0.0), # red width=0.005, ) **Drawing points:** Use :meth:`~newton.viewer.ViewerBase.log_points` to draw a point cloud: .. code-block:: python viewer.log_points( "/debug/targets", points=target_positions, # wp.array(dtype=wp.vec3) radii=0.02, # uniform radius, or wp.array(dtype=wp.float32) colors=(0.0, 1.0, 0.0), # green ) **Visualizing contacts:** Use :meth:`~newton.viewer.ViewerBase.log_contacts` to draw contact normals from a :class:`~newton.Contacts` object. The viewer's ``show_contacts`` flag (toggled in the :class:`~newton.viewer.ViewerGL` sidebar) controls visibility: .. code-block:: python viewer.log_contacts(contacts, state) **Transform gizmos:** Use :meth:`~newton.viewer.ViewerBase.log_gizmo` to display a coordinate-frame gizmo at a given transform: .. code-block:: python viewer.log_gizmo("/debug/target_frame", wp.transform(pos, rot)) **Camera and world layout:** Set the camera programmatically with :meth:`~newton.viewer.ViewerBase.set_camera`: .. code-block:: python viewer.set_camera(pos=wp.vec3(5.0, 2.0, 3.0), pitch=-0.3, yaw=0.5) When visualizing multiple worlds, use :meth:`~newton.viewer.ViewerBase.set_world_offsets` to arrange them in a grid (must be called after :meth:`~newton.viewer.ViewerBase.set_model`): .. code-block:: python viewer.set_world_offsets(spacing=(5.0, 5.0, 0.0)) Choosing the Right Viewer ------------------------- .. list-table:: Viewer Comparison :header-rows: 1 * - Viewer - Use Case - Output - Dependencies * - :class:`~newton.viewer.ViewerGL` - Interactive development and debugging - Real-time display - pyglet, imgui_bundle * - :class:`~newton.viewer.ViewerFile` - Recording for replay/sharing - .json or .bin files - None * - :class:`~newton.viewer.ViewerUSD` - Integration with 3D pipelines - .usd files - usd-core * - :class:`~newton.viewer.ViewerRerun` - Advanced visualization and analysis - Web interface - rerun-sdk * - :class:`~newton.viewer.ViewerViser` - Browser-based visualization and Jupyter notebooks - Web interface, .viser files - viser * - :class:`~newton.viewer.ViewerNull` - Headless/automated environments - None - None ================================================ FILE: docs/images/examples/resize.bat ================================================ @echo off REM resize all PNGs to half size, crop to square, and convert to JPG for %%f in (*.png) do ( echo Processing %%f... REM First crop to square (keep as PNG), then resize to half and convert to JPG ffmpeg -y -i "%%f" -vf "crop=min(iw\,ih):min(iw\,ih)" -update 1 "%%~nf_temp.png" ffmpeg -y -i "%%~nf_temp.png" -vf "scale=iw/2:ih/2,format=yuv420p" -update 1 -q:v 2 "%%~nf.jpg" del "%%~nf_temp.png" ) ================================================ FILE: docs/images/examples/resize.sh ================================================ # resize all pngs in a directory by 2x in dimension, crop to square, + convert to jpg for f in *.png; do ffmpeg -y -i "$f" -vf "crop=min(iw\,ih):min(iw\,ih),scale=iw/2:ih/2,format=yuv420p" -update 1 -q:v 3 "${f%.png}.jpg"; done ================================================ FILE: docs/index.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 .. raw:: html Newton Physics =============== .. toctree:: :maxdepth: 1 :hidden: :caption: User Guide Overview guide/installation guide/visualization guide/tutorials Development .. toctree:: :maxdepth: 1 :hidden: :caption: Concepts Worlds Articulations Mass and Inertia Sites Sensors Conventions USD Parsing Custom Attributes Extended Attributes Collisions and Contacts .. toctree:: :maxdepth: 1 :hidden: :caption: API Reference api/newton api/newton_geometry api/newton_ik api/newton_math api/newton_selection api/newton_sensors api/newton_solvers api/newton_usd api/newton_utils api/newton_viewer .. toctree:: :hidden: :caption: Further Reading FAQ Migration Guide Integrations .. toctree:: :hidden: :caption: Project Links GitHub ================================================ FILE: docs/integrations/index.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 Newton Integrations ==================== .. toctree:: :maxdepth: 1 isaac-lab mujoco ================================================ FILE: docs/integrations/isaac-lab.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 Isaac Lab Integration ===================== For details about Isaac Lab support for Newton, see the `Isaac Lab documentation `_. ================================================ FILE: docs/integrations/mujoco.rst ================================================ .. SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers .. SPDX-License-Identifier: CC-BY-4.0 .. currentmodule:: newton MuJoCo Integration ================== :class:`~newton.solvers.SolverMuJoCo` translates a Newton :class:`~newton.Model` into a `MuJoCo `_ model and steps it with `mujoco_warp `_. Because MuJoCo has its own modelling conventions, some Newton properties are mapped differently or not at all. The sections below describe each conversion in detail. Coordinate conventions ---------------------- **Quaternion order.** Newton stores quaternions as ``(x, y, z, w)``; MuJoCo uses ``(w, x, y, z)``. The solver converts between the two automatically. Be aware of this when inspecting raw MuJoCo model or data objects (e.g. via ``save_to_mjcf`` or the ``mj_model``/``mj_data`` attributes on the solver). Joint types ----------- .. list-table:: :header-rows: 1 :widths: 25 35 40 * - Newton type - MuJoCo type(s) - Notes * - ``FREE`` - ``mjJNT_FREE`` - Initial pose taken from ``body_q``. * - ``BALL`` - ``mjJNT_BALL`` - Per-axis actuators mapped via ``gear``. * - ``REVOLUTE`` - ``mjJNT_HINGE`` - * - ``PRISMATIC`` - ``mjJNT_SLIDE`` - * - ``D6`` - Up to 3 × ``mjJNT_SLIDE`` + 3 × ``mjJNT_HINGE`` - Each active linear/angular DOF becomes a separate MuJoCo joint (``_lin``/``_ang`` suffixes, with numeric indices when multiple axes are active). * - ``FIXED`` - *(no joint)* - The child body is nested directly under its parent. If the fixed joint connects to the world, the body is created as a **mocap** body. Geometry types -------------- .. list-table:: :header-rows: 1 :widths: 25 25 50 * - Newton type - MuJoCo type - Notes * - ``SPHERE`` - ``mjGEOM_SPHERE`` - * - ``CAPSULE`` - ``mjGEOM_CAPSULE`` - * - ``CYLINDER`` - ``mjGEOM_CYLINDER`` - * - ``BOX`` - ``mjGEOM_BOX`` - * - ``ELLIPSOID`` - ``mjGEOM_ELLIPSOID`` - * - ``PLANE`` - ``mjGEOM_PLANE`` - Must be attached to the world body. Rendered size defaults to ``5 × 5 × 5``. * - ``HFIELD`` - ``mjGEOM_HFIELD`` - Heightfield data is normalized ``[0, 1]``; the geom origin is shifted by ``min_z`` so the lowest point is at the correct world height. * - ``MESH`` / ``CONVEX_MESH`` - ``mjGEOM_MESH`` - MuJoCo only supports **convex** collision meshes. Non-convex meshes are convex-hulled automatically, which changes the collision boundary. ``maxhullvert`` is forwarded from the mesh source when set. **Sites** (shapes with the ``SITE`` flag) are converted to MuJoCo sites, which are non-colliding reference frames used for sensor attachment and spatial tendons. Shape parameters ---------------- **Friction.** Newton's ``shape_material_mu``, ``shape_material_mu_torsional``, and ``shape_material_mu_rolling`` map directly to MuJoCo's three-element geom ``friction`` vector: ``(sliding, torsional, rolling)``. **Stiffness and damping (solref).** Newton's ``shape_material_ke`` (stiffness) and ``shape_material_kd`` (damping) are converted to MuJoCo's geom ``solref`` ``(timeconst, dampratio)`` pair. When either value is zero or negative, the solver falls back to MuJoCo's defaults (``timeconst = 0.02``, ``dampratio = 1.0``). **Joint-limit stiffness and damping (solref_limit).** ``joint_limit_ke`` and ``joint_limit_kd`` are forwarded as negative ``solref_limit`` values ``(-ke, -kd)``, which MuJoCo interprets as direct stiffness/damping rather than time-constant/damp-ratio. **Margin.** Newton's ``shape_margin`` maps to MuJoCo ``geom_margin``. **MuJoCo-specific custom attributes.** Many MuJoCo-specific parameters are stored in Newton's ``mujoco`` custom-attribute namespace and forwarded to the MuJoCo model when present. These cover geom properties (``condim``, ``geom_priority``, ``geom_solimp``, ``geom_solmix``), joint properties (``dof_passive_stiffness``, ``dof_passive_damping``, ``jnt_actgravcomp``, ``dof_springref``, ``dof_ref``, ``limit_margin``, ``solimplimit``, ``solreffriction``, ``solimpfriction``), equality constraints (``eq_solref``), tendons, general actuators, and solver options. See :doc:`/concepts/custom_attributes` for the full list. Collision filtering ------------------- Newton uses integer ``shape_collision_group`` labels to control which shapes can collide. MuJoCo uses ``contype``/``conaffinity`` bitmasks with a different semantic: two geoms collide when ``(contype_A & conaffinity_B) || (contype_B & conaffinity_A)`` is non-zero. The solver bridges the two systems with **graph coloring**. Shapes that must *not* collide are assigned the same color; each color maps to one bit in ``contype``. ``conaffinity`` is set to the complement so that same-color geoms never match. Up to 32 colors are supported (one per ``contype`` bit). If the graph requires more than 32 colors, shapes with color index ≥ 32 fall back to MuJoCo defaults (``contype=1``, ``conaffinity=1``) and will collide with all other shapes, silently bypassing the intended filtering. Non-colliding shapes (no ``COLLIDE_SHAPES`` flag, or ``collision_group == 0``) get ``contype = conaffinity = 0``. Additionally, body pairs for which all shape-shape combinations are filtered are registered as ```` elements. Mass and inertia ---------------- Bodies with positive mass have their mass, center-of-mass offset (``ipos``), and inertia tensor set explicitly (``explicitinertial="true"``). When the inertia tensor is diagonal the solver uses ``diaginertia``; otherwise it uses ``fullinertia``. Zero-mass bodies (e.g. sensor frames) omit mass and inertia entirely, letting MuJoCo derive them from child geoms (``inertiafromgeom="auto"``). Actuators --------- Newton's per-DOF ``joint_target_mode`` determines which MuJoCo general actuators are created: .. list-table:: :header-rows: 1 :widths: 25 75 * - Mode - MuJoCo actuator(s) * - ``POSITION`` - One actuator: ``gainprm = [kp]``, ``biasprm = [0, -kp, -kd]``. * - ``VELOCITY`` - One actuator: ``gainprm = [kd]``, ``biasprm = [0, 0, -kd]``. * - ``POSITION_VELOCITY`` - Two actuators — a position actuator (``gainprm = [kp]``, ``biasprm = [0, -kp, 0]``) and a velocity actuator (``gainprm = [kd]``, ``biasprm = [0, 0, -kd]``). * - ``NONE`` - No actuator created for this DOF. ``joint_effort_limit`` is forwarded as ``actfrcrange`` on the joint (for prismatic, revolute, and D6 joints) or as ``forcerange`` on the actuator (for ball joints). Additional MuJoCo general actuators (motors, etc.) can be attached through custom attributes and are appended after the joint-target actuators. Equality constraints -------------------- .. list-table:: :header-rows: 1 :widths: 20 20 60 * - Newton type - MuJoCo type - Notes * - ``CONNECT`` - ``mjEQ_CONNECT`` - Anchor forwarded in ``data[0:3]``. * - ``WELD`` - ``mjEQ_WELD`` - Relative pose and torque scale forwarded. * - ``JOINT`` - ``mjEQ_JOINT`` - Polynomial coefficients forwarded in ``data[0:5]``. * - Mimic - ``mjEQ_JOINT`` - ``coef0`` / ``coef1`` mapped to polynomial coefficients. Only ``REVOLUTE`` and ``PRISMATIC`` joints are supported. ``eq_solref`` custom attributes are forwarded when present. Solver options -------------- Solver parameters follow a three-level resolution priority: 1. **Constructor argument** — value passed to :class:`~newton.solvers.SolverMuJoCo`. 2. **Custom attribute** (``model.mujoco.` for a full overview of world semantics, layout, and supported workflows. There are two supported workflows for assigning world indices: 1. **Using begin_world()/end_world()**: Entities added outside any world context, before the first :meth:`begin_world` or after the matching :meth:`end_world`, are assigned to the global world (index ``-1``). :class:`ModelBuilder` manages :attr:`current_world` while a world context is active:: builder = ModelBuilder() builder.add_ground_plane() # global (world -1) builder.begin_world(label="robot_0") builder.add_body(...) # world 0 builder.end_world() 2. **Using add_world()/replicate()**: All entities from the sub-builder are assigned to a new world:: robot = ModelBuilder() robot.add_body(...) # World assignments here will be overridden main = ModelBuilder() main.add_world(robot) # All robot entities -> world 0 main.replicate(robot, world_count=2) # Add more worlds from the same source :attr:`current_world` is builder-managed, read-only state. Use :meth:`begin_world`, :meth:`end_world`, :meth:`add_world`, or :meth:`replicate` to manage world assignment. Note: It is strongly recommended to use the ModelBuilder to construct a simulation rather than creating your own Model object directly, however it is possible to do so if desired. """ _DEFAULT_GROUND_PLANE_COLOR = (0.125, 0.125, 0.15) _SHAPE_COLOR_PALETTE = ( # Paul Tol - Bright 9 (68, 119, 170), # blue (102, 204, 238), # cyan (34, 136, 51), # green (204, 187, 68), # yellow (238, 102, 119), # red (170, 51, 119), # magenta (238, 153, 51), # orange (0, 153, 136), # teal ) _BODY_ARMATURE_ARG_DEPRECATION_MESSAGE = ( "ModelBuilder.add_link(..., armature=...) and ModelBuilder.add_body(..., armature=...) " "are deprecated and will be removed in a future release. " "Add any isotropic artificial inertia directly to 'inertia' instead." ) _DEFAULT_BODY_ARMATURE_DEPRECATION_MESSAGE = ( "ModelBuilder.default_body_armature is deprecated and will be removed in a future release. " "Add any isotropic artificial inertia directly to 'inertia' instead." ) @staticmethod def _shape_palette_color(index: int) -> tuple[float, float, float]: color = ModelBuilder._SHAPE_COLOR_PALETTE[index % len(ModelBuilder._SHAPE_COLOR_PALETTE)] return (color[0] / 255.0, color[1] / 255.0, color[2] / 255.0) @dataclass class ActuatorEntry: """Stores accumulated indices and arguments for one actuator type + scalar params combo. Each element in input_indices/output_indices represents one actuator. For single-input actuators: [[idx1], [idx2], ...] → flattened to 1D array For multi-input actuators: [[idx1, idx2], [idx3, idx4], ...] → 2D array """ input_indices: list[list[int]] # Per-actuator input indices output_indices: list[list[int]] # Per-actuator output indices args: list[dict[str, Any]] # Per-actuator array params (scalar params in dict key) @dataclass class ShapeConfig: """ Represents the properties of a collision shape used in simulation. """ density: float = 1000.0 """The density of the shape material.""" ke: float = 2.5e3 """The contact elastic stiffness. Used by SemiImplicit, Featherstone, MuJoCo.""" kd: float = 100.0 """The contact damping coefficient. Used by SemiImplicit, Featherstone, MuJoCo.""" kf: float = 1000.0 """The friction damping coefficient. Used by SemiImplicit, Featherstone.""" ka: float = 0.0 """The contact adhesion distance. Used by SemiImplicit, Featherstone.""" mu: float = 1.0 """The coefficient of friction. Used by all solvers.""" restitution: float = 0.0 """The coefficient of restitution. Used by XPBD. To take effect, enable restitution in solver constructor via ``enable_restitution=True``.""" mu_torsional: float = 0.005 """The coefficient of torsional friction (resistance to spinning at contact point). Used by XPBD, MuJoCo.""" mu_rolling: float = 0.0001 """The coefficient of rolling friction (resistance to rolling motion). Used by XPBD, MuJoCo.""" margin: float = 0.0 """Outward offset from the shape's surface [m] for collision detection. Extends the effective collision surface outward by this amount. When two shapes collide, their margins are summed (margin_a + margin_b) to determine the total separation [m]. This value is also used when computing inertia for hollow shapes (``is_solid=False``).""" gap: float | None = None """Additional contact detection gap [m]. If None, uses builder.rigid_gap as default. Broad phase uses (margin + gap) [m] for AABB expansion and pair filtering.""" is_solid: bool = True """Indicates whether the shape is solid or hollow. Defaults to True.""" collision_group: int = 1 """The collision group ID for the shape. Defaults to 1 (default group). Set to 0 to disable collisions for this shape.""" collision_filter_parent: bool = True """Whether to inherit collision filtering from the parent. Defaults to True.""" has_shape_collision: bool = True """Whether the shape can collide with other shapes. Defaults to True.""" has_particle_collision: bool = True """Whether the shape can collide with particles. Defaults to True.""" is_visible: bool = True """Indicates whether the shape is visible in the simulation. Defaults to True.""" is_site: bool = False """Indicates whether the shape is a site (non-colliding reference point). Directly setting this to True will NOT enforce site invariants. Use `mark_as_site()` or set via the `flags` property to ensure invariants. Defaults to False.""" sdf_narrow_band_range: tuple[float, float] = (-0.1, 0.1) """The narrow band distance range (inner, outer) for primitive SDF computation.""" sdf_target_voxel_size: float | None = None """Target voxel size for sparse SDF grid. If provided, enables primitive SDF generation and takes precedence over sdf_max_resolution. Requires GPU since wp.Volume only supports CUDA.""" sdf_max_resolution: int | None = None """Maximum dimension for sparse SDF grid (must be divisible by 8). If provided (and sdf_target_voxel_size is None), enables primitive SDF generation. Requires GPU since wp.Volume only supports CUDA.""" sdf_texture_format: str = "uint16" """Subgrid texture storage format for the SDF. ``"uint16"`` (default) stores subgrid voxels as 16-bit normalized textures (half the memory of ``"float32"``). ``"float32"`` stores full-precision values. ``"uint8"`` uses 8-bit textures for minimum memory.""" is_hydroelastic: bool = False """Whether the shape collides using SDF-based hydroelastics. For hydroelastic collisions, both participating shapes must have is_hydroelastic set to True. Defaults to False. .. note:: Hydroelastic collision handling only works with volumetric shapes and in particular will not work for shapes like flat meshes or cloth. This flag will be automatically set to False for planes and heightfields in :meth:`ModelBuilder.add_shape`. """ kh: float = 1.0e10 """Contact stiffness coefficient for hydroelastic collisions. Used by MuJoCo, Featherstone, SemiImplicit when is_hydroelastic is True. .. note:: For MuJoCo, stiffness values will internally be scaled by masses. Users should choose kh to match their desired force-to-penetration ratio. """ def configure_sdf( self, *, max_resolution: int | None = None, target_voxel_size: float | None = None, is_hydroelastic: bool = False, kh: float = 1.0e10, texture_format: str | None = None, ) -> None: """Enable SDF-based collision for this shape. Sets SDF and hydroelastic options in one place. Call this when the shape should use SDF mesh-mesh collision and optionally hydroelastic contacts. Args: max_resolution: Maximum dimension for sparse SDF grid (must be divisible by 8). If provided, enables SDF-based mesh-mesh collision and clears any previous target_voxel_size setting. target_voxel_size: Target voxel size for sparse SDF grid. If provided, enables SDF generation and clears any previous max_resolution setting. is_hydroelastic: Whether to use SDF-based hydroelastic contacts. Both shapes in a pair must have this enabled. kh: Contact stiffness coefficient for hydroelastic collisions. texture_format: Subgrid texture storage format. ``"uint16"`` (default) uses 16-bit normalized textures. ``"float32"`` uses full-precision. ``"uint8"`` uses 8-bit textures. Raises: ValueError: If both max_resolution and target_voxel_size are provided. """ if max_resolution is not None and target_voxel_size is not None: raise ValueError("configure_sdf accepts either max_resolution or target_voxel_size, not both.") if max_resolution is not None: self.sdf_max_resolution = max_resolution self.sdf_target_voxel_size = None if target_voxel_size is not None: self.sdf_target_voxel_size = target_voxel_size self.sdf_max_resolution = None self.is_hydroelastic = is_hydroelastic self.kh = kh if texture_format is not None: self.sdf_texture_format = texture_format def validate(self, shape_type: int | None = None) -> None: """Validate ShapeConfig parameters. Args: shape_type: Optional shape geometry type used for context-specific validation. """ _valid_tex_fmts = ("float32", "uint16", "uint8") if self.sdf_texture_format not in _valid_tex_fmts: raise ValueError( f"Unknown sdf_texture_format {self.sdf_texture_format!r}. Expected one of {list(_valid_tex_fmts)}." ) if self.sdf_max_resolution is not None and self.sdf_target_voxel_size is not None: raise ValueError("Set only one of sdf_max_resolution or sdf_target_voxel_size, not both.") if self.sdf_max_resolution is not None and self.sdf_max_resolution % 8 != 0: raise ValueError( f"sdf_max_resolution must be divisible by 8 (got {self.sdf_max_resolution}). " "This is required because SDF volumes are allocated in 8x8x8 tiles." ) hydroelastic_supported = shape_type not in (GeoType.PLANE, GeoType.HFIELD) hydroelastic_requires_configured_sdf = shape_type in ( GeoType.SPHERE, GeoType.BOX, GeoType.CAPSULE, GeoType.CYLINDER, GeoType.ELLIPSOID, GeoType.CONE, ) if ( self.is_hydroelastic and hydroelastic_supported and hydroelastic_requires_configured_sdf and self.has_shape_collision and self.sdf_max_resolution is None and self.sdf_target_voxel_size is None ): raise ValueError( "Hydroelastic shapes require an SDF. Set either sdf_max_resolution or sdf_target_voxel_size." ) def mark_as_site(self) -> None: """Marks this shape as a site and enforces all site invariants. Sets: - is_site = True - has_shape_collision = False - has_particle_collision = False - density = 0.0 - collision_group = 0 """ self.is_site = True self.has_shape_collision = False self.has_particle_collision = False self.density = 0.0 self.collision_group = 0 @property def flags(self) -> int: """Returns the flags for the shape.""" shape_flags = ShapeFlags.VISIBLE if self.is_visible else 0 shape_flags |= ShapeFlags.COLLIDE_SHAPES if self.has_shape_collision else 0 shape_flags |= ShapeFlags.COLLIDE_PARTICLES if self.has_particle_collision else 0 shape_flags |= ShapeFlags.SITE if self.is_site else 0 shape_flags |= ShapeFlags.HYDROELASTIC if self.is_hydroelastic else 0 return shape_flags @flags.setter def flags(self, value: int): """Sets the flags for the shape.""" self.is_visible = bool(value & ShapeFlags.VISIBLE) self.is_hydroelastic = bool(value & ShapeFlags.HYDROELASTIC) # Check if SITE flag is being set is_site_flag = bool(value & ShapeFlags.SITE) if is_site_flag: # Use mark_as_site() to enforce invariants self.mark_as_site() # Collision flags will be cleared by mark_as_site() else: # SITE flag is being cleared - restore non-site defaults defaults = self.__class__() self.is_site = False self.density = defaults.density self.collision_group = defaults.collision_group self.has_shape_collision = bool(value & ShapeFlags.COLLIDE_SHAPES) self.has_particle_collision = bool(value & ShapeFlags.COLLIDE_PARTICLES) def copy(self) -> ModelBuilder.ShapeConfig: return copy.copy(self) class JointDofConfig: """ Describes a joint axis (a single degree of freedom) that can have limits and be driven towards a target. """ def __init__( self, axis: AxisType | Vec3 = Axis.X, limit_lower: float = -MAXVAL, limit_upper: float = MAXVAL, limit_ke: float = 1e4, limit_kd: float = 1e1, target_pos: float = 0.0, target_vel: float = 0.0, target_ke: float = 0.0, target_kd: float = 0.0, armature: float = 0.0, effort_limit: float = 1e6, velocity_limit: float = 1e6, friction: float = 0.0, actuator_mode: JointTargetMode | None = None, ): self.axis = wp.normalize(axis_to_vec3(axis)) """The 3D joint axis in the joint parent anchor frame.""" self.limit_lower = limit_lower """The lower position limit of the joint axis. Defaults to -MAXVAL (unlimited).""" self.limit_upper = limit_upper """The upper position limit of the joint axis. Defaults to MAXVAL (unlimited).""" self.limit_ke = limit_ke """The elastic stiffness of the joint axis limits. Defaults to 1e4.""" self.limit_kd = limit_kd """The damping stiffness of the joint axis limits. Defaults to 1e1.""" self.target_pos = target_pos """The target position of the joint axis. If the initial `target_pos` is outside the limits, it defaults to the midpoint of `limit_lower` and `limit_upper`. Otherwise, defaults to 0.0.""" self.target_vel = target_vel """The target velocity of the joint axis.""" self.target_ke = target_ke """The proportional gain of the target drive PD controller. Defaults to 0.0.""" self.target_kd = target_kd """The derivative gain of the target drive PD controller. Defaults to 0.0.""" self.armature = armature """Artificial inertia added around the joint axis [kg·m² or kg]. Defaults to 0.""" self.effort_limit = effort_limit """Maximum effort (force or torque) the joint axis can exert. Defaults to 1e6.""" self.velocity_limit = velocity_limit """Maximum velocity the joint axis can achieve. Defaults to 1e6.""" self.friction = friction """Friction coefficient for the joint axis. Defaults to 0.0.""" self.actuator_mode = actuator_mode """Actuator mode for this DOF. Determines which actuators are installed (see :class:`JointTargetMode`). If None, the mode is inferred from gains and targets.""" if self.target_pos > self.limit_upper or self.target_pos < self.limit_lower: self.target_pos = 0.5 * (self.limit_lower + self.limit_upper) @classmethod def create_unlimited(cls, axis: AxisType | Vec3) -> ModelBuilder.JointDofConfig: """Creates a JointDofConfig with no limits.""" return ModelBuilder.JointDofConfig( axis=axis, limit_lower=-MAXVAL, limit_upper=MAXVAL, target_pos=0.0, target_vel=0.0, target_ke=0.0, target_kd=0.0, armature=0.0, limit_ke=0.0, limit_kd=0.0, ) @dataclass class CustomAttribute: """ Represents a custom attribute definition for the ModelBuilder. This is used to define custom attributes that are not part of the standard ModelBuilder API. Custom attributes can be defined for the :class:`~newton.Model`, :class:`~newton.State`, :class:`~newton.Control`, or :class:`~newton.Contacts` objects, depending on the :class:`Model.AttributeAssignment` category. Custom attributes must be declared before use via the :meth:`newton.ModelBuilder.add_custom_attribute` method. See :ref:`custom_attributes` for more information. """ name: str """Variable name to expose on the Model. Must be a valid Python identifier.""" dtype: type """Warp dtype (e.g., wp.float32, wp.int32, wp.bool, wp.vec3) that is compatible with Warp arrays, or ``str`` for string attributes that remain as Python lists.""" frequency: Model.AttributeFrequency | str """Frequency category that determines how the attribute is indexed in the Model. Can be either: - A :class:`Model.AttributeFrequency` enum value for built-in frequencies (BODY, SHAPE, JOINT, etc.) Uses dict-based storage where keys are entity indices, allowing sparse assignment. - A string for custom frequencies using the full frequency key (e.g., ``"mujoco:pair"``). Uses list-based storage for sequential data appended via :meth:`~newton.ModelBuilder.add_custom_values`. All attributes sharing the same custom frequency must have the same count, validated by :meth:`finalize `.""" assignment: Model.AttributeAssignment = Model.AttributeAssignment.MODEL """Assignment category (see :class:`Model.AttributeAssignment`), defaults to :attr:`Model.AttributeAssignment.MODEL`""" namespace: str | None = None """Namespace for the attribute. If None, the attribute is added directly to the assigned object without a namespace.""" references: str | None = None """For attributes containing entity indices, specifies how values are transformed during add_builder/add_world/replicate merging. Built-in entity types (values are offset by entity count): - ``"body"``, ``"shape"``, ``"joint"``, ``"joint_dof"``, ``"joint_coord"``, ``"articulation"``, ``"equality_constraint"``, ``"constraint_mimic"``, ``"particle"``, ``"edge"``, ``"triangle"``, ``"tetrahedron"``, ``"spring"`` Special handling: - ``"world"``: Values are replaced with the builder-managed :attr:`ModelBuilder.current_world` context (not offset) Custom frequencies (values are offset by that frequency's count): - Any custom frequency string, e.g., ``"mujoco:pair"`` """ default: Any = None """Default value for the attribute. If None, the default value is determined based on the dtype.""" values: dict[int, Any] | list[Any] | None = None """Storage for specific values (overrides). For enum frequencies (BODY, SHAPE, etc.): dict[int, Any] mapping entity indices to values. For string frequencies ("mujoco:pair", etc.): list[Any] for sequential custom data. If None, the attribute is not initialized with any values. Values can be assigned in subsequent ``ModelBuilder.add_*(..., custom_attributes={...})`` method calls for specific entities after the CustomAttribute has been added through the :meth:`ModelBuilder.add_custom_attribute` method.""" usd_attribute_name: str | None = None """Name of the USD attribute to read values from during USD parsing. - If ``None`` (default), the name is derived automatically as ``"newton:"`` where ```` is ``":"`` or just ``""`` if no namespace is set. - If set to ``"*"``, the :attr:`usd_value_transformer` is called for every prim matching the attribute's frequency, regardless of which USD attributes exist on the prim. The transformer receives ``None`` as the value argument. This is useful for computing attribute values from arbitrary prim data rather than reading a specific USD attribute. A :attr:`usd_value_transformer` **must** be provided when using ``"*"``; otherwise, :meth:`~newton.ModelBuilder.add_custom_attribute` raises a :class:`ValueError`. """ mjcf_attribute_name: str | None = None """Name of the attribute in the MJCF definition. If None, the attribute name is used.""" urdf_attribute_name: str | None = None """Name of the attribute in the URDF definition. If None, the attribute name is used.""" usd_value_transformer: Callable[[Any, dict[str, Any]], Any] | None = None """Transformer function that converts a USD attribute value to a valid Warp dtype. If undefined, the generic converter from :func:`newton.usd.convert_warp_value` is used. Receives a context dict with the following keys: - ``"prim"``: The USD prim to query. - ``"attr"``: The :class:`~newton.ModelBuilder.CustomAttribute` object to get the value for.""" mjcf_value_transformer: Callable[[str, dict[str, Any] | None], Any] | None = None """Transformer function that converts a MJCF attribute value string to a valid Warp dtype. If undefined, the generic converter from :func:`newton.utils.parse_warp_value_from_string` is used. Receives an optional context dict with parsing-time information (e.g., use_degrees, joint_type).""" urdf_value_transformer: Callable[[str, dict[str, Any] | None], Any] | None = None """Transformer function that converts a URDF attribute value string to a valid Warp dtype. If undefined, the generic converter from :func:`newton.utils.parse_warp_value_from_string` is used. Receives an optional context dict with parsing-time information.""" def __post_init__(self): """Initialize default values and validate dtype compatibility.""" # Allow str dtype for string attributes (stored as Python lists, not warp arrays) if self.dtype is not str: # ensure dtype is a valid Warp dtype try: _size = wp.types.type_size_in_bytes(self.dtype) except TypeError as e: raise ValueError(f"Invalid dtype: {self.dtype}. Must be a valid Warp dtype or str.") from e # Set dtype-specific default value if none was provided if self.default is None: self.default = self._default_for_dtype(self.dtype) # Initialize values with correct container type based on frequency if self.values is None: self.values = self._create_empty_values_container() if self.usd_attribute_name is None: self.usd_attribute_name = f"newton:{self.key}" if self.mjcf_attribute_name is None: self.mjcf_attribute_name = self.name if self.urdf_attribute_name is None: self.urdf_attribute_name = self.name @staticmethod def _default_for_dtype(dtype: object) -> Any: """Get default value for dtype when not specified.""" # string type gets empty string if dtype is str: return "" # quaternions get identity quaternion if wp.types.type_is_quaternion(dtype): return wp.quat_identity(dtype._wp_scalar_type_) if dtype is wp.bool or dtype is bool: return False # vectors, matrices, scalars return dtype(0) @property def key(self) -> str: """Return the full name of the attribute, formatted as "namespace:name" or "name" if no namespace is specified.""" return f"{self.namespace}:{self.name}" if self.namespace else self.name @property def is_custom_frequency(self) -> bool: """Check if this attribute uses a custom (string) frequency. Returns: True if the frequency is a string (custom frequency), False if it's a Model.AttributeFrequency enum (built-in frequency like BODY, SHAPE, etc.). """ return isinstance(self.frequency, str) def _create_empty_values_container(self) -> list | dict: """Create appropriate empty container based on frequency type.""" return [] if self.is_custom_frequency else {} def _get_values_count(self) -> int: """Get current count of values in this attribute.""" if self.values is None: return 0 return len(self.values) def build_array( self, count: int, device: Devicelike | None = None, requires_grad: bool = False ) -> wp.array | list: """Build wp.array (or list for string dtype) from count, dtype, default and overrides. For string dtype, returns a Python list[str] instead of a Warp array. """ if self.values is None or len(self.values) == 0: # No values provided, use default for all arr = [self.default] * count elif self.is_custom_frequency: # Custom frequency: vals is a list, replace None with defaults and pad/truncate as needed arr = [val if val is not None else self.default for val in self.values] arr = arr + [self.default] * max(0, count - len(arr)) arr = arr[:count] # Truncate if needed else: # Enum frequency: vals is a dict, use get() to fill gaps with defaults arr = [self.values.get(i, self.default) for i in range(count)] # String dtype: return as Python list instead of warp array if self.dtype is str: return arr return wp.array(arr, dtype=self.dtype, requires_grad=requires_grad, device=device) @dataclass class CustomFrequency: """ Represents a custom frequency definition for the ModelBuilder. Custom frequencies allow defining entity types beyond the built-in ones (BODY, SHAPE, JOINT, etc.). They must be registered via :meth:`ModelBuilder.add_custom_frequency` before any custom attributes using them can be added. The optional ``usd_prim_filter`` callback enables automatic USD parsing for this frequency. When provided, :meth:`ModelBuilder.add_usd` will call this function for each prim in the USD stage to determine whether custom attribute values with this frequency should be extracted from it. See :ref:`custom_attributes` for more information on custom frequencies. Example: .. code-block:: python # Define a custom frequency for MuJoCo actuators with USD parsing support def is_actuator_prim(prim: Usd.Prim, context: dict[str, Any]) -> bool: return prim.GetTypeName() == "MjcActuator" builder.add_custom_frequency( ModelBuilder.CustomFrequency( name="actuator", namespace="mujoco", usd_prim_filter=is_actuator_prim, ) ) """ name: str """The name of the custom frequency (e.g., ``"actuator"``, ``"pair"``).""" namespace: str | None = None """Namespace for the custom frequency. If provided, the frequency key becomes ``"namespace:name"``. If None, the custom frequency is registered without a namespace.""" usd_prim_filter: Callable[[Usd.Prim, dict[str, Any]], bool] | None = None """Select which USD prims are used for this frequency. Called by :meth:`newton.ModelBuilder.add_usd` for each visited prim with: - ``prim``: current ``Usd.Prim`` - ``context``: callback context dictionary with ``prim``, ``result``, and ``builder`` Return ``True`` to parse this prim for the frequency, or ``False`` to skip it. If this is ``None``, the frequency is not parsed automatically from USD. Example: .. code-block:: python def is_actuator_prim(prim: Usd.Prim, context: dict[str, Any]) -> bool: return prim.GetTypeName() == "MjcActuator" """ usd_entry_expander: Callable[[Usd.Prim, dict[str, Any]], Iterable[dict[str, Any]]] | None = None """Build row entries for a matching USD prim. Called by :meth:`newton.ModelBuilder.add_usd` after :attr:`usd_prim_filter` returns ``True``. Return an iterable of dictionaries; each dictionary is one row passed to :meth:`newton.ModelBuilder.add_custom_values`. Use this when one prim should produce multiple rows. Missing keys in a row are filled with ``None`` so defaults still apply. Returning an empty iterable adds no rows. See also: When this callback is set, :meth:`newton.ModelBuilder.add_usd` does not run default per-attribute extraction for this frequency on matched prims (``usd_attribute_name`` / ``usd_value_transformer``). Example: .. code-block:: python def expand_tendon_rows(prim: Usd.Prim, context: dict[str, Any]) -> Iterable[dict[str, Any]]: for joint_path in prim.GetCustomDataByKey("joint_paths") or []: yield {"joint": joint_path, "stiffness": prim.GetCustomDataByKey("stiffness")} """ def __post_init__(self): """Validate frequency naming and callback relationships.""" if not self.name or ":" in self.name: raise ValueError(f"name must be non-empty and colon-free, got '{self.name}'") if self.namespace is not None and (not self.namespace or ":" in self.namespace): raise ValueError(f"namespace must be non-empty and colon-free, got '{self.namespace}'") if self.usd_entry_expander is not None and self.usd_prim_filter is None: raise ValueError("usd_entry_expander requires usd_prim_filter") @property def key(self) -> str: """The key of the custom frequency (e.g., ``"mujoco:actuator"`` or ``"pair"``).""" return f"{self.namespace}:{self.name}" if self.namespace else self.name def __init__(self, up_axis: AxisType = Axis.Z, gravity: float = -9.81): """ Initializes a new ModelBuilder instance for constructing simulation models. Args: up_axis: The axis to use as the "up" direction in the simulation. Defaults to Axis.Z. gravity: The magnitude of gravity to apply along the up axis. Defaults to -9.81. """ self.world_count: int = 0 """Number of worlds accumulated for :attr:`Model.world_count`.""" # region defaults self.default_shape_cfg = ModelBuilder.ShapeConfig() """Default shape configuration used when shape-creation methods are called with ``cfg=None``. Update this object before adding shapes to set default contact/material properties.""" self.default_joint_cfg = ModelBuilder.JointDofConfig() """Default joint DoF configuration used when joint DoF configuration is omitted.""" self.default_particle_radius = 0.1 """Default particle radius used when particle radius is not provided explicitly.""" self.default_tri_ke = 100.0 """Default triangle elastic stiffness for cloth/soft-triangle constraints.""" self.default_tri_ka = 100.0 """Default triangle area stiffness for cloth/soft-triangle constraints.""" self.default_tri_kd = 10.0 """Default triangle damping for cloth/soft-triangle constraints.""" self.default_tri_drag = 0.0 """Default aerodynamic drag coefficient for triangle elements.""" self.default_tri_lift = 0.0 """Default aerodynamic lift coefficient for triangle elements.""" self.default_spring_ke = 100.0 """Default spring elastic stiffness for distance constraints.""" self.default_spring_kd = 0.0 """Default spring damping for distance constraints.""" self.default_edge_ke = 100.0 """Default edge-bending elastic stiffness.""" self.default_edge_kd = 0.0 """Default edge-bending damping.""" self.default_tet_k_mu = 1.0e3 """Default first Lame parameter [Pa] for tetrahedral elements.""" self.default_tet_k_lambda = 1.0e3 """Default second Lame parameter [Pa] for tetrahedral elements.""" self.default_tet_k_damp = 0.0 """Default damping stiffness for tetrahedral elements.""" self.default_tet_density = 1.0 """Default density [kg/m^3] for tetrahedral soft bodies.""" self._default_body_armature = 0.0 # endregion # region compiler settings (similar to MuJoCo) self.balance_inertia: bool = True """Whether to automatically correct rigid body inertia tensors that violate the triangle inequality. When True, adds a scalar multiple of the identity matrix to preserve rotation structure while ensuring physical validity (I1 + I2 >= I3 for principal moments). Default: True.""" self.bound_mass: float | None = None """Minimum allowed mass value for rigid bodies [kg]. If set, any body mass below this value will be clamped to this minimum. Set to None to disable mass clamping. Default: None.""" self.bound_inertia: float | None = None """Minimum allowed eigenvalue for rigid body inertia tensors [kg*m^2]. If set, ensures all principal moments of inertia are at least this value. Set to None to disable inertia eigenvalue clamping. Default: None.""" self.validate_inertia_detailed: bool = False """Whether to use detailed (slower) inertia validation that provides per-body warnings. When False, uses a fast GPU kernel that reports only the total number of corrected bodies. When True, uses a CPU implementation that reports specific issues for each body. Both modes produce semantically identical corrected values on the returned :class:`Model`. Neither mode modifies the builder's internal state — corrected values live only on the Model. Default: False.""" # endregion # particles self.particle_q: list[Vec3] = [] """Particle positions [m] accumulated for :attr:`Model.particle_q`.""" self.particle_qd: list[Vec3] = [] """Particle velocities [m/s] accumulated for :attr:`Model.particle_qd`.""" self.particle_mass: list[float] = [] """Particle masses [kg] accumulated for :attr:`Model.particle_mass`.""" self.particle_radius: list[float] = [] """Particle radii [m] accumulated for :attr:`Model.particle_radius`.""" self.particle_flags: list[int | ParticleFlags] = [] """Particle flags accumulated for :attr:`Model.particle_flags`.""" self.particle_max_velocity: float = 1e5 """Maximum particle velocity [m/s] propagated to :attr:`Model.particle_max_velocity`.""" self.particle_color_groups: list[Any] = [] """Particle color groups accumulated for :attr:`Model.particle_color_groups`.""" self.particle_world: list[int] = [] """World indices accumulated for :attr:`Model.particle_world`.""" # shapes (each shape has an entry in these arrays) self.shape_label: list[str] = [] """Shape labels accumulated for :attr:`Model.shape_label`.""" self.shape_transform: list[Transform] = [] """Shape-to-body transforms accumulated for :attr:`Model.shape_transform`.""" self.shape_body: list[int] = [] """Body indices accumulated for :attr:`Model.shape_body`.""" self.shape_flags: list[int] = [] """Shape flags accumulated for :attr:`Model.shape_flags`.""" self.shape_type: list[int] = [] """Geometry type ids accumulated for :attr:`Model.shape_type`.""" self.shape_scale: list[Vec3] = [] """Shape scales accumulated for :attr:`Model.shape_scale`.""" self.shape_source: list[Any] = [] """Source geometry objects accumulated for :attr:`Model.shape_source`.""" self.shape_color: list[Vec3] = [] """Resolved display colors accumulated for :attr:`Model.shape_color`.""" self.shape_is_solid: list[bool] = [] """Solid-vs-hollow flags accumulated for :attr:`Model.shape_is_solid`.""" self.shape_margin: list[float] = [] """Shape margins [m] accumulated for :attr:`Model.shape_margin`.""" self.shape_material_ke: list[float] = [] """Contact stiffness values [N/m] accumulated for :attr:`Model.shape_material_ke`.""" self.shape_material_kd: list[float] = [] """Contact damping values accumulated for :attr:`Model.shape_material_kd`.""" self.shape_material_kf: list[float] = [] """Friction stiffness values accumulated for :attr:`Model.shape_material_kf`.""" self.shape_material_ka: list[float] = [] """Adhesion distances [m] accumulated for :attr:`Model.shape_material_ka`.""" self.shape_material_mu: list[float] = [] """Friction coefficients accumulated for :attr:`Model.shape_material_mu`.""" self.shape_material_restitution: list[float] = [] """Restitution coefficients accumulated for :attr:`Model.shape_material_restitution`.""" self.shape_material_mu_torsional: list[float] = [] """Torsional friction coefficients accumulated for :attr:`Model.shape_material_mu_torsional`.""" self.shape_material_mu_rolling: list[float] = [] """Rolling friction coefficients accumulated for :attr:`Model.shape_material_mu_rolling`.""" self.shape_material_kh: list[float] = [] """Hydroelastic stiffness values accumulated for :attr:`Model.shape_material_kh`.""" self.shape_gap: list[float] = [] """Contact gaps [m] accumulated for :attr:`Model.shape_gap`.""" self.shape_collision_group: list[int] = [] """Collision groups accumulated for :attr:`Model.shape_collision_group`.""" self.shape_collision_radius: list[float] = [] """Broadphase collision radii [m] accumulated for :attr:`Model.shape_collision_radius`.""" self.shape_world: list[int] = [] """World indices accumulated for :attr:`Model.shape_world`.""" self.shape_sdf_narrow_band_range: list[tuple[float, float]] = [] """Per-shape SDF narrow-band ranges retained until :meth:`finalize ` generates SDF data.""" self.shape_sdf_target_voxel_size: list[float | None] = [] """Per-shape target SDF voxel sizes retained until :meth:`finalize `.""" self.shape_sdf_max_resolution: list[int | None] = [] """Per-shape SDF maximum resolutions retained until :meth:`finalize `.""" self.shape_sdf_texture_format: list[str] = [] """Per-shape SDF texture format retained until :meth:`finalize `.""" # Mesh SDF storage (texture SDF arrays created at finalize) # filtering to ignore certain collision pairs self.shape_collision_filter_pairs: list[tuple[int, int]] = [] """Shape collision filter pairs accumulated for :attr:`Model.shape_collision_filter_pairs`.""" self._requested_contact_attributes: set[str] = set() """Optional contact attributes requested via :meth:`request_contact_attributes`.""" self._requested_state_attributes: set[str] = set() """Optional state attributes requested via :meth:`request_state_attributes`.""" # springs self.spring_indices: list[int] = [] """Spring particle index pairs accumulated for :attr:`Model.spring_indices`.""" self.spring_rest_length: list[float] = [] """Spring rest lengths [m] accumulated for :attr:`Model.spring_rest_length`.""" self.spring_stiffness: list[float] = [] """Spring stiffness values [N/m] accumulated for :attr:`Model.spring_stiffness`.""" self.spring_damping: list[float] = [] """Spring damping values accumulated for :attr:`Model.spring_damping`.""" self.spring_control: list[float] = [] """Spring control activations accumulated for :attr:`Model.spring_control`.""" # triangles self.tri_indices: list[tuple[int, int, int]] = [] """Triangle connectivity accumulated for :attr:`Model.tri_indices`.""" self.tri_poses: list[Mat22] = [] """Triangle rest-pose 2x2 matrices accumulated for :attr:`Model.tri_poses`.""" self.tri_activations: list[float] = [] """Triangle activations accumulated for :attr:`Model.tri_activations`.""" self.tri_materials: list[tuple[float, float, float, float, float]] = [] """Triangle material rows accumulated for :attr:`Model.tri_materials`.""" self.tri_areas: list[float] = [] """Triangle rest areas [m^2] accumulated for :attr:`Model.tri_areas`.""" # edges (bending) self.edge_indices: list[tuple[int, int, int, int]] = [] """Bending-edge connectivity accumulated for :attr:`Model.edge_indices`.""" self.edge_rest_angle: list[float] = [] """Edge rest angles [rad] accumulated for :attr:`Model.edge_rest_angle`.""" self.edge_rest_length: list[float] = [] """Edge rest lengths [m] accumulated for :attr:`Model.edge_rest_length`.""" self.edge_bending_properties: list[tuple[float, float]] = [] """Bending stiffness/damping rows accumulated for :attr:`Model.edge_bending_properties`.""" # tetrahedra self.tet_indices: list[tuple[int, int, int, int]] = [] """Tetrahedral connectivity accumulated for :attr:`Model.tet_indices`.""" self.tet_poses: list[Mat33] = [] """Tetrahedral rest-pose 3x3 matrices accumulated for :attr:`Model.tet_poses`.""" self.tet_activations: list[float] = [] """Tetrahedral activations accumulated for :attr:`Model.tet_activations`.""" self.tet_materials: list[tuple[float, float, float]] = [] """Tetrahedral material rows accumulated for :attr:`Model.tet_materials`.""" # muscles self.muscle_start: list[int] = [] """Muscle waypoint start indices accumulated for :attr:`Model.muscle_start`.""" self.muscle_params: list[tuple[float, float, float, float, float]] = [] """Muscle parameter rows accumulated for :attr:`Model.muscle_params`.""" self.muscle_activations: list[float] = [] """Muscle activations accumulated for :attr:`Model.muscle_activations`.""" self.muscle_bodies: list[int] = [] """Muscle waypoint body indices accumulated for :attr:`Model.muscle_bodies`.""" self.muscle_points: list[Vec3] = [] """Muscle waypoint local offsets accumulated for :attr:`Model.muscle_points`.""" # rigid bodies self.body_mass: list[float] = [] """Body masses [kg] accumulated for :attr:`Model.body_mass`.""" self.body_inertia: list[Mat33] = [] """Body inertia tensors accumulated for :attr:`Model.body_inertia`.""" self.body_inv_mass: list[float] = [] """Inverse body masses accumulated for :attr:`Model.body_inv_mass`.""" self.body_inv_inertia: list[Mat33] = [] """Inverse body inertia tensors accumulated for :attr:`Model.body_inv_inertia`.""" self.body_com: list[Vec3] = [] """Body centers of mass [m] accumulated for :attr:`Model.body_com`.""" self.body_q: list[Transform] = [] """Body poses accumulated for :attr:`Model.body_q`.""" self.body_qd: list[Vec6] = [] """Body spatial velocities accumulated for :attr:`Model.body_qd`.""" self.body_label: list[str] = [] """Body labels accumulated for :attr:`Model.body_label`.""" self.body_lock_inertia: list[bool] = [] """Per-body inertia-lock flags retained while composing bodies in the builder.""" self.body_flags: list[int] = [] """Body flags accumulated for :attr:`Model.body_flags`.""" self.body_shapes: dict[int, list[int]] = {-1: []} """Mapping from body index to attached shape indices, finalized into :attr:`Model.body_shapes`.""" self.body_world: list[int] = [] """World indices accumulated for :attr:`Model.body_world`.""" self.body_color_groups: list[Any] = [] """Rigid-body color groups accumulated for :attr:`Model.body_color_groups`.""" # rigid joints self.joint_parent: list[int] = [] """Parent body indices accumulated for :attr:`Model.joint_parent`.""" self.joint_parents: dict[int, list[int]] = {} """Mapping from child body index to parent body indices used while composing articulations.""" self.joint_children: dict[int, list[int]] = {} """Mapping from parent body index to child body indices used while composing articulations.""" self.joint_child: list[int] = [] """Child body indices accumulated for :attr:`Model.joint_child`.""" self.joint_axis: list[Vec3] = [] """Joint axes accumulated for :attr:`Model.joint_axis`.""" self.joint_X_p: list[Transform] = [] """Parent-frame joint transforms accumulated for :attr:`Model.joint_X_p`.""" self.joint_X_c: list[Transform] = [] """Child-frame joint transforms accumulated for :attr:`Model.joint_X_c`.""" self.joint_q: list[float] = [] """Joint coordinates accumulated for :attr:`Model.joint_q`.""" self.joint_qd: list[float] = [] """Joint velocities accumulated for :attr:`Model.joint_qd`.""" self.joint_cts: list[float] = [] """Per-joint constraint placeholders used to derive finalized joint-constraint counts.""" self.joint_f: list[float] = [] """Joint forces accumulated for :attr:`Model.joint_f`.""" self.joint_act: list[float] = [] """Joint actuation inputs accumulated for :attr:`Model.joint_act`.""" self.joint_type: list[int] = [] """Joint type ids accumulated for :attr:`Model.joint_type`.""" self.joint_label: list[str] = [] """Joint labels accumulated for :attr:`Model.joint_label`.""" self.joint_armature: list[float] = [] """Joint armature values accumulated for :attr:`Model.joint_armature`.""" self.joint_target_mode: list[int] = [] """Joint target modes accumulated for :attr:`Model.joint_target_mode`.""" self.joint_target_ke: list[float] = [] """Joint target stiffness values accumulated for :attr:`Model.joint_target_ke`.""" self.joint_target_kd: list[float] = [] """Joint target damping values accumulated for :attr:`Model.joint_target_kd`.""" self.joint_limit_lower: list[float] = [] """Lower joint limits accumulated for :attr:`Model.joint_limit_lower`.""" self.joint_limit_upper: list[float] = [] """Upper joint limits accumulated for :attr:`Model.joint_limit_upper`.""" self.joint_limit_ke: list[float] = [] """Joint limit stiffness values accumulated for :attr:`Model.joint_limit_ke`.""" self.joint_limit_kd: list[float] = [] """Joint limit damping values accumulated for :attr:`Model.joint_limit_kd`.""" self.joint_target_pos: list[float] = [] """Joint position targets accumulated for :attr:`Model.joint_target_pos`.""" self.joint_target_vel: list[float] = [] """Joint velocity targets accumulated for :attr:`Model.joint_target_vel`.""" self.joint_effort_limit: list[float] = [] """Joint effort limits accumulated for :attr:`Model.joint_effort_limit`.""" self.joint_velocity_limit: list[float] = [] """Joint velocity limits accumulated for :attr:`Model.joint_velocity_limit`.""" self.joint_friction: list[float] = [] """Joint friction values accumulated for :attr:`Model.joint_friction`.""" self.joint_twist_lower: list[float] = [] """Lower twist limits accumulated for :attr:`Model.joint_twist_lower`.""" self.joint_twist_upper: list[float] = [] """Upper twist limits accumulated for :attr:`Model.joint_twist_upper`.""" self.joint_enabled: list[bool] = [] """Joint enabled flags accumulated for :attr:`Model.joint_enabled`.""" self.joint_q_start: list[int] = [] """Joint coordinate start indices accumulated for :attr:`Model.joint_q_start`.""" self.joint_qd_start: list[int] = [] """Joint DoF start indices accumulated for :attr:`Model.joint_qd_start`.""" self.joint_cts_start: list[int] = [] """Joint-constraint start indices retained while building per-joint constraint data.""" self.joint_dof_dim: list[tuple[int, int]] = [] """Per-joint linear/angular DoF dimensions accumulated for :attr:`Model.joint_dof_dim`.""" self.joint_world: list[int] = [] """World indices accumulated for :attr:`Model.joint_world`.""" self.joint_articulation: list[int] = [] """Articulation indices accumulated for :attr:`Model.joint_articulation`.""" self.articulation_start: list[int] = [] """Articulation start indices accumulated for :attr:`Model.articulation_start`.""" self.articulation_label: list[str] = [] """Articulation labels accumulated for :attr:`Model.articulation_label`.""" self.articulation_world: list[int] = [] """World indices accumulated for :attr:`Model.articulation_world`.""" self.joint_dof_count: int = 0 """Total joint DoF count propagated to :attr:`Model.joint_dof_count`.""" self.joint_coord_count: int = 0 """Total joint coordinate count propagated to :attr:`Model.joint_coord_count`.""" self.joint_constraint_count: int = 0 """Total joint constraint count propagated to :attr:`Model.joint_constraint_count`.""" self._current_world: int = -1 """Internal world context backing the read-only :attr:`current_world` property.""" self.up_axis: Axis = Axis.from_any(up_axis) """Up axis used when expanding scalar gravity into per-world gravity vectors.""" self.gravity: float = gravity """Gravity acceleration [m/s^2] applied along :attr:`up_axis` for newly added worlds.""" self.world_gravity: list[Vec3] = [] """Per-world gravity vectors retained until :meth:`finalize ` populates :attr:`Model.gravity`.""" self.rigid_gap: float = 0.1 """Default rigid contact gap [m] applied when adding a shape whose ``ModelBuilder.ShapeConfig.gap`` is ``None``. The resolved per-shape values are later propagated to :attr:`Model.shape_gap`.""" self.num_rigid_contacts_per_world: int | None = None """Optional per-world rigid-contact allocation budget used to set :attr:`Model.rigid_contact_max`.""" # equality constraints self.equality_constraint_type: list[EqType] = [] """Equality constraint types accumulated for :attr:`Model.equality_constraint_type`.""" self.equality_constraint_body1: list[int] = [] """First body indices accumulated for :attr:`Model.equality_constraint_body1`.""" self.equality_constraint_body2: list[int] = [] """Second body indices accumulated for :attr:`Model.equality_constraint_body2`.""" self.equality_constraint_anchor: list[Vec3] = [] """Equality constraint anchors accumulated for :attr:`Model.equality_constraint_anchor`.""" self.equality_constraint_relpose: list[Transform] = [] """Relative poses accumulated for :attr:`Model.equality_constraint_relpose`.""" self.equality_constraint_torquescale: list[float] = [] """Torque scales accumulated for :attr:`Model.equality_constraint_torquescale`.""" self.equality_constraint_joint1: list[int] = [] """First joint indices accumulated for :attr:`Model.equality_constraint_joint1`.""" self.equality_constraint_joint2: list[int] = [] """Second joint indices accumulated for :attr:`Model.equality_constraint_joint2`.""" self.equality_constraint_polycoef: list[list[float]] = [] """Polynomial coefficient rows accumulated for :attr:`Model.equality_constraint_polycoef`.""" self.equality_constraint_label: list[str] = [] """Equality constraint labels accumulated for :attr:`Model.equality_constraint_label`.""" self.equality_constraint_enabled: list[bool] = [] """Equality constraint enabled flags accumulated for :attr:`Model.equality_constraint_enabled`.""" self.equality_constraint_world: list[int] = [] """World indices accumulated for :attr:`Model.equality_constraint_world`.""" # mimic constraints self.constraint_mimic_joint0: list[int] = [] """Follower joint indices accumulated for :attr:`Model.constraint_mimic_joint0`.""" self.constraint_mimic_joint1: list[int] = [] """Leader joint indices accumulated for :attr:`Model.constraint_mimic_joint1`.""" self.constraint_mimic_coef0: list[float] = [] """Offset coefficients accumulated for :attr:`Model.constraint_mimic_coef0`.""" self.constraint_mimic_coef1: list[float] = [] """Scale coefficients accumulated for :attr:`Model.constraint_mimic_coef1`.""" self.constraint_mimic_enabled: list[bool] = [] """Enabled flags accumulated for :attr:`Model.constraint_mimic_enabled`.""" self.constraint_mimic_label: list[str] = [] """Mimic constraint labels accumulated for :attr:`Model.constraint_mimic_label`.""" self.constraint_mimic_world: list[int] = [] """World indices accumulated for :attr:`Model.constraint_mimic_world`.""" # per-world entity start indices self.particle_world_start: list[int] = [] """Per-world particle starts accumulated for :attr:`Model.particle_world_start`.""" self.body_world_start: list[int] = [] """Per-world body starts accumulated for :attr:`Model.body_world_start`.""" self.shape_world_start: list[int] = [] """Per-world shape starts accumulated for :attr:`Model.shape_world_start`.""" self.joint_world_start: list[int] = [] """Per-world joint starts accumulated for :attr:`Model.joint_world_start`.""" self.articulation_world_start: list[int] = [] """Per-world articulation starts accumulated for :attr:`Model.articulation_world_start`.""" self.equality_constraint_world_start: list[int] = [] """Per-world equality-constraint starts accumulated for :attr:`Model.equality_constraint_world_start`.""" self.joint_dof_world_start: list[int] = [] """Per-world joint DoF starts accumulated for :attr:`Model.joint_dof_world_start`.""" self.joint_coord_world_start: list[int] = [] """Per-world joint-coordinate starts accumulated for :attr:`Model.joint_coord_world_start`.""" self.joint_constraint_world_start: list[int] = [] """Per-world joint-constraint starts accumulated for :attr:`Model.joint_constraint_world_start`.""" # Custom attributes (user-defined per-frequency arrays) self.custom_attributes: dict[str, ModelBuilder.CustomAttribute] = {} """Registered custom attributes to materialize during :meth:`finalize `.""" # Registered custom frequencies (must be registered before adding attributes with that frequency) self.custom_frequencies: dict[str, ModelBuilder.CustomFrequency] = {} """Registered custom string frequencies keyed by ``namespace:name`` or bare name.""" # Incrementally maintained counts for custom string frequencies self._custom_frequency_counts: dict[str, int] = {} """Running counts for custom string frequencies used to size custom attribute arrays.""" # Actuator entries (accumulated during add_actuator calls) # Key is (actuator_class, scalar_params_tuple) to separate instances with different scalar params self.actuator_entries: dict[tuple[type[Actuator], tuple[Any, ...]], ModelBuilder.ActuatorEntry] = {} """Actuator entry groups accumulated from :meth:`add_actuator`, keyed by class and scalar parameters.""" def add_shape_collision_filter_pair(self, shape_a: int, shape_b: int) -> None: """Add a collision filter pair in canonical order. Args: shape_a: First shape index shape_b: Second shape index """ self.shape_collision_filter_pairs.append((min(shape_a, shape_b), max(shape_a, shape_b))) def add_custom_attribute(self, attribute: CustomAttribute) -> None: """ Define a custom per-entity attribute to be added to the Model. See :ref:`custom_attributes` for more information. For attributes with custom string frequencies (not enum frequencies like BODY, SHAPE, etc.), the frequency must be registered first via :meth:`add_custom_frequency`. This ensures explicit declaration of custom entity types and enables USD parsing support. Args: attribute: The custom attribute to add. Raises: ValueError: If the attribute key already exists with incompatible specification, if the attribute uses a custom string frequency that hasn't been registered, or if ``usd_attribute_name`` is ``"*"`` without a ``usd_value_transformer``. Example: .. doctest:: builder = newton.ModelBuilder() builder.add_custom_attribute( newton.ModelBuilder.CustomAttribute( name="my_attribute", frequency=newton.Model.AttributeFrequency.BODY, dtype=wp.float32, default=20.0, assignment=newton.Model.AttributeAssignment.MODEL, namespace="my_namespace", ) ) builder.add_body(custom_attributes={"my_namespace:my_attribute": 30.0}) builder.add_body() # we leave out the custom_attributes, so the attribute will use the default value 20.0 model = builder.finalize() # the model has now a Model.AttributeNamespace object with the name "my_namespace" # and an attribute "my_attribute" that is a wp.array of shape (body_count, 1) # with the default value 20.0 assert np.allclose(model.my_namespace.my_attribute.numpy(), [30.0, 20.0]) """ key = attribute.key existing = self.custom_attributes.get(key) if existing: # validate that specification matches exactly if ( existing.frequency != attribute.frequency or existing.dtype != attribute.dtype or existing.assignment != attribute.assignment or existing.namespace != attribute.namespace or existing.references != attribute.references ): raise ValueError(f"Custom attribute '{key}' already exists with incompatible spec") return # Validate that custom frequencies are registered before use if attribute.is_custom_frequency: freq_key = attribute.frequency if freq_key not in self.custom_frequencies: raise ValueError( f"Custom frequency '{freq_key}' is not registered. " f"Please register it first using add_custom_frequency() before adding attributes with this frequency." ) # Validate that wildcard USD attributes have a transformer if attribute.usd_attribute_name == "*" and attribute.usd_value_transformer is None: raise ValueError( f"Custom attribute '{key}' uses usd_attribute_name='*' but no usd_value_transformer is provided. " f"A wildcard USD attribute requires a usd_value_transformer to compute values from prim data." ) self.custom_attributes[key] = attribute def add_custom_frequency(self, frequency: CustomFrequency) -> None: """ Register a custom frequency for the builder. Custom frequencies must be registered before adding any custom attributes that use them. This enables explicit declaration of custom entity types and optionally provides USD parsing support via the ``usd_prim_filter`` callback. This method is idempotent: registering the same frequency multiple times is silently ignored (useful when loading multiple files that all register the same frequencies). Args: frequency: A :class:`CustomFrequency` object with full configuration. Example: .. code-block:: python # Full registration with USD parsing support builder.add_custom_frequency( ModelBuilder.CustomFrequency( name="actuator", namespace="mujoco", usd_prim_filter=is_actuator_prim, ) ) """ freq_obj = frequency freq_key = freq_obj.key if freq_key in self.custom_frequencies: existing = self.custom_frequencies[freq_key] if ( existing.usd_prim_filter is not freq_obj.usd_prim_filter or existing.usd_entry_expander is not freq_obj.usd_entry_expander ): raise ValueError(f"Custom frequency '{freq_key}' is already registered with different callbacks.") # Already registered with equivalent callbacks - silently skip return self.custom_frequencies[freq_key] = freq_obj if freq_key not in self._custom_frequency_counts: self._custom_frequency_counts[freq_key] = 0 def has_custom_attribute(self, key: str) -> bool: """Check if a custom attribute is defined.""" return key in self.custom_attributes def get_custom_attributes_by_frequency( self, frequencies: Sequence[Model.AttributeFrequency | str] ) -> list[CustomAttribute]: """ Get custom attributes by frequency. This is useful for processing custom attributes for different kinds of simulation objects. For example, you can get all the custom attributes for bodies, shapes, joints, etc. Args: frequencies: The frequencies to get custom attributes for. Returns: Custom attributes matching the requested frequencies. """ return [attr for attr in self.custom_attributes.values() if attr.frequency in frequencies] def get_custom_frequency_keys(self) -> set[str]: """Return set of custom frequency keys (string frequencies) defined in this builder.""" return set(self._custom_frequency_counts.keys()) def add_custom_values(self, **kwargs: Any) -> dict[str, int]: """Append values to custom attributes with custom string frequencies. Each keyword argument specifies an attribute key and the value to append. Values are stored in a list and appended sequentially for robust indexing. Only works with attributes that have a custom string frequency (not built-in enum frequencies). This is useful for custom entity types that aren't built into the model, such as user-defined groupings or solver-specific data. Args: **kwargs: Mapping of attribute keys to values. Keys should be the full attribute key (e.g., ``"mujoco:pair_geom1"`` or just ``"my_attr"`` if no namespace). Returns: A mapping from attribute keys to the index where each value was added. If all attributes had the same count before the call, all indices will be equal. Raises: AttributeError: If an attribute key is not defined. TypeError: If an attribute has an enum frequency (must have custom frequency). Example: .. code-block:: python builder.add_custom_values( **{ "mujoco:pair_geom1": 0, "mujoco:pair_geom2": 1, "mujoco:pair_world": builder.current_world, } ) # Returns: {'mujoco:pair_geom1': 0, 'mujoco:pair_geom2': 0, 'mujoco:pair_world': 0} """ indices: dict[str, int] = {} frequency_indices: dict[str, int] = {} # Track indices assigned per frequency in this call for key, value in kwargs.items(): attr = self.custom_attributes.get(key) if attr is None: raise AttributeError( f"Custom attribute '{key}' is not defined. Please declare it first using add_custom_attribute()." ) if not attr.is_custom_frequency: raise TypeError( f"Custom attribute '{key}' has frequency={attr.frequency}, " f"but add_custom_values() only works with custom frequency attributes." ) # Ensure attr.values is initialized if attr.values is None: attr.values = [] freq_key = attr.frequency assert isinstance(freq_key, str), f"Custom frequency '{freq_key}' is not a string" # Determine index for this frequency (same index for all attrs with same frequency in this call) if freq_key not in frequency_indices: # First attribute with this frequency - use authoritative counter current_count = self._custom_frequency_counts.get(freq_key, 0) frequency_indices[freq_key] = current_count # Update authoritative counter for this frequency self._custom_frequency_counts[freq_key] = current_count + 1 idx = frequency_indices[freq_key] # Ensure attr.values has length at least idx+1, padding with None as needed while len(attr.values) <= idx: attr.values.append(None) # Assign value at the correct index attr.values[idx] = value indices[key] = idx return indices def add_custom_values_batch(self, entries: Sequence[dict[str, Any]]) -> list[dict[str, int]]: """Append multiple custom-frequency rows in a single call. Args: entries: Sequence of rows where each row maps custom attribute keys to values. Each row is forwarded to :meth:`add_custom_values`. Returns: Index maps returned by :meth:`add_custom_values` for each row. """ out: list[dict[str, int]] = [] for row in entries: out.append(self.add_custom_values(**row)) return out def _process_custom_attributes( self, entity_index: int | list[int], custom_attrs: dict[str, Any], expected_frequency: Model.AttributeFrequency, ) -> None: """Process custom attributes from kwargs and assign them to an entity. This method validates that custom attributes exist with the correct frequency, then assigns values to the specific entity. The assignment is inferred from the attribute definition. Attribute names can optionally include a namespace prefix in the format "namespace:attr_name". If no namespace prefix is provided, the attribute is assumed to be in the default namespace (None). Args: entity_index: Index of the entity (body, shape, joint, etc.). Can be a single index or a list of indices. custom_attrs: Dictionary of custom attribute names to values. Keys can be "attr_name" or "namespace:attr_name". Values can be a single value or a list of values. expected_frequency: Expected frequency for these attributes. """ for attr_key, value in custom_attrs.items(): # Parse namespace prefix if present (format: "namespace:attr_name" or "attr_name") full_key = attr_key # Ensure the custom attribute is defined custom_attr = self.custom_attributes.get(full_key) if custom_attr is None: raise AttributeError( f"Custom attribute '{full_key}' is not defined. " f"Please declare it first using add_custom_attribute()." ) # Validate frequency matches if custom_attr.frequency != expected_frequency: raise ValueError( f"Custom attribute '{full_key}' has frequency {custom_attr.frequency}, " f"but expected {expected_frequency} for this entity type" ) # Set the value for this specific entity if custom_attr.values is None: custom_attr.values = {} # Fill in the value(s) if isinstance(entity_index, list): value_is_sequence = isinstance(value, (list, tuple)) if isinstance(value, np.ndarray): value_is_sequence = value.ndim != 0 if value_is_sequence: if len(value) != len(entity_index): raise ValueError(f"Expected {len(entity_index)} values, got {len(value)}") custom_attr.values.update(zip(entity_index, value, strict=False)) else: custom_attr.values.update((idx, value) for idx in entity_index) else: custom_attr.values[entity_index] = value def _process_joint_custom_attributes( self, joint_index: int, custom_attrs: dict[str, Any], ) -> None: """Process custom attributes from kwargs for joints, supporting multiple frequencies. Joint attributes are processed based on their declared frequency: - JOINT frequency: Single value per joint - JOINT_DOF frequency: List or dict of values for each DOF - JOINT_COORD frequency: List or dict of values for each coordinate For DOF and COORD attributes, values can be: - A list with length matching the joint's DOF/coordinate count (all DOFs get values) - A dict mapping DOF/coord indices to values (only specified indices get values, rest use defaults) - A single scalar value, which is broadcast (replicated) to all DOFs/coordinates of the joint For joints with zero DOFs (e.g., fixed joints), JOINT_DOF attributes are silently skipped regardless of the value passed. When using dict format, unspecified indices will be filled with the attribute's default value by :meth:`finalize `. Args: joint_index: Index of the joint custom_attrs: Dictionary of custom attribute names to values """ def apply_indexed_values( *, value: Any, attr_key: str, expected_frequency: Model.AttributeFrequency, index_start: int, index_count: int, index_label: str, count_label: str, length_error_template: str, ) -> None: # For joints with zero DOFs/coords (e.g., fixed joints), there is nothing to assign. if index_count == 0: return if isinstance(value, dict): for offset, offset_value in value.items(): if not isinstance(offset, int): raise TypeError( f"{expected_frequency.name} attribute '{attr_key}' dict keys must be integers " f"({index_label} indices), got {type(offset)}" ) if offset < 0 or offset >= index_count: raise ValueError( f"{expected_frequency.name} attribute '{attr_key}' has invalid {index_label} index " f"{offset} (joint has {index_count} {count_label})" ) self._process_custom_attributes( entity_index=index_start + offset, custom_attrs={attr_key: offset_value}, expected_frequency=expected_frequency, ) return value_sanitized = value if isinstance(value_sanitized, np.ndarray): if value_sanitized.ndim == 0: value_sanitized = value_sanitized.item() else: value_sanitized = value_sanitized.tolist() if not isinstance(value_sanitized, (list, tuple)): # Broadcast a single scalar value to all DOFs/coords of the joint. value_sanitized = [value_sanitized] * index_count actual = len(value_sanitized) if actual != index_count: raise ValueError(length_error_template.format(attr_key=attr_key, actual=actual, expected=index_count)) for i, indexed_value in enumerate(value_sanitized): self._process_custom_attributes( entity_index=index_start + i, custom_attrs={attr_key: indexed_value}, expected_frequency=expected_frequency, ) for attr_key, value in custom_attrs.items(): # Look up the attribute to determine its frequency custom_attr = self.custom_attributes.get(attr_key) if custom_attr is None: raise AttributeError( f"Custom attribute '{attr_key}' is not defined. " f"Please declare it first using add_custom_attribute()." ) # Process based on declared frequency if custom_attr.frequency == Model.AttributeFrequency.JOINT: # Single value per joint self._process_custom_attributes( entity_index=joint_index, custom_attrs={attr_key: value}, expected_frequency=Model.AttributeFrequency.JOINT, ) elif custom_attr.frequency in ( Model.AttributeFrequency.JOINT_DOF, Model.AttributeFrequency.JOINT_COORD, Model.AttributeFrequency.JOINT_CONSTRAINT, ): freq = custom_attr.frequency freq_config = { Model.AttributeFrequency.JOINT_DOF: ( self.joint_qd_start, self.joint_dof_count, "DOF", "DOFs", ), Model.AttributeFrequency.JOINT_COORD: ( self.joint_q_start, self.joint_coord_count, "coord", "coordinates", ), Model.AttributeFrequency.JOINT_CONSTRAINT: ( self.joint_cts_start, self.joint_constraint_count, "constraint", "constraints", ), } start_array, total_count, index_label, count_label = freq_config[freq] index_start = start_array[joint_index] if joint_index + 1 < len(start_array): index_end = start_array[joint_index + 1] else: index_end = total_count apply_indexed_values( value=value, attr_key=attr_key, expected_frequency=freq, index_start=index_start, index_count=index_end - index_start, index_label=index_label, count_label=count_label, length_error_template=( f"{freq.name} attribute '{{attr_key}}' has {{actual}} values " f"but joint has {{expected}} {count_label}" ), ) else: raise ValueError( f"Custom attribute '{attr_key}' has unsupported frequency {custom_attr.frequency} for joints" ) def add_actuator( self, actuator_class: type[Actuator], input_indices: list[int], output_indices: list[int] | None = None, **kwargs: Any, ) -> None: """Add an external actuator, independent of any ``UsdPhysics`` joint drives. External actuators (e.g. :class:`newton_actuators.ActuatorPD`) apply forces computed outside the physics engine. Multiple calls with the same *actuator_class* and identical scalar parameters are accumulated into one entry; the actuator instance is created during :meth:`finalize `. Args: actuator_class: The actuator class (must derive from :class:`newton_actuators.Actuator`). input_indices: DOF indices this actuator reads from. Length 1 for single-input, length > 1 for multi-input actuators. output_indices: DOF indices for writing output. Defaults to *input_indices*. **kwargs: Actuator parameters (e.g., ``kp``, ``kd``, ``max_force``). """ if output_indices is None: output_indices = input_indices.copy() resolved = actuator_class.resolve_arguments(kwargs) # Extract scalar params to form the entry key scalar_param_names = getattr(actuator_class, "SCALAR_PARAMS", set()) scalar_key = tuple(sorted((k, resolved[k]) for k in scalar_param_names if k in resolved)) # Key is (class, scalar_params) so different scalar values create separate entries entry_key = (actuator_class, scalar_key) entry = self.actuator_entries.setdefault( entry_key, ModelBuilder.ActuatorEntry(input_indices=[], output_indices=[], args=[]), ) # Filter out scalar params from args (they're already in the key) array_params = {k: v for k, v in resolved.items() if k not in scalar_param_names} # Validate dimension consistency before appending if entry.input_indices: expected_input_dim = len(entry.input_indices[0]) if len(input_indices) != expected_input_dim: raise ValueError( f"Input indices dimension mismatch for {actuator_class.__name__}: " f"expected {expected_input_dim}, got {len(input_indices)}. " f"All actuators of the same type must have the same number of inputs." ) if entry.output_indices: expected_output_dim = len(entry.output_indices[0]) if len(output_indices) != expected_output_dim: raise ValueError( f"Output indices dimension mismatch for {actuator_class.__name__}: " f"expected {expected_output_dim}, got {len(output_indices)}. " f"All actuators of the same type must have the same number of outputs." ) # Each call adds one actuator with its input/output indices entry.input_indices.append(input_indices) entry.output_indices.append(output_indices) entry.args.append(array_params) def _stack_args_to_arrays( self, args_list: list[dict[str, Any]], device: Devicelike | None = None, requires_grad: bool = False, ) -> dict[str, wp.array]: """Convert list of per-index arg dicts into dict of warp arrays. Args: args_list: List of dicts, one per index. Each dict has same keys. device: Device for warp arrays. requires_grad: Whether the arrays require gradients. Returns: Mapping from parameter names to warp arrays. """ if not args_list: return {} result = {} for key in args_list[0].keys(): values = [args[key] for args in args_list] result[key] = wp.array(values, dtype=wp.float32, device=device, requires_grad=requires_grad) return result @staticmethod def _build_index_array(indices: list[list[int]], device: Devicelike) -> wp.array: """Build a warp array from nested index lists. If all inner lists have length 1, creates a 1D array (N,). Otherwise, creates a 2D array (N, M) where M is the inner list length. Args: indices: Nested list of indices, one inner list per actuator. device: Device for the warp array. Returns: Array with shape ``(N,)`` or ``(N, M)``. Raises: ValueError: If inner lists have inconsistent lengths (for 2D case). """ if not indices: return wp.array([], dtype=wp.uint32, device=device) inner_lengths = [len(idx_list) for idx_list in indices] max_len = max(inner_lengths) if max_len == 1: # All single-input: flatten to 1D flat = [idx_list[0] for idx_list in indices] return wp.array(flat, dtype=wp.uint32, device=device) else: # Multi-input: create 2D array if not all(length == max_len for length in inner_lengths): raise ValueError( f"All actuators must have the same number of inputs for 2D indexing. Got lengths: {inner_lengths}" ) return wp.array(indices, dtype=wp.uint32, device=device) @property def default_site_cfg(self) -> ShapeConfig: """Returns a ShapeConfig configured for sites (non-colliding reference points). This config has all site invariants enforced: - is_site = True - has_shape_collision = False - has_particle_collision = False - density = 0.0 - collision_group = 0 Returns: A new configuration suitable for creating sites. """ cfg = self.ShapeConfig() cfg.mark_as_site() return cfg @property def up_vector(self) -> tuple[float, float, float]: """ Returns the 3D unit vector corresponding to the current up axis (read-only). This property computes the up direction as a 3D vector based on the value of :attr:`up_axis`. For example, if ``up_axis`` is ``Axis.Z``, this returns ``(0, 0, 1)``. Returns: The 3D up vector corresponding to the current up axis. """ return self.up_axis.to_vector() @up_vector.setter def up_vector(self, _): raise AttributeError( "The 'up_vector' property is read-only and cannot be set. Instead, use 'up_axis' to set the up axis." ) @property def current_world(self) -> int: """Returns the builder-managed world context for subsequently added entities. A value of ``-1`` means newly added entities are global. Use :meth:`begin_world`, :meth:`end_world`, :meth:`add_world`, or :meth:`replicate` to manage world assignment. Returns: The current world index for newly added entities. """ return self._current_world @current_world.setter def current_world(self, _): message = ( "The 'current_world' property is read-only and cannot be set. " + "Use 'begin_world()', 'end_world()', 'add_world()', or " + "'replicate()' to manage worlds." ) raise AttributeError(message) # region counts @property def shape_count(self): """ The number of shapes in the model. """ return len(self.shape_type) @property def body_count(self): """ The number of rigid bodies in the model. """ return len(self.body_q) @property def joint_count(self): """ The number of joints in the model. """ return len(self.joint_type) @property def particle_count(self): """ The number of particles in the model. """ return len(self.particle_q) @property def tri_count(self): """ The number of triangles in the model. """ return len(self.tri_poses) @property def tet_count(self): """ The number of tetrahedra in the model. """ return len(self.tet_poses) @property def edge_count(self): """ The number of edges (for bending) in the model. """ return len(self.edge_rest_angle) @property def spring_count(self): """ The number of springs in the model. """ return len(self.spring_rest_length) @property def muscle_count(self): """ The number of muscles in the model. """ return len(self.muscle_start) @property def articulation_count(self): """ The number of articulations in the model. """ return len(self.articulation_start) # endregion def replicate( self, builder: ModelBuilder, world_count: int, spacing: tuple[float, float, float] = (0.0, 0.0, 0.0), ): """ Replicates the given builder multiple times, offsetting each copy according to the supplied spacing. This method is useful for creating multiple instances of a sub-model (e.g., robots, scenes) arranged in a regular grid or along a line. Each copy is offset in space by a multiple of the specified spacing vector, and all entities from each copy are assigned to a new world. Note: For visual separation of worlds, it is recommended to use the viewer's `set_world_offsets()` method instead of physical spacing. This improves numerical stability by keeping all worlds at the origin in the physics simulation. Args: builder: The builder to replicate. All entities from this builder will be copied. world_count: The number of worlds to create. spacing: The spacing between each copy along each axis. For example, (5.0, 5.0, 0.0) arranges copies in a 2D grid in the XY plane. Defaults to (0.0, 0.0, 0.0). """ offsets = compute_world_offsets(world_count, spacing, self.up_axis) xform = wp.transform_identity() for i in range(world_count): xform[:3] = offsets[i] self.add_world(builder, xform=xform) def add_articulation( self, joints: list[int], label: str | None = None, custom_attributes: dict[str, Any] | None = None ): """ Adds an articulation to the model from a list of joint indices. The articulation is a set of joints that must be contiguous and monotonically increasing. Some functions, such as forward kinematics :func:`newton.eval_fk`, are parallelized over articulations. Args: joints: List of joint indices to include in the articulation. Must be contiguous and monotonic. label: The label of the articulation. If None, a default label will be created. custom_attributes: Dictionary of custom attribute values for ARTICULATION frequency attributes. Raises: ValueError: If joints are not contiguous, not monotonic, or belong to different worlds. Example: .. code-block:: python link1 = builder.add_link(...) link2 = builder.add_link(...) link3 = builder.add_link(...) joint1 = builder.add_joint_revolute(parent=-1, child=link1) joint2 = builder.add_joint_revolute(parent=link1, child=link2) joint3 = builder.add_joint_revolute(parent=link2, child=link3) # Create articulation from the joints builder.add_articulation([joint1, joint2, joint3]) """ if not joints: raise ValueError("Cannot create an articulation with no joints") # Sort joints to ensure we can validate them properly sorted_joints = sorted(joints) # Validate joints are monotonically increasing (no duplicates) if sorted_joints != joints: raise ValueError( f"Joints must be provided in monotonically increasing order. Got {joints}, expected {sorted_joints}" ) # Validate joints are contiguous for i in range(1, len(sorted_joints)): if sorted_joints[i] != sorted_joints[i - 1] + 1: raise ValueError( f"Joints must be contiguous. Got indices {sorted_joints}, but there is a gap between " f"{sorted_joints[i - 1]} and {sorted_joints[i]}. Create all joints for an articulation " f"before creating joints for another articulation." ) # Validate all joints exist and don't already belong to an articulation for joint_idx in joints: if joint_idx < 0 or joint_idx >= len(self.joint_type): raise ValueError( f"Joint index {joint_idx} is out of range. Valid range is 0 to {len(self.joint_type) - 1}" ) if self.joint_articulation[joint_idx] >= 0: existing_art = self.joint_articulation[joint_idx] raise ValueError( f"Joint {joint_idx} ('{self.joint_label[joint_idx]}') already belongs to articulation {existing_art} " f"('{self.articulation_label[existing_art]}'). Each joint can only belong to one articulation." ) # Validate all joints belong to the same world (current world) for joint_idx in joints: if joint_idx < len(self.joint_world) and self.joint_world[joint_idx] != self.current_world: raise ValueError( f"Joint {joint_idx} belongs to world {self.joint_world[joint_idx]}, but current world is " f"{self.current_world}. All joints in an articulation must belong to the same world." ) # Basic tree structure validation (check for cycles, single parent) # Build a simple tree structure check - each child should have only one parent in this articulation child_to_parent = {} for joint_idx in joints: child = self.joint_child[joint_idx] parent = self.joint_parent[joint_idx] if child in child_to_parent and child_to_parent[child] != parent: raise ValueError( f"Body {child} has multiple parents in this articulation: {child_to_parent[child]} and {parent}. " f"This creates an invalid tree structure. Loop-closing joints must not be part of an articulation." ) child_to_parent[child] = parent # Validate that only root bodies (parent == -1) can be kinematic self._validate_kinematic_articulation_joints(joints) # Store the articulation using the first joint's index as the start articulation_idx = self.articulation_count self.articulation_start.append(sorted_joints[0]) self.articulation_label.append(label or f"articulation_{articulation_idx}") self.articulation_world.append(self.current_world) # Mark all joints as belonging to this articulation for joint_idx in joints: self.joint_articulation[joint_idx] = articulation_idx # Process custom attributes for this articulation if custom_attributes: self._process_custom_attributes( entity_index=articulation_idx, custom_attrs=custom_attributes, expected_frequency=Model.AttributeFrequency.ARTICULATION, ) # region importers def add_urdf( self, source: str, *, xform: Transform | None = None, floating: bool | None = None, base_joint: dict | None = None, parent_body: int = -1, scale: float = 1.0, hide_visuals: bool = False, parse_visuals_as_colliders: bool = False, up_axis: AxisType = Axis.Z, force_show_colliders: bool = False, enable_self_collisions: bool = True, ignore_inertial_definitions: bool = False, joint_ordering: Literal["bfs", "dfs"] | None = "dfs", bodies_follow_joint_ordering: bool = True, collapse_fixed_joints: bool = False, mesh_maxhullvert: int | None = None, force_position_velocity_actuation: bool = False, override_root_xform: bool = False, ): """ Parses a URDF file and adds the bodies and joints to the given ModelBuilder. Args: source: The filename of the URDF file to parse, or the URDF XML string content. xform: The transform to apply to the root body. If None, the transform is set to identity. override_root_xform: If ``True``, the articulation root's world-space transform is replaced by ``xform`` instead of being composed with it, preserving only the internal structure (relative body positions). Useful for cloning articulations at explicit positions. When a ``base_joint`` is specified, ``xform`` is applied as the full parent transform (including rotation) rather than splitting position/rotation. Not intended for sources containing multiple articulations, as all roots would be placed at the same ``xform``. Defaults to ``False``. floating: Controls the base joint type for the root body. - ``None`` (default): Uses format-specific default (creates a FIXED joint for URDF). - ``True``: Creates a FREE joint with 6 DOF (3 translation + 3 rotation). Only valid when ``parent_body == -1`` since FREE joints must connect to world frame. - ``False``: Creates a FIXED joint (0 DOF). Cannot be specified together with ``base_joint``. base_joint: Custom joint specification for connecting the root body to the world (or to ``parent_body`` if specified). This parameter enables hierarchical composition with custom mobility. Dictionary with joint parameters as accepted by :meth:`ModelBuilder.add_joint` (e.g., joint type, axes, limits, stiffness). Cannot be specified together with ``floating``. parent_body: Parent body index for hierarchical composition. If specified, attaches the imported root body to this existing body, making them part of the same kinematic articulation. The connection type is determined by ``floating`` or ``base_joint``. If ``-1`` (default), the root connects to the world frame. **Restriction**: Only the most recently added articulation can be used as parent; attempting to attach to an older articulation will raise a ``ValueError``. .. note:: Valid combinations of ``floating``, ``base_joint``, and ``parent_body``: .. list-table:: :header-rows: 1 :widths: 15 15 15 55 * - floating - base_joint - parent_body - Result * - ``None`` - ``None`` - ``-1`` - Format default (URDF: FIXED joint) * - ``True`` - ``None`` - ``-1`` - FREE joint to world (6 DOF) * - ``False`` - ``None`` - ``-1`` - FIXED joint to world (0 DOF) * - ``None`` - ``{dict}`` - ``-1`` - Custom joint to world (e.g., D6) * - ``False`` - ``None`` - ``body_idx`` - FIXED joint to parent body * - ``None`` - ``{dict}`` - ``body_idx`` - Custom joint to parent body (e.g., D6) * - *explicitly set* - *explicitly set* - *any* - ❌ Error: mutually exclusive (cannot specify both) * - ``True`` - ``None`` - ``body_idx`` - ❌ Error: FREE joints require world frame scale: The scaling factor to apply to the imported mechanism. hide_visuals: If True, hide visual shapes. parse_visuals_as_colliders: If True, the geometry defined under the `` tags is used for collision handling instead of the `` geometries. up_axis: The up axis of the URDF. This is used to transform the URDF to the builder's up axis. It also determines the up axis of capsules and cylinders in the URDF. The default is Z. force_show_colliders: If True, the collision shapes are always shown, even if there are visual shapes. enable_self_collisions: If True, self-collisions are enabled. ignore_inertial_definitions: If True, the inertial parameters defined in the URDF are ignored and the inertia is calculated from the shape geometry. joint_ordering: The ordering of the joints in the simulation. Can be either "bfs" or "dfs" for breadth-first or depth-first search, or ``None`` to keep joints in the order in which they appear in the URDF. Default is "dfs". bodies_follow_joint_ordering: If True, the bodies are added to the builder in the same order as the joints (parent then child body). Otherwise, bodies are added in the order they appear in the URDF. Default is True. collapse_fixed_joints: If True, fixed joints are removed and the respective bodies are merged. mesh_maxhullvert: Maximum vertices for convex hull approximation of meshes. force_position_velocity_actuation: If True and both position (stiffness) and velocity (damping) gains are non-zero, joints use :attr:`~newton.JointTargetMode.POSITION_VELOCITY` actuation mode. If False (default), actuator modes are inferred per joint via :func:`newton.JointTargetMode.from_gains`: :attr:`~newton.JointTargetMode.POSITION` if stiffness > 0, :attr:`~newton.JointTargetMode.VELOCITY` if only damping > 0, :attr:`~newton.JointTargetMode.EFFORT` if a drive is present but both gains are zero (direct torque control), or :attr:`~newton.JointTargetMode.NONE` if no drive/actuation is applied. """ from ..utils.import_urdf import parse_urdf # noqa: PLC0415 return parse_urdf( self, source, xform=xform, floating=floating, base_joint=base_joint, parent_body=parent_body, scale=scale, hide_visuals=hide_visuals, parse_visuals_as_colliders=parse_visuals_as_colliders, up_axis=up_axis, force_show_colliders=force_show_colliders, enable_self_collisions=enable_self_collisions, ignore_inertial_definitions=ignore_inertial_definitions, joint_ordering=joint_ordering, bodies_follow_joint_ordering=bodies_follow_joint_ordering, collapse_fixed_joints=collapse_fixed_joints, mesh_maxhullvert=mesh_maxhullvert, force_position_velocity_actuation=force_position_velocity_actuation, override_root_xform=override_root_xform, ) def add_usd( self, source: str | UsdStage, *, xform: Transform | None = None, floating: bool | None = None, base_joint: dict | None = None, parent_body: int = -1, only_load_enabled_rigid_bodies: bool = False, only_load_enabled_joints: bool = True, joint_drive_gains_scaling: float = 1.0, verbose: bool = False, ignore_paths: list[str] | None = None, collapse_fixed_joints: bool = False, enable_self_collisions: bool = True, apply_up_axis_from_stage: bool = False, root_path: str = "/", joint_ordering: Literal["bfs", "dfs"] | None = "dfs", bodies_follow_joint_ordering: bool = True, skip_mesh_approximation: bool = False, load_sites: bool = True, load_visual_shapes: bool = True, hide_collision_shapes: bool = False, force_show_colliders: bool = False, parse_mujoco_options: bool = True, mesh_maxhullvert: int | None = None, schema_resolvers: list[SchemaResolver] | None = None, force_position_velocity_actuation: bool = False, override_root_xform: bool = False, ) -> dict[str, Any]: """Parses a Universal Scene Description (USD) stage containing UsdPhysics schema definitions for rigid-body articulations and adds the bodies, shapes and joints to the given ModelBuilder. The USD description has to be either a path (file name or URL), or an existing USD stage instance that implements the `Stage `_ interface. See :ref:`usd_parsing` for more information. Args: source: The file path to the USD file, or an existing USD stage instance. xform: The transform to apply to the entire scene. override_root_xform: If ``True``, the articulation root's world-space transform is replaced by ``xform`` instead of being composed with it, preserving only the internal structure (relative body positions). Useful for cloning articulations at explicit positions. Not intended for sources containing multiple articulations, as all roots would be placed at the same ``xform``. Defaults to ``False``. floating: Controls the base joint type for the root body (bodies not connected as a child to any joint). - ``None`` (default): Uses format-specific default (creates a FREE joint for USD bodies without joints). - ``True``: Creates a FREE joint with 6 DOF (3 translation + 3 rotation). Only valid when ``parent_body == -1`` since FREE joints must connect to world frame. - ``False``: Creates a FIXED joint (0 DOF). Cannot be specified together with ``base_joint``. base_joint: Custom joint specification for connecting the root body to the world (or to ``parent_body`` if specified). This parameter enables hierarchical composition with custom mobility. Dictionary with joint parameters as accepted by :meth:`ModelBuilder.add_joint` (e.g., joint type, axes, limits, stiffness). Cannot be specified together with ``floating``. parent_body: Parent body index for hierarchical composition. If specified, attaches the imported root body to this existing body, making them part of the same kinematic articulation. The connection type is determined by ``floating`` or ``base_joint``. If ``-1`` (default), the root connects to the world frame. **Restriction**: Only the most recently added articulation can be used as parent; attempting to attach to an older articulation will raise a ``ValueError``. .. note:: Valid combinations of ``floating``, ``base_joint``, and ``parent_body``: .. list-table:: :header-rows: 1 :widths: 15 15 15 55 * - floating - base_joint - parent_body - Result * - ``None`` - ``None`` - ``-1`` - Format default (USD: FREE joint for bodies without joints) * - ``True`` - ``None`` - ``-1`` - FREE joint to world (6 DOF) * - ``False`` - ``None`` - ``-1`` - FIXED joint to world (0 DOF) * - ``None`` - ``{dict}`` - ``-1`` - Custom joint to world (e.g., D6) * - ``False`` - ``None`` - ``body_idx`` - FIXED joint to parent body * - ``None`` - ``{dict}`` - ``body_idx`` - Custom joint to parent body (e.g., D6) * - *explicitly set* - *explicitly set* - *any* - ❌ Error: mutually exclusive (cannot specify both) * - ``True`` - ``None`` - ``body_idx`` - ❌ Error: FREE joints require world frame only_load_enabled_rigid_bodies: If True, only rigid bodies which do not have `physics:rigidBodyEnabled` set to False are loaded. only_load_enabled_joints: If True, only joints which do not have `physics:jointEnabled` set to False are loaded. joint_drive_gains_scaling: The default scaling of the PD control gains (stiffness and damping), if not set in the PhysicsScene with as "newton:joint_drive_gains_scaling". verbose: If True, print additional information about the parsed USD file. Default is False. ignore_paths: A list of regular expressions matching prim paths to ignore. collapse_fixed_joints: If True, fixed joints are removed and the respective bodies are merged. Only considered if not set on the PhysicsScene as "newton:collapse_fixed_joints". enable_self_collisions: Default for whether self-collisions are enabled for all shapes within an articulation. Resolved via the schema resolver from ``newton:selfCollisionEnabled`` (NewtonArticulationRootAPI) or ``physxArticulation:enabledSelfCollisions``; if neither is authored, this value takes precedence. apply_up_axis_from_stage: If True, the up axis of the stage will be used to set :attr:`newton.ModelBuilder.up_axis`. Otherwise, the stage will be rotated such that its up axis aligns with the builder's up axis. Default is False. root_path: The USD path to import, defaults to "/". joint_ordering: The ordering of the joints in the simulation. Can be either "bfs" or "dfs" for breadth-first or depth-first search, or ``None`` to keep joints in the order in which they appear in the USD. Default is "dfs". bodies_follow_joint_ordering: If True, the bodies are added to the builder in the same order as the joints (parent then child body). Otherwise, bodies are added in the order they appear in the USD. Default is True. skip_mesh_approximation: If True, mesh approximation is skipped. Otherwise, meshes are approximated according to the ``physics:approximation`` attribute defined on the UsdPhysicsMeshCollisionAPI (if it is defined). Default is False. load_sites: If True, sites (prims with MjcSiteAPI) are loaded as non-colliding reference points. If False, sites are ignored. Default is True. load_visual_shapes: 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: If True, collision shapes on bodies that already have visual-only geometry are hidden unconditionally, regardless of whether the collider has authored PBR material data. Collision shapes on bodies without visual-only geometry remain visible as a rendering fallback. Default is False. force_show_colliders: If True, collision shapes get the VISIBLE flag regardless of whether visual shapes exist on the same body. Note that ``hide_collision_shapes=True`` still suppresses the VISIBLE flag for colliders on bodies with visual-only geometry. Default is False. parse_mujoco_options: 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: Maximum vertices for convex hull approximation of meshes. Note that an authored ``newton:maxHullVertices`` attribute on any shape with a ``NewtonMeshCollisionAPI`` will take priority over this value. schema_resolvers: Resolver instances in priority order. Default is to only parse Newton-specific attributes. Schema resolvers collect per-prim "solver-specific" attributes, see :ref:`schema_resolvers` for more information. These include namespaced attributes such as ``newton:*``, ``physx*`` (e.g., ``physxScene:*``, ``physxRigidBody:*``, ``physxSDFMeshCollision:*``), and ``mjc:*`` that are authored in the USD but not strictly required to build the simulation. This is useful for inspection, experimentation, or custom pipelines that read these values via ``result["schema_attrs"]`` returned from ``parse_usd()``. .. note:: Using the ``schema_resolvers`` argument is an experimental feature that may be removed or changed significantly in the future. force_position_velocity_actuation: If True and both stiffness (kp) and damping (kd) are non-zero, joints use :attr:`~newton.JointTargetMode.POSITION_VELOCITY` actuation mode. If False (default), actuator modes are inferred per joint via :func:`newton.JointTargetMode.from_gains`: :attr:`~newton.JointTargetMode.POSITION` if stiffness > 0, :attr:`~newton.JointTargetMode.VELOCITY` if only damping > 0, :attr:`~newton.JointTargetMode.EFFORT` if a drive is present but both gains are zero (direct torque control), or :attr:`~newton.JointTargetMode.NONE` if no drive/actuation is applied. Returns: The returned mapping has the following entries: .. list-table:: :widths: 25 75 * - ``"fps"`` - USD stage frames per second * - ``"duration"`` - Difference between end time code and start time code of the USD stage * - ``"up_axis"`` - :class:`Axis` representing the stage's up axis ("X", "Y", or "Z") * - ``"path_body_map"`` - Mapping from prim path (str) of a rigid body prim (e.g. that implements the PhysicsRigidBodyAPI) to the respective body index in :class:`~newton.ModelBuilder` * - ``"path_joint_map"`` - Mapping from prim path (str) of a joint prim (e.g. that implements the PhysicsJointAPI) to the respective joint index in :class:`~newton.ModelBuilder` * - ``"path_shape_map"`` - Mapping from prim path (str) of the UsdGeom to the respective shape index in :class:`~newton.ModelBuilder` * - ``"path_shape_scale"`` - Mapping from prim path (str) of the UsdGeom to its respective 3D world scale * - ``"mass_unit"`` - The stage's Kilograms Per Unit (KGPU) definition (1.0 by default) * - ``"linear_unit"`` - The stage's Meters Per Unit (MPU) definition (1.0 by default) * - ``"scene_attributes"`` - Dictionary of all attributes applied to the PhysicsScene prim * - ``"collapse_results"`` - Dictionary returned by :meth:`newton.ModelBuilder.collapse_fixed_joints` if ``collapse_fixed_joints`` is True, otherwise None. * - ``"physics_dt"`` - The resolved physics scene time step (float or None) * - ``"schema_attrs"`` - Dictionary of collected per-prim schema attributes (dict) * - ``"max_solver_iterations"`` - The resolved maximum solver iterations (int or None) * - ``"path_body_relative_transform"`` - Mapping from prim path to relative transform for bodies merged via ``collapse_fixed_joints`` * - ``"path_original_body_map"`` - Mapping from prim path to original body index before ``collapse_fixed_joints`` * - ``"actuator_count"`` - Number of external actuators parsed from the USD stage """ from ..utils.import_usd import parse_usd # noqa: PLC0415 return parse_usd( self, source, xform=xform, floating=floating, base_joint=base_joint, parent_body=parent_body, only_load_enabled_rigid_bodies=only_load_enabled_rigid_bodies, only_load_enabled_joints=only_load_enabled_joints, joint_drive_gains_scaling=joint_drive_gains_scaling, verbose=verbose, ignore_paths=ignore_paths, collapse_fixed_joints=collapse_fixed_joints, enable_self_collisions=enable_self_collisions, apply_up_axis_from_stage=apply_up_axis_from_stage, root_path=root_path, joint_ordering=joint_ordering, bodies_follow_joint_ordering=bodies_follow_joint_ordering, skip_mesh_approximation=skip_mesh_approximation, load_sites=load_sites, load_visual_shapes=load_visual_shapes, hide_collision_shapes=hide_collision_shapes, force_show_colliders=force_show_colliders, parse_mujoco_options=parse_mujoco_options, mesh_maxhullvert=mesh_maxhullvert, schema_resolvers=schema_resolvers, force_position_velocity_actuation=force_position_velocity_actuation, override_root_xform=override_root_xform, ) def add_mjcf( self, source: str, *, xform: Transform | None = None, floating: bool | None = None, base_joint: dict | None = None, parent_body: int = -1, armature_scale: float = 1.0, scale: float = 1.0, hide_visuals: bool = False, parse_visuals_as_colliders: bool = False, 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] = (), visual_classes: Sequence[str] = ("visual",), collider_classes: Sequence[str] = ("collision",), no_class_as_colliders: bool = True, force_show_colliders: bool = False, enable_self_collisions: bool = True, ignore_inertial_definitions: bool = False, collapse_fixed_joints: bool = False, verbose: bool = False, skip_equality_constraints: bool = False, convert_3d_hinge_to_ball_joints: bool = False, mesh_maxhullvert: int | None = None, ctrl_direct: bool = False, path_resolver: Callable[[str | None, str], str] | None = None, override_root_xform: bool = False, ): """ Parses MuJoCo XML (MJCF) file and adds the bodies and joints to the given ModelBuilder. MuJoCo-specific custom attributes are registered on the builder automatically. Args: source: The filename of the MuJoCo file to parse, or the MJCF XML string content. xform: The transform to apply to the imported mechanism. override_root_xform: If ``True``, the articulation root's world-space transform is replaced by ``xform`` instead of being composed with it, preserving only the internal structure (relative body positions). Useful for cloning articulations at explicit positions. Not intended for sources containing multiple articulations, as all roots would be placed at the same ``xform``. Defaults to ``False``. floating: Controls the base joint type for the root body. - ``None`` (default): Uses format-specific default (honors ```` tags in MJCF, otherwise creates a FIXED joint). - ``True``: Creates a FREE joint with 6 DOF (3 translation + 3 rotation). Only valid when ``parent_body == -1`` since FREE joints must connect to world frame. - ``False``: Creates a FIXED joint (0 DOF). Cannot be specified together with ``base_joint``. base_joint: Custom joint specification for connecting the root body to the world (or to ``parent_body`` if specified). This parameter enables hierarchical composition with custom mobility. Dictionary with joint parameters as accepted by :meth:`ModelBuilder.add_joint` (e.g., joint type, axes, limits, stiffness). Cannot be specified together with ``floating``. parent_body: Parent body index for hierarchical composition. If specified, attaches the imported root body to this existing body, making them part of the same kinematic articulation. The connection type is determined by ``floating`` or ``base_joint``. If ``-1`` (default), the root connects to the world frame. **Restriction**: Only the most recently added articulation can be used as parent; attempting to attach to an older articulation will raise a ``ValueError``. .. note:: Valid combinations of ``floating``, ``base_joint``, and ``parent_body``: .. list-table:: :header-rows: 1 :widths: 15 15 15 55 * - floating - base_joint - parent_body - Result * - ``None`` - ``None`` - ``-1`` - Format default (MJCF: honors ````, else FIXED) * - ``True`` - ``None`` - ``-1`` - FREE joint to world (6 DOF) * - ``False`` - ``None`` - ``-1`` - FIXED joint to world (0 DOF) * - ``None`` - ``{dict}`` - ``-1`` - Custom joint to world (e.g., D6) * - ``False`` - ``None`` - ``body_idx`` - FIXED joint to parent body * - ``None`` - ``{dict}`` - ``body_idx`` - Custom joint to parent body (e.g., D6) * - *explicitly set* - *explicitly set* - *any* - ❌ Error: mutually exclusive (cannot specify both) * - ``True`` - ``None`` - ``body_idx`` - ❌ Error: FREE joints require world frame armature_scale: Scaling factor to apply to the MJCF-defined joint armature values. scale: The scaling factor to apply to the imported mechanism. hide_visuals: If True, hide visual shapes after loading them (affects visibility, not loading). parse_visuals_as_colliders: If True, the geometry defined under the `visual_classes` tags is used for collision handling instead of the `collider_classes` geometries. parse_meshes: Whether geometries of type `"mesh"` should be parsed. If False, geometries of type `"mesh"` are ignored. parse_sites: Whether sites (non-colliding reference points) should be parsed. If False, sites are ignored. parse_visuals: 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: Whether solver options from the MJCF `
""" builder = newton.ModelBuilder() builder.add_mjcf(mjcf) self.assertEqual(builder.shape_type[0], GeoType.BOX) # shape_scale stores (hx, hy, hz) s = builder.shape_scale[0] np.testing.assert_allclose([s[0], s[1], s[2]], [1.0, 0.5, 2.0], atol=1e-4) def test_fit_sphere_to_mesh_aabb(self): """type='sphere' mesh='...' with fitaabb='true' uses max half-extent as radius.""" with tempfile.TemporaryDirectory() as tmpdir: stl_path = os.path.join(tmpdir, "box.stl") self._write_box_stl(stl_path, hx=1.0, hy=0.5, hz=2.0) mjcf = f"""\ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf) self.assertEqual(builder.shape_type[0], GeoType.SPHERE) # Sphere radius = max(1.0, 0.5, 2.0) = 2.0 s = builder.shape_scale[0] self.assertAlmostEqual(s[0], 2.0, places=4) def test_fit_capsule_to_mesh_aabb(self): """type='capsule' mesh='...' with fitaabb='true' fits capsule to AABB.""" with tempfile.TemporaryDirectory() as tmpdir: stl_path = os.path.join(tmpdir, "box.stl") self._write_box_stl(stl_path, hx=1.0, hy=0.5, hz=2.0) mjcf = f"""\ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf) self.assertEqual(builder.shape_type[0], GeoType.CAPSULE) s = builder.shape_scale[0] # radius = max(1.0, 0.5) = 1.0, half_height = 2.0 - 1.0 = 1.0 self.assertAlmostEqual(s[0], 1.0, places=4) self.assertAlmostEqual(s[1], 1.0, places=4) def test_fit_box_to_mesh_inertia(self): """type='box' mesh='...' with fitaabb='false' (default) uses equivalent inertia box.""" with tempfile.TemporaryDirectory() as tmpdir: stl_path = os.path.join(tmpdir, "box.stl") # Asymmetric box offset from the origin to exercise axis ordering # and COM translation. self._write_box_stl(stl_path, hx=1.0, hy=0.5, hz=2.0, cx=3.0, cy=0.0, cz=0.0) mjcf = f"""\ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf) self.assertEqual(builder.shape_type[0], GeoType.BOX) s = builder.shape_scale[0] # Half-extents are sorted ascending: (0.5, 1.0, 2.0) np.testing.assert_allclose([s[0], s[1], s[2]], [0.5, 1.0, 2.0], atol=0.05) # Shape transform should include the COM offset (3, 0, 0) t = builder.shape_transform[0] self.assertAlmostEqual(t.p[0], 3.0, places=1) def test_fit_box_to_mesh_inertia_rotated(self): """Inertia-box fitting aligns the primitive to the principal axes.""" with tempfile.TemporaryDirectory() as tmpdir: stl_path = os.path.join(tmpdir, "rotated.stl") # Write an axis-aligned box and then rotate its vertices 45 deg # around Z so the principal axes are no longer axis-aligned. hx, hy, hz = 2.0, 0.5, 1.0 angle = np.pi / 4.0 cos_a, sin_a = np.cos(angle), np.sin(angle) tris = [] for sign in (-1, 1): for axis in range(3): v = [None, None, None, None] u, w = (axis + 1) % 3, (axis + 2) % 3 h = [hx, hy, hz] for i, (su, sw) in enumerate([(1, 1), (-1, 1), (-1, -1), (1, -1)]): p = [0.0, 0.0, 0.0] p[axis] = sign * h[axis] p[u] = su * h[u] p[w] = sw * h[w] # Rotate around Z. rx = cos_a * p[0] - sin_a * p[1] ry = sin_a * p[0] + cos_a * p[1] v[i] = [rx, ry, p[2]] if sign > 0: tris.append((v[0], v[1], v[2])) tris.append((v[0], v[2], v[3])) else: tris.append((v[0], v[2], v[1])) tris.append((v[0], v[3], v[2])) with open(stl_path, "wb") as f: f.write(b"\0" * 80) f.write(struct.pack(" """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf) self.assertEqual(builder.shape_type[0], GeoType.BOX) s = builder.shape_scale[0] # Sorted half-extents should match the original box dims. np.testing.assert_allclose(sorted([s[0], s[1], s[2]]), [0.5, 1.0, 2.0], atol=0.05) # Eigenvector signs are platform-dependent, so just verify the # rotation is non-trivial. Warp XYZW identity = [0, 0, 0, 1]. t = builder.shape_transform[0] q = t.q q_np = np.array([q[0], q[1], q[2], q[3]]) self.assertFalse( np.allclose(np.abs(q_np), [0, 0, 0, 1], atol=0.1), "Expected non-identity rotation for rotated mesh", ) def test_fit_with_fitscale(self): """fitscale attribute scales the fitted primitive.""" with tempfile.TemporaryDirectory() as tmpdir: stl_path = os.path.join(tmpdir, "box.stl") self._write_box_stl(stl_path, hx=1.0, hy=0.5, hz=2.0) mjcf = f"""\ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf) self.assertEqual(builder.shape_type[0], GeoType.BOX) s = builder.shape_scale[0] np.testing.assert_allclose([s[0], s[1], s[2]], [2.0, 1.0, 4.0], atol=1e-4) def test_fit_cylinder_to_mesh_aabb(self): """type='cylinder' mesh='...' with fitaabb='true' fits cylinder to AABB.""" with tempfile.TemporaryDirectory() as tmpdir: stl_path = os.path.join(tmpdir, "box.stl") self._write_box_stl(stl_path, hx=1.0, hy=0.5, hz=2.0) mjcf = f"""\ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf) self.assertEqual(builder.shape_type[0], GeoType.CYLINDER) s = builder.shape_scale[0] # radius = max(1.0, 0.5) = 1.0, half_height = 2.0 (no cap subtraction) self.assertAlmostEqual(s[0], 1.0, places=4) self.assertAlmostEqual(s[1], 2.0, places=4) def test_fit_ellipsoid_to_mesh_aabb(self): """type='ellipsoid' mesh='...' with fitaabb='true' fits ellipsoid to AABB.""" with tempfile.TemporaryDirectory() as tmpdir: stl_path = os.path.join(tmpdir, "box.stl") self._write_box_stl(stl_path, hx=1.0, hy=0.5, hz=2.0) mjcf = f"""\ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf) self.assertEqual(builder.shape_type[0], GeoType.ELLIPSOID) s = builder.shape_scale[0] # Ellipsoid uses AABB half-extents directly: (1.0, 0.5, 2.0) np.testing.assert_allclose([s[0], s[1], s[2]], [1.0, 0.5, 2.0], atol=1e-4) def test_mesh_without_explicit_type_stays_mesh(self): """A geom with mesh= but no type= should still be treated as a mesh shape.""" with tempfile.TemporaryDirectory() as tmpdir: stl_path = os.path.join(tmpdir, "box.stl") self._write_box_stl(stl_path, hx=1.0, hy=1.0, hz=1.0) mjcf = f"""\ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf) self.assertEqual(builder.shape_type[0], GeoType.MESH) class TestImportMjcfSolverParams(unittest.TestCase): def test_solimplimit_parsing(self): """Test that solimplimit attribute is parsed correctly from MJCF.""" mjcf = """ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf) model = builder.finalize() # Check if solimplimit custom attribute exists self.assertTrue(hasattr(model, "mujoco"), "Model should have mujoco namespace for custom attributes") self.assertTrue(hasattr(model.mujoco, "solimplimit"), "Model should have solimplimit attribute") solimplimit = model.mujoco.solimplimit.numpy() # Newton model has only 2 joints because it combines the ones under the same body into a single joint self.assertEqual(model.joint_count, 2, "Should have 2 joints") # Find joints by name joint_names = model.joint_label joint1_idx = joint_names.index("worldbody/body1/joint1_joint2") joint2_idx = joint_names.index("worldbody/body2/joint3") # For the merged joint (joint1_idx), both joint1 and joint2 should be present in the qd array. # We don't know the order, but both expected values should be present at joint1_idx and joint1_idx + 1. joint1_qd_start = model.joint_qd_start.numpy()[joint1_idx] # The joint should have 2 DoFs (since joint1 and joint2 are merged) self.assertEqual(model.joint_dof_dim.numpy()[joint1_idx, 1], 2) expected_joint1 = [0.89, 0.9, 0.01, 2.1, 1.8] # from joint1 expected_joint2 = [0.9, 0.95, 0.001, 0.5, 2.0] # from joint2 (default values) val_qd_0 = solimplimit[joint1_qd_start, :] val_qd_1 = solimplimit[joint1_qd_start + 1, :] # Helper to check if two arrays match within tolerance def arrays_match(arr, expected, tol=1e-4): return all(abs(arr[i] - expected[i]) < tol for i in range(len(expected))) # The two DoFs should be exactly one joint1 and one default, in _some_ order if arrays_match(val_qd_0, expected_joint1): self.assertTrue( arrays_match(val_qd_1, expected_joint2), "Second DoF should have default solimplimit values" ) elif arrays_match(val_qd_0, expected_joint2): self.assertTrue( arrays_match(val_qd_1, expected_joint1), "Second DoF should have joint1's solimplimit values" ) else: self.fail(f"First DoF solimplimit {val_qd_0.tolist()} doesn't match either expected value") # Test joint3: explicit solimplimit with different values joint3_qd_start = model.joint_qd_start.numpy()[joint2_idx] expected_joint3 = [0.8, 0.85, 0.002, 0.6, 1.5] for i, expected in enumerate(expected_joint3): self.assertAlmostEqual( solimplimit[joint3_qd_start, i], expected, places=4, msg=f"joint3 solimplimit[{i}] should be {expected}" ) def test_limit_margin_parsing(self): """Test importing limit_margin from MJCF.""" mjcf = """ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf) model = builder.finalize() self.assertTrue(hasattr(model, "mujoco")) self.assertTrue(hasattr(model.mujoco, "limit_margin")) np.testing.assert_allclose(model.mujoco.limit_margin.numpy(), [0.01, 0.02, 0.0]) def test_solreffriction_parsing(self): """Test that solreffriction attribute is parsed correctly from MJCF.""" mjcf = """ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf) model = builder.finalize() # Check if solreffriction custom attribute exists self.assertTrue(hasattr(model, "mujoco"), "Model should have mujoco namespace for custom attributes") self.assertTrue(hasattr(model.mujoco, "solreffriction"), "Model should have solreffriction attribute") solreffriction = model.mujoco.solreffriction.numpy() # Newton model has only 2 joints because it combines the ones under the same body into a single joint self.assertEqual(model.joint_count, 2, "Should have 2 joints") # Find joints by name joint_names = model.joint_label joint1_idx = joint_names.index("worldbody/body1/joint1_joint2") joint2_idx = joint_names.index("worldbody/body2/joint3") # For the merged joint (joint1_idx), both joint1 and joint2 should be present in the qd array. joint1_qd_start = model.joint_qd_start.numpy()[joint1_idx] # The joint should have 2 DoFs (since joint1 and joint2 are merged) self.assertEqual(model.joint_dof_dim.numpy()[joint1_idx, 1], 2) expected_joint1 = [0.01, 0.5] # from joint1 expected_joint2 = [0.02, 1.0] # from joint2 (default values) val_qd_0 = solreffriction[joint1_qd_start, :] val_qd_1 = solreffriction[joint1_qd_start + 1, :] # Helper to check if two arrays match within tolerance def arrays_match(arr, expected, tol=1e-4): return all(abs(arr[i] - expected[i]) < tol for i in range(len(expected))) # The two DoFs should be exactly one joint1 and one default, in _some_ order if arrays_match(val_qd_0, expected_joint1): self.assertTrue( arrays_match(val_qd_1, expected_joint2), "Second DoF should have default solreffriction values" ) elif arrays_match(val_qd_0, expected_joint2): self.assertTrue( arrays_match(val_qd_1, expected_joint1), "Second DoF should have joint1's solreffriction values" ) else: self.fail(f"First DoF solreffriction {val_qd_0.tolist()} doesn't match either expected value") # Test joint3: explicit solreffriction with different values joint3_qd_start = model.joint_qd_start.numpy()[joint2_idx] expected_joint3 = [0.05, 2.0] for i, expected in enumerate(expected_joint3): self.assertAlmostEqual( solreffriction[joint3_qd_start, i], expected, places=4, msg=f"joint3 solreffriction[{i}] should be {expected}", ) def test_solimpfriction_parsing(self): """Test that solimpfriction attribute is parsed correctly from MJCF.""" mjcf = """ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf) model = builder.finalize() # Check if solimpfriction custom attribute exists self.assertTrue(hasattr(model, "mujoco"), "Model should have mujoco namespace for custom attributes") self.assertTrue(hasattr(model.mujoco, "solimpfriction"), "Model should have solimpfriction attribute") solimpfriction = model.mujoco.solimpfriction.numpy() # Newton model has only 2 joints because it combines the ones under the same body into a single joint self.assertEqual(model.joint_count, 2, "Should have 2 joints") # Find joints by name joint_names = model.joint_label joint1_idx = joint_names.index("worldbody/body1/joint1_joint2") joint2_idx = joint_names.index("worldbody/body2/joint3") # For the merged joint (joint1_idx), both joint1 and joint2 should be present in the qd array. joint1_qd_start = model.joint_qd_start.numpy()[joint1_idx] # The joint should have 2 DoFs (since joint1 and joint2 are merged) self.assertEqual(model.joint_dof_dim.numpy()[joint1_idx, 1], 2) expected_joint1 = [0.89, 0.9, 0.01, 2.1, 1.8] # from joint1 expected_joint2 = [0.9, 0.95, 0.001, 0.5, 2.0] # from joint2 (default values) val_qd_0 = solimpfriction[joint1_qd_start, :] val_qd_1 = solimpfriction[joint1_qd_start + 1, :] # Helper to check if two arrays match within tolerance def arrays_match(arr, expected, tol=1e-4): return all(abs(arr[i] - expected[i]) < tol for i in range(len(expected))) # The two DoFs should be exactly one joint1 and one default, in _some_ order if arrays_match(val_qd_0, expected_joint1): self.assertTrue( arrays_match(val_qd_1, expected_joint2), "Second DoF should have default solimpfriction values" ) elif arrays_match(val_qd_0, expected_joint2): self.assertTrue( arrays_match(val_qd_1, expected_joint1), "Second DoF should have joint1's solimpfriction values" ) else: self.fail(f"First DoF solimpfriction {val_qd_0.tolist()} doesn't match either expected value") # Test joint3: explicit solimp_friction with different values joint3_qd_start = model.joint_qd_start.numpy()[joint2_idx] expected_joint3 = [0.8, 0.85, 0.002, 0.6, 1.5] for i, expected in enumerate(expected_joint3): self.assertAlmostEqual( solimpfriction[joint3_qd_start, i], expected, places=4, msg=f"joint3 solimpfriction[{i}] should be {expected}", ) def test_granular_loading_flags(self): """Test granular control over sites and visual shapes loading.""" mjcf_filename = newton.examples.get_asset("nv_humanoid.xml") # Test 1: Load all (default behavior) builder_all = newton.ModelBuilder() builder_all.add_mjcf(mjcf_filename, ignore_names=["floor", "ground"], up_axis="Z") count_all = builder_all.shape_count # Test 2: Load sites only, no visual shapes builder_sites_only = newton.ModelBuilder() builder_sites_only.add_mjcf( mjcf_filename, parse_sites=True, parse_visuals=False, ignore_names=["floor", "ground"], up_axis="Z" ) count_sites_only = builder_sites_only.shape_count # Test 3: Load visual shapes only, no sites builder_visuals_only = newton.ModelBuilder() builder_visuals_only.add_mjcf( mjcf_filename, parse_sites=False, parse_visuals=True, ignore_names=["floor", "ground"], up_axis="Z" ) count_visuals_only = builder_visuals_only.shape_count # Test 4: Load neither (physics collision shapes only) builder_physics_only = newton.ModelBuilder() builder_physics_only.add_mjcf( mjcf_filename, parse_sites=False, parse_visuals=False, ignore_names=["floor", "ground"], up_axis="Z" ) count_physics_only = builder_physics_only.shape_count # Verify behavior # When loading all, should have most shapes self.assertEqual(count_all, 41, "Loading all should give 41 shapes (sites + visuals + collision)") # Sites only should have sites + collision shapes self.assertEqual(count_sites_only, 41, "Sites only should give 41 shapes (22 sites + 19 collision)") # Visuals only should have collision shapes only (no sites) self.assertEqual(count_visuals_only, 19, "Visuals only should give 19 shapes (collision only, no sites)") # Physics only should have collision shapes only self.assertEqual(count_physics_only, 19, "Physics only should give 19 shapes (collision only)") # Verify that sites are actually filtered self.assertLess(count_visuals_only, count_all, "Excluding sites should reduce shape count") self.assertLess(count_physics_only, count_all, "Excluding sites and visuals should reduce shape count") def test_parse_sites_backward_compatibility(self): """Test that parse_sites parameter works and maintains backward compatibility.""" mjcf_filename = newton.examples.get_asset("nv_humanoid.xml") # Default (should parse sites) builder1 = newton.ModelBuilder() builder1.add_mjcf(mjcf_filename, ignore_names=["floor", "ground"], up_axis="Z") # Explicitly enable sites builder2 = newton.ModelBuilder() builder2.add_mjcf(mjcf_filename, parse_sites=True, ignore_names=["floor", "ground"], up_axis="Z") # Should have same count self.assertEqual(builder1.shape_count, builder2.shape_count, "Default should parse sites") # Explicitly disable sites builder3 = newton.ModelBuilder() builder3.add_mjcf(mjcf_filename, parse_sites=False, ignore_names=["floor", "ground"], up_axis="Z") # Should have fewer shapes self.assertLess(builder3.shape_count, builder1.shape_count, "Disabling sites should reduce shape count") def test_parse_visuals_vs_hide_visuals(self): """Test the distinction between parse_visuals (loading) and hide_visuals (visibility).""" mjcf_filename = newton.examples.get_asset("nv_humanoid.xml") # Test 1: parse_visuals=False (don't load) builder_no_load = newton.ModelBuilder() builder_no_load.add_mjcf( mjcf_filename, parse_visuals=False, parse_sites=False, ignore_names=["floor", "ground"], up_axis="Z" ) # Test 2: hide_visuals=True (load but hide) builder_hidden = newton.ModelBuilder() builder_hidden.add_mjcf( mjcf_filename, hide_visuals=True, parse_sites=False, ignore_names=["floor", "ground"], up_axis="Z" ) # Note: nv_humanoid.xml doesn't have separate visual-only geometries # so both will have the same count (collision shapes only) # The important thing is that neither crashes and the API works correctly self.assertEqual( builder_no_load.shape_count, builder_hidden.shape_count, "For nv_humanoid.xml, both should have same count (no separate visuals)", ) # Verify parse_visuals=False doesn't crash self.assertGreater(builder_no_load.shape_count, 0, "Should still load collision shapes") # Verify hide_visuals=True doesn't crash self.assertGreater(builder_hidden.shape_count, 0, "Should still load collision shapes") def test_mjcf_friction_parsing(self): """Test MJCF friction parsing with 1, 2, and 3 element vectors.""" mjcf_content = """ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf_content, up_axis="Z") self.assertEqual(builder.shape_count, 5) # 3-element: friction="0.5 0.1 0.01" → absolute values self.assertAlmostEqual(builder.shape_material_mu[0], 0.5, places=5) self.assertAlmostEqual(builder.shape_material_mu_torsional[0], 0.1, places=5) self.assertAlmostEqual(builder.shape_material_mu_rolling[0], 0.01, places=5) # 3-element: friction="0.8 0.2 0.05" → absolute values self.assertAlmostEqual(builder.shape_material_mu[1], 0.8, places=5) self.assertAlmostEqual(builder.shape_material_mu_torsional[1], 0.2, places=5) self.assertAlmostEqual(builder.shape_material_mu_rolling[1], 0.05, places=5) # 3-element with zeros self.assertAlmostEqual(builder.shape_material_mu[2], 0.0, places=5) self.assertAlmostEqual(builder.shape_material_mu_torsional[2], 0.0, places=5) self.assertAlmostEqual(builder.shape_material_mu_rolling[2], 0.0, places=5) # 1-element: friction="1.0" → others use ShapeConfig defaults (0.005, 0.0001) self.assertAlmostEqual(builder.shape_material_mu[3], 1.0, places=5) self.assertAlmostEqual(builder.shape_material_mu_torsional[3], 0.005, places=5) self.assertAlmostEqual(builder.shape_material_mu_rolling[3], 0.0001, places=5) # 2-element: friction="0.6 0.15" → torsional: 0.15, rolling uses default (0.0001) self.assertAlmostEqual(builder.shape_material_mu[4], 0.6, places=5) self.assertAlmostEqual(builder.shape_material_mu_torsional[4], 0.15, places=5) self.assertAlmostEqual(builder.shape_material_mu_rolling[4], 0.0001, places=5) def test_mjcf_geom_margin_parsing(self): """Test MJCF geom margin is parsed to shape thickness. Verifies that MJCF geom margin values are mapped to shape thickness and that geoms without an explicit margin use the default thickness. Also checks that the model scale is applied to the margin value. """ mjcf_content = """ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf_content, up_axis="Z") self.assertEqual(builder.shape_count, 3) self.assertAlmostEqual(builder.shape_margin[0], 0.003, places=6) self.assertAlmostEqual(builder.shape_margin[1], 0.01, places=6) # geom3 has no margin, should use ShapeConfig default (0.0) self.assertAlmostEqual(builder.shape_margin[2], 0.0, places=8) # Verify scale is applied to margin builder_scaled = newton.ModelBuilder() builder_scaled.add_mjcf(mjcf_content, up_axis="Z", scale=2.0) self.assertAlmostEqual(builder_scaled.shape_margin[0], 0.006, places=6) self.assertAlmostEqual(builder_scaled.shape_margin[1], 0.02, places=6) def test_mjcf_geom_solref_parsing(self): """Test MJCF geom solref parsing for contact stiffness/damping. MuJoCo solref format: [timeconst, dampratio] - Standard mode (timeconst > 0): ke = 1/(tc^2 * dr^2), kd = 2/tc - Direct mode (both negative): ke = -tc, kd = -dr """ mjcf_content = """ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf_content, up_axis="Z") self.assertEqual(builder.shape_count, 3) # No solref specified -> Newton defaults: ke=2500 (ShapeConfig.ke), kd=100 (ShapeConfig.kd) self.assertAlmostEqual(builder.shape_material_ke[0], 2500.0, places=1) self.assertAlmostEqual(builder.shape_material_kd[0], 100.0, places=1) # Custom solref [0.04, 1.0]: ke = 1/(0.04^2 * 1^2) = 625, kd = 2/0.04 = 50 self.assertAlmostEqual(builder.shape_material_ke[1], 625.0, places=1) self.assertAlmostEqual(builder.shape_material_kd[1], 50.0, places=1) # Direct mode solref [-1000, -50]: ke = 1000, kd = 50 self.assertAlmostEqual(builder.shape_material_ke[2], 1000.0, places=1) self.assertAlmostEqual(builder.shape_material_kd[2], 50.0, places=1) def test_mjcf_gravcomp(self): """Test parsing of gravcomp from MJCF""" mjcf_content = """ """ builder = newton.ModelBuilder() # Register gravcomp builder.add_mjcf(mjcf_content) model = builder.finalize() self.assertTrue(hasattr(model, "mujoco")) self.assertTrue(hasattr(model.mujoco, "gravcomp")) gravcomp = model.mujoco.gravcomp.numpy() # Bodies are added in order self.assertAlmostEqual(gravcomp[0], 0.5) self.assertAlmostEqual(gravcomp[1], 1.0) self.assertAlmostEqual(gravcomp[2], 0.0) # Default def test_joint_stiffness_damping(self): mjcf_content = """ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf_content) model = builder.finalize() self.assertTrue(hasattr(model, "mujoco")) self.assertTrue(hasattr(model.mujoco, "dof_passive_stiffness")) self.assertTrue(hasattr(model.mujoco, "dof_passive_damping")) joint_names = model.joint_label joint_qd_start = model.joint_qd_start.numpy() joint_stiffness = model.mujoco.dof_passive_stiffness.numpy() joint_damping = model.mujoco.dof_passive_damping.numpy() joint_target_ke = model.joint_target_ke.numpy() joint_target_kd = model.joint_target_kd.numpy() prefix = "stiffness_damping_comprehensive_test/worldbody" expected_values = { f"{prefix}/body1/joint1": {"stiffness": 0.05, "damping": 0.5, "target_ke": 10000.0, "target_kd": 500.0}, f"{prefix}/body2/joint2": {"stiffness": 0.0, "damping": 0.0, "target_ke": 5000.0, "target_kd": 1000.0}, f"{prefix}/body3/joint3": {"stiffness": 0.1, "damping": 0.8, "target_ke": 0.0, "target_kd": 800.0}, f"{prefix}/body4/joint4": {"stiffness": 0.02, "damping": 0.3, "target_ke": 0.0, "target_kd": 3000.0}, } for joint_name, expected in expected_values.items(): joint_idx = joint_names.index(joint_name) dof_idx = joint_qd_start[joint_idx] self.assertAlmostEqual(joint_stiffness[dof_idx], expected["stiffness"], places=4) self.assertAlmostEqual(joint_damping[dof_idx], expected["damping"], places=4) self.assertAlmostEqual(joint_target_ke[dof_idx], expected["target_ke"], places=1) self.assertAlmostEqual(joint_target_kd[dof_idx], expected["target_kd"], places=1) def test_jnt_actgravcomp_parsing(self): """Test parsing of actuatorgravcomp from MJCF""" mjcf_content = """ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf_content) model = builder.finalize() self.assertTrue(hasattr(model, "mujoco")) self.assertTrue(hasattr(model.mujoco, "jnt_actgravcomp")) jnt_actgravcomp = model.mujoco.jnt_actgravcomp.numpy() # Bodies are added in order self.assertEqual(jnt_actgravcomp[0], True) self.assertEqual(jnt_actgravcomp[1], False) self.assertEqual(jnt_actgravcomp[2], False) # Default def test_xform_with_floating_false(self): """Test that xform parameter is respected when floating=False""" local_pos = wp.vec3(1.0, 2.0, 3.0) local_quat = wp.quat_rpy(0.5, -0.8, 0.7) local_xform = wp.transform(local_pos, local_quat) # Create a simple MJCF with a body that has a freejoint mjcf_content = f""" """ # Create a non-identity transform to apply xform_pos = wp.vec3(5.0, 10.0, 15.0) xform_quat = wp.quat_from_axis_angle(wp.vec3(0.0, 0.0, 1.0), wp.pi / 4.0) # 45 degree rotation around Z xform = wp.transform(xform_pos, xform_quat) # Parse with floating=False and the xform builder = newton.ModelBuilder() builder.add_mjcf(mjcf_content, floating=False, xform=xform) model = builder.finalize() # Verify the model has a fixed joint self.assertEqual(model.joint_count, 1) joint_type = model.joint_type.numpy()[0] self.assertEqual(joint_type, newton.JointType.FIXED) # Verify the fixed joint has the correct parent_xform # The joint_X_p should match the world_xform (xform * local_xform) joint_X_p = model.joint_X_p.numpy()[0] expected_xform = xform * local_xform # Check position np.testing.assert_allclose( joint_X_p[:3], [expected_xform.p[0], expected_xform.p[1], expected_xform.p[2]], rtol=1e-5, atol=1e-5, err_msg="Fixed joint parent_xform position does not match expected xform", ) # Check quaternion (note: quaternions can be negated and still represent the same rotation) expected_quat = np.array([expected_xform.q[0], expected_xform.q[1], expected_xform.q[2], expected_xform.q[3]]) actual_quat = joint_X_p[3:7] # Check if quaternions match (accounting for q and -q representing the same rotation) quat_match = np.allclose(actual_quat, expected_quat, rtol=1e-5, atol=1e-5) or np.allclose( actual_quat, -expected_quat, rtol=1e-5, atol=1e-5 ) self.assertTrue( quat_match, f"Fixed joint parent_xform quaternion does not match expected xform.\n" f"Expected: {expected_quat}\nActual: {actual_quat}", ) # Verify body_q after eval_fk also matches the expected transform state = model.state() newton.eval_fk(model, model.joint_q, model.joint_qd, state) body_q = state.body_q.numpy()[0] np.testing.assert_allclose( body_q[:3], [expected_xform.p[0], expected_xform.p[1], expected_xform.p[2]], rtol=1e-5, atol=1e-5, err_msg="Body position after eval_fk does not match expected xform", ) # Check body quaternion body_quat = body_q[3:7] quat_match = np.allclose(body_quat, expected_quat, rtol=1e-5, atol=1e-5) or np.allclose( body_quat, -expected_quat, rtol=1e-5, atol=1e-5 ) self.assertTrue( quat_match, f"Body quaternion after eval_fk does not match expected xform.\n" f"Expected: {expected_quat}\nActual: {body_quat}", ) def test_joint_type_free_with_floating_false(self): """Test that respects floating=False parameter. MuJoCo supports two syntaxes for free joints: 1. 2. Both should be treated identically when the floating parameter is set. """ # MJCF using instead of mjcf_content = """ """ # Test with floating=False - should create a fixed joint builder = newton.ModelBuilder() builder.add_mjcf(mjcf_content, floating=False) model = builder.finalize() self.assertEqual(model.joint_count, 1) joint_type = model.joint_type.numpy()[0] self.assertEqual(joint_type, newton.JointType.FIXED) # Test with floating=True - should create a free joint builder2 = newton.ModelBuilder() builder2.add_mjcf(mjcf_content, floating=True) model2 = builder2.finalize() self.assertEqual(model2.joint_count, 1) joint_type2 = model2.joint_type.numpy()[0] self.assertEqual(joint_type2, newton.JointType.FREE) # Test with floating=None (default) - should preserve the free joint from MJCF builder3 = newton.ModelBuilder() builder3.add_mjcf(mjcf_content, floating=None) model3 = builder3.finalize() self.assertEqual(model3.joint_count, 1) joint_type3 = model3.joint_type.numpy()[0] self.assertEqual(joint_type3, newton.JointType.FREE) def test_geom_priority_parsing(self): """Test parsing of geom priority from MJCF""" mjcf_content = """ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf_content) model = builder.finalize() self.assertTrue(hasattr(model, "mujoco")) self.assertTrue(hasattr(model.mujoco, "geom_priority")) geom_priority = model.mujoco.geom_priority.numpy() # Shapes are added in order self.assertEqual(geom_priority[0], 1) self.assertEqual(geom_priority[1], 0) self.assertEqual(geom_priority[2], 0) # Default def test_geom_solimp_parsing(self): """Test that geom_solimp attribute is parsed correctly from MJCF.""" mjcf = """ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf) model = builder.finalize() self.assertTrue(hasattr(model, "mujoco"), "Model should have mujoco namespace for custom attributes") self.assertTrue(hasattr(model.mujoco, "geom_solimp"), "Model should have geom_solimp attribute") geom_solimp = model.mujoco.geom_solimp.numpy() self.assertEqual(model.shape_count, 3, "Should have 3 shapes") # Expected values: shape 0 has explicit solimp, shape 1 has defaults, shape 2 has explicit solimp expected_values = { 0: [0.8, 0.9, 0.002, 0.4, 3.0], 1: [0.9, 0.95, 0.001, 0.5, 2.0], # default 2: [0.7, 0.85, 0.003, 0.6, 2.5], } for shape_idx, expected in expected_values.items(): actual = geom_solimp[shape_idx].tolist() for i, (a, e) in enumerate(zip(actual, expected, strict=False)): self.assertAlmostEqual(a, e, places=4, msg=f"geom_solimp[{shape_idx}][{i}] should be {e}, got {a}") def _create_mjcf_with_option(self, option_attr, option_value): """Helper to create standard MJCF with a single option.""" return f""" """ def test_option_scalar_world_parsing(self): """Test parsing of WORLD frequency scalar options from MJCF (6 options).""" test_cases = [ ("impratio", "1.5", 1.5, 6), ("tolerance", "1e-6", 1e-6, 10), ("ls_tolerance", "0.001", 0.001, 6), ("ccd_tolerance", "1e-5", 1e-5, 10), ("density", "1.225", 1.225, 6), ("viscosity", "1.8e-5", 1.8e-5, 10), ] for option_name, mjcf_value, expected, places in test_cases: with self.subTest(option=option_name): mjcf = self._create_mjcf_with_option(option_name, mjcf_value) builder = newton.ModelBuilder() builder.add_mjcf(mjcf) model = builder.finalize() self.assertTrue(hasattr(model, "mujoco")) self.assertTrue(hasattr(model.mujoco, option_name)) value = getattr(model.mujoco, option_name).numpy() self.assertEqual(len(value), 1) self.assertAlmostEqual(value[0], expected, places=places) def test_option_scalar_per_world(self): """Test that scalar options are correctly remapped per world when merging builders.""" # Robot A robot_a = newton.ModelBuilder() robot_a.add_mjcf(""" """) # Robot B robot_b = newton.ModelBuilder() robot_b.add_mjcf(""" """) # Merge into main builder main = newton.ModelBuilder() main.add_world(robot_a) main.add_world(robot_b) model = main.finalize() self.assertTrue(hasattr(model, "mujoco")) self.assertTrue(hasattr(model.mujoco, "impratio")) self.assertTrue(hasattr(model.mujoco, "tolerance")) self.assertTrue(hasattr(model.mujoco, "ls_tolerance")) impratio = model.mujoco.impratio.numpy() tolerance = model.mujoco.tolerance.numpy() ls_tolerance = model.mujoco.ls_tolerance.numpy() # Should have 2 worlds with different values self.assertEqual(len(impratio), 2) self.assertEqual(len(tolerance), 2) self.assertEqual(len(ls_tolerance), 2) self.assertAlmostEqual(impratio[0], 1.5, places=4, msg="World 0 should have impratio=1.5") self.assertAlmostEqual(impratio[1], 2.0, places=4, msg="World 1 should have impratio=2.0") self.assertAlmostEqual(tolerance[0], 1e-6, places=10, msg="World 0 should have tolerance=1e-6") self.assertAlmostEqual(tolerance[1], 1e-7, places=10, msg="World 1 should have tolerance=1e-7") self.assertAlmostEqual(ls_tolerance[0], 0.001, places=6, msg="World 0 should have ls_tolerance=0.001") self.assertAlmostEqual(ls_tolerance[1], 0.002, places=6, msg="World 1 should have ls_tolerance=0.002") def test_option_vector_world_parsing(self): """Test parsing of WORLD frequency vector options from MJCF (2 options).""" test_cases = [ ("wind", "1 0.5 -0.5", [1, 0.5, -0.5]), ("magnetic", "0 -1 0.5", [0, -1, 0.5]), ] for option_name, mjcf_value, expected in test_cases: with self.subTest(option=option_name): mjcf = self._create_mjcf_with_option(option_name, mjcf_value) builder = newton.ModelBuilder() builder.add_mjcf(mjcf) model = builder.finalize() self.assertTrue(hasattr(model, "mujoco")) self.assertTrue(hasattr(model.mujoco, option_name)) value = getattr(model.mujoco, option_name).numpy() self.assertEqual(len(value), 1) self.assertTrue(np.allclose(value[0], expected)) def test_option_numeric_once_parsing(self): """Test parsing of ONCE frequency numeric options from MJCF (3 options).""" test_cases = [ ("ccd_iterations", "25", 25), ("sdf_iterations", "20", 20), ("sdf_initpoints", "50", 50), ] for option_name, mjcf_value, expected in test_cases: with self.subTest(option=option_name): mjcf = self._create_mjcf_with_option(option_name, mjcf_value) builder = newton.ModelBuilder() builder.add_mjcf(mjcf) model = builder.finalize() self.assertTrue(hasattr(model, "mujoco")) self.assertTrue(hasattr(model.mujoco, option_name)) value = getattr(model.mujoco, option_name).numpy() # ONCE frequency: single value, not per-world self.assertEqual(len(value), 1) self.assertEqual(value[0], expected) def test_option_enum_once_parsing(self): """Test parsing of ONCE frequency enum options from MJCF (4 options).""" test_cases = [ ("integrator", "Euler", 0), ("solver", "Newton", 2), ("cone", "elliptic", 1), ("jacobian", "sparse", 1), ] for option_name, mjcf_value, expected_int in test_cases: with self.subTest(option=option_name): mjcf = self._create_mjcf_with_option(option_name, mjcf_value) builder = newton.ModelBuilder() builder.add_mjcf(mjcf) model = builder.finalize() self.assertTrue(hasattr(model, "mujoco")) self.assertTrue(hasattr(model.mujoco, option_name)) value = getattr(model.mujoco, option_name).numpy() self.assertEqual(len(value), 1) # ONCE frequency self.assertEqual(value[0], expected_int) def test_option_tag_pair_syntax(self): """Test that options work with tag-pair syntax in addition to self-closing tags.""" # Test with tag-pair syntax: mjcf = """ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf) model = builder.finalize() self.assertTrue(hasattr(model, "mujoco")) self.assertTrue(hasattr(model.mujoco, "impratio")) self.assertTrue(hasattr(model.mujoco, "tolerance")) self.assertTrue(hasattr(model.mujoco, "integrator")) # Verify values are parsed correctly self.assertAlmostEqual(model.mujoco.impratio.numpy()[0], 2.5, places=4) self.assertAlmostEqual(model.mujoco.tolerance.numpy()[0], 1e-7, places=10) self.assertEqual(model.mujoco.integrator.numpy()[0], 1) # RK4 def test_geom_solmix_parsing(self): """Test that geom_solmix attribute is parsed correctly from MJCF.""" mjcf = """ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf) model = builder.finalize() self.assertTrue(hasattr(model, "mujoco"), "Model should have mujoco namespace for custom attributes") self.assertTrue(hasattr(model.mujoco, "geom_solmix"), "Model should have geom_solmix attribute") geom_solmix = model.mujoco.geom_solmix.numpy() self.assertEqual(model.shape_count, 3, "Should have 3 shapes") # Expected values: shape 0 has explicit solimp=0.5, shape 1 has solimp=default=1.0, shape 2 has explicit solimp=0.8 expected_values = { 0: 0.5, 1: 1.0, # default 2: 0.8, } for shape_idx, expected in expected_values.items(): actual = geom_solmix[shape_idx].tolist() self.assertAlmostEqual(actual, expected, places=4) def test_shape_gap_from_mjcf(self): """Test that MJCF gap attribute is parsed into shape_gap.""" mjcf = """ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf) model = builder.finalize() shape_gap = model.shape_gap.numpy() self.assertEqual(model.shape_count, 3, "Should have 3 shapes") expected_values = { 0: 0.1, 1: builder.rigid_gap, # default gap when not specified in MJCF 2: 0.2, } for shape_idx, expected in expected_values.items(): actual = float(shape_gap[shape_idx]) self.assertAlmostEqual(actual, expected, places=4) def test_margin_gap_combined_conversion(self): """Test MuJoCo->Newton conversion when both margin and gap are set. Verifies that newton_margin = mj_margin - mj_gap and newton_gap = mj_gap when both attributes are present on the same geom. """ mjcf = """ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf) model = builder.finalize() shape_margin = model.shape_margin.numpy() shape_gap = model.shape_gap.numpy() self.assertEqual(model.shape_count, 4) # geom "both": margin=0.5, gap=0.2 -> newton_margin=0.3, newton_gap=0.2 self.assertAlmostEqual(float(shape_margin[0]), 0.3, places=5) self.assertAlmostEqual(float(shape_gap[0]), 0.2, places=5) # geom "margin_only": margin=0.3, gap absent -> newton_margin=0.3, gap=default self.assertAlmostEqual(float(shape_margin[1]), 0.3, places=5) self.assertAlmostEqual(float(shape_gap[1]), builder.rigid_gap, places=5) # geom "gap_only": margin absent, gap=0.15 -> margin=default(0.0), gap=0.15 self.assertAlmostEqual(float(shape_margin[2]), 0.0, places=5) self.assertAlmostEqual(float(shape_gap[2]), 0.15, places=5) # geom "neither": both absent -> defaults self.assertAlmostEqual(float(shape_margin[3]), 0.0, places=5) self.assertAlmostEqual(float(shape_gap[3]), builder.rigid_gap, places=5) def test_margin_gap_mujoco_solver(self): """Verify geom_margin = shape_margin and geom_gap = 0 in the MuJoCo solver. MJCF margin/gap are parsed into the Newton model with the standard conversion (newton_margin = mj_margin - mj_gap, newton_gap = mj_gap), but the MuJoCo solver does not forward gap: geom_gap is always 0 and geom_margin equals shape_margin (not shape_margin + shape_gap). """ mjcf = """ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf) model = builder.finalize() solver = SolverMuJoCo(model, iterations=1, disable_contacts=True) geom_margin = solver.mjw_model.geom_margin.numpy() geom_gap = solver.mjw_model.geom_gap.numpy() shape_margin = model.shape_margin.numpy() shape_gap = model.shape_gap.numpy() # Verify import conversion: newton_margin = mj_margin - mj_gap # geom "both": margin=0.5, gap=0.2 -> newton_margin=0.3, newton_gap=0.2 self.assertAlmostEqual(float(shape_margin[0]), 0.3, places=5) self.assertAlmostEqual(float(shape_gap[0]), 0.2, places=5) # geom "margin_only": margin=0.3 -> newton_margin=0.3, gap=default self.assertAlmostEqual(float(shape_margin[1]), 0.3, places=5) # geom_margin should equal shape_margin (gap is NOT added back) self.assertAlmostEqual(float(geom_margin[0, 0]), float(shape_margin[0]), places=5) self.assertAlmostEqual(float(geom_margin[0, 1]), float(shape_margin[1]), places=5) # geom_gap is always 0 in the MuJoCo solver self.assertAlmostEqual(float(geom_gap[0, 0]), 0.0, places=5) self.assertAlmostEqual(float(geom_gap[0, 1]), 0.0, places=5) def test_default_inheritance(self): """Test nested default class inheritanc.""" mjcf_content = """ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf_content) model = builder.finalize() self.assertEqual(builder.shape_count, 1) self.assertEqual(builder.shape_type[0], GeoType.SPHERE) # Verify condim is 6 (inherited from parent) # If inheritance is broken, this will be the default value (usually 3) if hasattr(model, "mujoco") and hasattr(model.mujoco, "condim"): condim = model.mujoco.condim.numpy()[0] self.assertEqual(condim, 6, "condim should be 6 (inherited from parent class 'collision')") else: self.fail("Model should have mujoco.condim attribute") class TestImportMjcfActuatorsFrames(unittest.TestCase): def test_actuatorfrcrange_parsing(self): """Test that actuatorfrcrange is parsed from MJCF joint attributes and applied to joint effort limits.""" mjcf_content = """ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf_content) model = builder.finalize() prefix = "test_actuatorfrcrange/worldbody" joint1_idx = model.joint_label.index(f"{prefix}/link1/joint1") joint2_idx = model.joint_label.index(f"{prefix}/link2/joint2") joint3_idx = model.joint_label.index(f"{prefix}/link3/joint3") joint4_idx = model.joint_label.index(f"{prefix}/link4/joint4") joint5_idx = model.joint_label.index(f"{prefix}/link5/joint5") joint1_dof_idx = model.joint_qd_start.numpy()[joint1_idx] joint2_dof_idx = model.joint_qd_start.numpy()[joint2_idx] joint3_dof_idx = model.joint_qd_start.numpy()[joint3_idx] joint4_dof_idx = model.joint_qd_start.numpy()[joint4_idx] joint5_dof_idx = model.joint_qd_start.numpy()[joint5_idx] effort_limits = model.joint_effort_limit.numpy() self.assertAlmostEqual( effort_limits[joint1_dof_idx], 100.0, places=5, msg="Effort limit for joint1 should be 100 from actuatorfrcrange with actuatorfrclimited='true'", ) self.assertAlmostEqual( effort_limits[joint2_dof_idx], 50.0, places=5, msg="Effort limit for joint2 should be 50 from actuatorfrcrange with actuatorfrclimited='auto'", ) self.assertAlmostEqual( effort_limits[joint3_dof_idx], 200.0, places=5, msg="Effort limit for joint3 should be 200 from actuatorfrcrange with default actuatorfrclimited", ) self.assertAlmostEqual( effort_limits[joint4_dof_idx], 1e6, places=5, msg="Effort limit for joint4 should be default value (1e6) when actuatorfrcrange not specified", ) self.assertAlmostEqual( effort_limits[joint5_dof_idx], 1e6, places=5, msg="Effort limit for joint5 should be default (1e6) when actuatorfrclimited='false'", ) def test_eq_solref_parsing(self): """Test that equality constraint solref attribute is parsed correctly from MJCF.""" mjcf = """ """ builder = newton.ModelBuilder() builder.add_mjcf(mjcf) model = builder.finalize() self.assertTrue(hasattr(model, "mujoco"), "Model should have mujoco namespace for custom attributes") self.assertTrue(hasattr(model.mujoco, "eq_solref"), "Model should have eq_solref attribute") eq_solref = model.mujoco.eq_solref.numpy() self.assertEqual(model.equality_constraint_count, 3, "Should have 3 equality constraints") # Note: Newton parses equality constraints in type order: connect, then weld, then joint # So the order is: connect (default), weld (0.03, 0.8), weld (0.05, 1.2) expected_values = { 0: [0.02, 1.0], # connect - default 1: [0.03, 0.8], # first weld 2: [0.05, 1.2], # second weld } for eq_idx, expected in expected_values.items(): actual = eq_solref[eq_idx].tolist() for i, (a, e) in enumerate(zip(actual, expected, strict=False)): self.assertAlmostEqual(a, e, places=4, msg=f"eq_solref[{eq_idx}][{i}] should be {e}, got {a}") def test_parse_mujoco_options_disabled(self): """Test that solver options from