[isaacsim.physics.newton] Isaac Sim Newton Physics#
Version: 0.7.14
Overview#
The isaacsim.physics.newton extension integrates Newton physics simulation into Isaac Sim, providing an alternative physics engine to PhysX with support for advanced solvers including XPBD and MuJoCo backends. This extension enables high-performance physics simulation with CUDA graph capture optimization and tensor-based interfaces for machine learning workflows.
Key Components#
Physics Engine Management#
The extension provides APIs to manage multiple physics engines within Isaac Sim. The get_available_physics_engines function lists all registered physics engines with their active status, while get_active_physics_engine returns the currently active engine name. This allows applications to query and switch between different physics backends dynamically.
Newton Physics Interface#
The core physics control is accessed through acquire_physics_interface, which returns a NewtonPhysicsInterface for controlling simulation parameters and execution. The interface manages simulation stepping, state synchronization, and provides access to the underlying Newton solver systems.
Stage Management#
The acquire_stage function provides access to the NewtonStage object, which handles the simulation stage and USD integration. This stage object manages the physics scene representation and coordinates with the broader Isaac Sim USD workflow.
Configuration System#
NewtonConfig serves as the primary configuration class, following IsaacLab’s pattern of separating simulation-level parameters from solver-specific settings. Key configuration areas include:
Performance Settings: CUDA graph capture, physics frequency, and substep control
USD Integration: Fabric synchronization, PhysX tracker coordination, and joint processing options
Contact Parameters: Stiffness, damping, friction coefficients, and restitution settings
Joint Settings: Limit parameters, armature values, and PD controller scaling
Solver Configurations#
The extension supports multiple solver backends through specialized configuration classes:
XPBDSolverConfig configures the Extended Position-Based Dynamics solver, an implicit integrator for rigid and soft body simulation. Parameters include iteration counts, relaxation values for different constraint types, and compliance settings for joint behaviors.
MuJoCoSolverConfig provides extensive configuration for the MuJoCo Warp solver backend, including constraint limits, solver type selection, integrator options, and actuator gear mappings. This solver can operate in pure MuJoCo CPU mode or utilize the mujoco_warp GPU acceleration.
Integration#
The extension integrates with Isaac Sim’s unified physics interface through omni.physics, allowing applications to switch between Newton and other physics engines seamlessly. The isaacsim.core.simulation_manager dependency provides coordination with the broader simulation workflow, while usdrt.scenegraph enables direct Fabric integration for high-performance scene graph access.
Performance optimization is achieved through CUDA graph capture, which can be controlled via the capture_graph_physics_step setting. The extension can automatically become the active physics engine on startup through the auto_switch_on_startup setting.
Enable Extension#
The extension can be enabled (if not already) in one of the following ways:
Define the next entry as an application argument from a terminal.
APP_SCRIPT.(sh|bat) --enable isaacsim.physics.newton
Define the next entry under [dependencies] in an experience (.kit) file or an extension configuration (extension.toml) file.
[dependencies]
"isaacsim.physics.newton" = {}
Open the Window > Extensions menu in a running application instance and search for isaacsim.physics.newton.
Then, toggle the enable control button if it is not already active.
Extension: {{ extension_version }} |
Documentation Generated: Jun 05, 2026 |
Settings#
Settings Provided by the Extension#
exts.”isaacsim.physics.newton”.capture_graph_physics_step#
Default Value: true
Description: Enable CUDA graph capture for physics stepping to improve performance on GPU.
exts.”isaacsim.physics.newton”.auto_switch_on_startup#
Default Value: true
Description: Automatically switch to Newton physics engine when the extension starts up.
Python API#
The following table summarizes the available classes and functions.
Get the Newton physics interface. |
|
Get the Newton simulation stage. |
|
Get the name of the currently active physics engine. |
|
Get list of all available physics engines. |
Configuration Classes#
Configuration for Newton physics simulation in Isaac Sim. |
|
Configuration for XPBD (Extended Position-Based Dynamics) solver. |
|
Configuration for MuJoCo Warp solver-related parameters. |
Tensor Interface#
The tensor interface provides NumPy, PyTorch, and Warp frontends for physics data access.
Create a simulation view with the specified tensor frontend. |
|
View for articulations in Newton physics simulation. |
|
View for rigid bodies in Newton physics simulation. |
|
View for contact sensors in Newton physics simulation. |
Functions#
- acquire_physics_interface() NewtonPhysicsInterface | None#
Get the Newton physics interface.
- Returns:
The physics interface for controlling simulation, or None if not initialized.
- acquire_stage() NewtonStage | None#
Get the Newton simulation stage.
Function name has a typo (“acuire”) but is kept for backward compatibility.
- Returns:
The simulation stage object, or None if not initialized.
- get_active_physics_engine() str#
Get the name of the currently active physics engine.
- Returns:
Name of the active engine (“newton”, “physx”, etc.) or “Unknown” if none active.
- get_available_physics_engines(
- verbose: bool = False,
Get list of all available physics engines.
- Parameters:
verbose – If True, print available engines to console.
- Returns:
List of tuples (engine_name, is_active) for all registered engines.
Configuration Classes#
- class NewtonConfig(
- num_substeps: int = 1,
- debug_mode: bool = False,
- use_cuda_graph: bool = True,
- time_step_app: bool = True,
- physics_frequency: float = 600.0,
- update_fabric: bool = True,
- disable_physx_fabric_tracker: bool = True,
- collapse_fixed_joints: bool = False,
- fix_missing_xform_ops: bool = True,
- contact_ke: float = 10000.0,
- contact_kd: float = 100.0,
- contact_kf: float = 10.0,
- contact_mu: float = 1.0,
- contact_ka: float = 0.5,
- restitution: float = 0.0,
- contact_margin: float = 0.01,
- soft_contact_margin: float = 0.01,
- joint_limit_ke: float = 100.0,
- joint_limit_kd: float = 1.0,
- armature: float = 0.1,
- joint_damping: float = 1.0,
- pd_scale: float = 1.0,
- solver_cfg: ~isaacsim.physics.newton.impl.solver_config.NewtonSolverConfig = <factory>,
Bases:
objectConfiguration for Newton physics simulation in Isaac Sim.
This configuration follows IsaacLab’s pattern of separating simulation-level parameters from solver-specific parameters.
- armature: float = 0.1#
Default joint armature (rotor inertia).
- collapse_fixed_joints: bool = False#
Whether to merge bodies connected by fixed joints during USD parsing.
When enabled, reduces body count and improves performance.
- contact_ka: float = 0.5#
Default contact adhesion coefficient.
- contact_kd: float = 100.0#
Default contact damping coefficient.
- contact_ke: float = 10000.0#
Default contact stiffness (spring constant).
- contact_kf: float = 10.0#
Default contact friction force coefficient.
- contact_margin: float = 0.01#
Contact margin for rigid body collision detection.
- contact_mu: float = 1.0#
Default friction coefficient (Coulomb friction).
- debug_mode: bool = False#
Whether to enable debug mode for the solver.
- disable_physx_fabric_tracker: bool = True#
Whether to pause PhysX fabric change tracking (if PhysX is loaded).
- fix_missing_xform_ops: bool = True#
Whether to add missing identity xform operations to geometry prims to suppress USD warnings.
- joint_damping: float = 1.0#
Default joint damping coefficient.
- joint_limit_kd: float = 1.0#
Default joint limit damping.
- joint_limit_ke: float = 100.0#
Default joint limit stiffness.
- num_substeps: int = 1#
Number of substeps to use for the solver.
- pd_scale: float = 1.0#
Scaling factor for PD controller gains when parsing USD joint drives.
- physics_frequency: float = 600.0#
Physics simulation frequency in Hz.
- restitution: float = 0.0#
Default coefficient of restitution (bounciness). 0 = no bounce, 1 = perfectly elastic.
- soft_contact_margin: float = 0.01#
Contact margin for soft body collision detection.
- solver_cfg: NewtonSolverConfig#
Solver-specific configuration.
- time_step_app: bool = True#
Whether the application should drive simulation time stepping.
If True, the stage update node calls step_sim(). If False, external code must step.
- update_fabric: bool = True#
Whether to synchronize Newton state to USD Fabric each frame.
- use_cuda_graph: bool = True#
Whether to use CUDA graph capture for performance optimization.
When enabled, the simulation loop is captured as a CUDA graph for faster execution. Highly recommended for production use.
- class XPBDSolverConfig(
- solver_type: Literal['xpbd'] = 'xpbd',
- iterations: int = 2,
- soft_body_relaxation: float = 0.9,
- soft_contact_relaxation: float = 0.9,
- joint_linear_relaxation: float = 0.7,
- joint_angular_relaxation: float = 0.4,
- joint_linear_compliance: float = 0.0,
- joint_angular_compliance: float = 0.0,
- rigid_contact_relaxation: float = 0.8,
- rigid_contact_con_weighting: bool = True,
- angular_damping: float = 0.0,
- enable_restitution: bool = False,
Bases:
NewtonSolverConfigConfiguration for XPBD (Extended Position-Based Dynamics) solver.
An implicit integrator using eXtended Position-Based Dynamics (XPBD) for rigid and soft body simulation.
References
Miles Macklin, Matthias Müller, and Nuttapong Chentanez. 2016. XPBD: position-based simulation of compliant constrained dynamics. In Proceedings of the 9th International Conference on Motion in Games (MIG ‘16). Association for Computing Machinery, New York, NY, USA, 49-54. https://doi.org/10.1145/2994258.2994272
Matthias Müller, Miles Macklin, Nuttapong Chentanez, Stefan Jeschke, and Tae-Yong Kim. 2020. Detailed rigid body simulation with extended position based dynamics. In Proceedings of the ACM SIGGRAPH/Eurographics Symposium on Computer Animation (SCA ‘20). Eurographics Association, Goslar, DEU, Article 10, 1-12. https://doi.org/10.1111/cgf.14105
- angular_damping: float = 0.0#
Angular damping parameter for rigid contact simulation.
- enable_restitution: bool = False#
Whether to enable restitution for rigid contact simulation.
- iterations: int = 2#
Number of solver iterations.
- joint_angular_compliance: float = 0.0#
Compliance parameter for joint angular simulation.
- joint_angular_relaxation: float = 0.4#
Relaxation parameter for joint angular simulation.
- joint_linear_compliance: float = 0.0#
Compliance parameter for joint linear simulation.
- joint_linear_relaxation: float = 0.7#
Relaxation parameter for joint linear simulation.
- rigid_contact_con_weighting: bool = True#
Whether to use contact constraint weighting for rigid contact simulation.
- rigid_contact_relaxation: float = 0.8#
Relaxation parameter for rigid contact simulation.
- soft_body_relaxation: float = 0.9#
Relaxation parameter for soft body simulation.
- soft_contact_relaxation: float = 0.9#
Relaxation parameter for soft contact simulation.
- class MuJoCoSolverConfig(
- solver_type: Literal['mujoco'] = 'mujoco',
- njmax: int = 1200,
- nconmax: int | None = 200,
- iterations: int = 100,
- ls_iterations: int = 15,
- solver: str = 'newton',
- integrator: str = 'implicitfast',
- cone: str = 'elliptic',
- impratio: float = 1.0,
- use_mujoco_cpu: bool = False,
- disable_contacts: bool = False,
- update_data_interval: int = 1,
- save_to_mjcf: str | None = None,
- ls_parallel: bool = True,
- use_mujoco_contacts: bool = False,
- tolerance: float = 1e-06,
- ls_tolerance: float = 0.001,
- include_sites: bool = False,
Bases:
NewtonSolverConfigConfiguration for MuJoCo Warp solver-related parameters.
These parameters are used to configure the MuJoCo Warp solver. For more information, see the MuJoCo Warp documentation.
- cone: str = 'elliptic'#
The type of contact friction cone. Can be “pyramidal” or “elliptic”.
- disable_contacts: bool = False#
Whether to disable contact computation in MuJoCo.
- impratio: float = 1.0#
Frictional-to-normal constraint impedance ratio.
- include_sites: bool = False#
If True, Newton shapes marked with ShapeFlags.SITE are exported as MuJoCo sites.
- integrator: str = 'implicitfast'#
Integrator type. Can be “euler”, “rk4”, or “implicit”, or their corresponding MuJoCo integer constants.
- iterations: int = 100#
Number of solver iterations.
- ls_iterations: int = 15#
Number of line search iterations for the solver.
- ls_parallel: bool = True#
Whether to use parallel line search.
- ls_tolerance: float = 0.001#
Solver tolerance for early termination of the line search.
- njmax: int = 1200#
Number of constraints per environment (world).
- solver: str = 'newton'#
Solver type. Can be “cg” or “newton”, or their corresponding MuJoCo integer constants.
- solver_type: Literal['mujoco'] = 'mujoco'#
‘xpbd’, ‘mujoco’, ‘featherstone’, ‘semiImplicit’.
- Type:
Type of solver to use
- tolerance: float = 1e-06#
Solver tolerance for early termination of the iterative solver.
- update_data_interval: int = 1#
Frequency (in simulation steps) at which to update the MuJoCo Data object from the Newton state.
- use_mujoco_contacts: bool = False#
Whether to use MuJoCo’s contact computation.
- use_mujoco_cpu: bool = False#
Whether to use the pure MuJoCo backend instead of mujoco_warp.
Tensor Views#
- create_simulation_view(
- frontend_name: str,
- newton_stage: NewtonStage,
- stage_id: int = -1,
Create a simulation view with the specified tensor frontend.
- Parameters:
frontend_name – Name of the frontend framework.
newton_stage – The Newton stage object from isaacsim.physics.newton.
stage_id – USD stage ID (currently unused, kept for API compatibility).
- Returns:
Simulation view object with the specified frontend.
- Raises:
Exception – If backend creation fails or invalid frontend name is provided.
- class NewtonArticulationView(backend: Any, frontend: Any)#
Bases:
objectView for articulations in Newton physics simulation.
Provides tensor-based access to articulation properties like joint positions, velocities, transforms, etc.
- Parameters:
backend – ArticulationSet backend instance from NewtonSimView.
frontend – Tensor framework frontend.
- apply_forces(
- force_data: Any,
- indices: Any | None = None,
- is_global: bool = True,
- indices_mask: Any | None = None,
Apply forces to articulation links (deprecated, use apply_forces_and_torques_at_position).
- Parameters:
force_data – Forces to apply, shape (count, max_links, 3).
indices – Indices of articulations to apply forces to. If None, applies to all articulations.
is_global – If True, forces are in global frame. If False, in link local frame.
indices_mask – Optional mask for the indices.
- apply_forces_and_torques_at_position(
- force_data: Any | None,
- torque_data: Any | None,
- position_data: Any | None,
- indices: Any,
- is_global: bool = True,
- indices_mask: Any | None = None,
Apply forces and torques to articulation links at specified positions.
This function provides flexible force application to articulation links: - Apply forces at link centers or at specified positions - Apply torques directly to links - Work in global or local coordinate frames - When position is specified with force, automatically computes induced torque
- Parameters:
force_data – Forces to apply, shape (count, max_links, 3). Can be None.
torque_data – Torques to apply, shape (count, max_links, 3). Can be None.
position_data – Positions where forces are applied, shape (count, max_links, 3). Can be None. If specified with force_data, the force is applied at this position relative to the link’s center of mass, generating additional torque.
indices – Indices of articulations to apply forces to.
is_global – If True, force/torque/position are in global frame. If False, in link local frame.
indices_mask – Optional mask for the indices.
- check() bool#
Check if the articulation view is valid and has articulations.
- Returns:
True if the view has a valid backend with at least one articulation.
- get_coms(copy: bool = True) Any#
Get link center of mass positions and orientations.
- Parameters:
copy – Whether to return a copy.
- Returns:
Flat tensor that should be reshaped to (count, max_links, 7). Each COM has 7 values: position (3) + quaternion (4) in scalar-first (w,x,y,z) format. Newton stores COM as offset in body frame. Position is read from Newton, orientation is cached (Newton doesn’t support COM orientation).
- get_coriolis_and_centrifugal_compensation_forces(
- copy: bool = True,
Get Coriolis and centrifugal compensation forces.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_dofs).
- get_disable_gravities(
- copy: bool = True,
Get gravity disable flags for links.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_links).
- get_dof_actuation_forces(
- copy: bool = True,
Get joint actuation forces/torques.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_dofs).
- get_dof_armatures(
- copy: bool = True,
Get joint armatures (rotor inertias).
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_dofs).
- get_dof_dampings(
- copy: bool = True,
Get joint dampings (for velocity control).
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_dofs) on CPU (host memory).
- get_dof_drive_model_properties(
- copy: bool = True,
Get joint drive model properties.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_dofs, 3) where the last dimension contains [speed_effort_gradient, max_actuator_velocity, velocity_dependent_resistance].
- get_dof_friction_properties(
- copy: bool = True,
Get joint friction properties.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_dofs, 3) where the last dimension contains [static_friction, dynamic_friction, viscous_friction].
- get_dof_limits(
- copy: bool = True,
Get joint limits [lower, upper].
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_dofs, 2).
- get_dof_max_forces(
- copy: bool = True,
Get joint maximum forces/torques (effort limits).
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_dofs).
- get_dof_max_velocities(
- copy: bool = True,
Get joint maximum velocities.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_dofs).
- get_dof_position_targets(
- copy: bool = True,
Get joint position targets (for position control).
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_dofs).
- get_dof_positions(
- copy: bool = True,
Get joint positions.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_dofs).
- get_dof_projected_joint_forces(
- copy: bool = True,
Get projected joint forces.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_dofs).
- get_dof_stiffnesses(
- copy: bool = True,
Get joint stiffnesses (for position control).
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_dofs) on CPU (host memory).
- get_dof_velocities(
- copy: bool = True,
Get joint velocities.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_dofs).
- get_dof_velocity_targets(
- copy: bool = True,
Get joint velocity targets (for velocity control).
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_dofs).
- get_drive_types(
- copy: bool = True,
Get joint drive types.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_dofs) of type uint8.
- get_generalized_mass_matrices(
- copy: bool = True,
Get generalized mass matrices.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_dofs, max_dofs).
- get_gravity_compensation_forces(
- copy: bool = True,
Get gravity compensation forces.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_dofs).
- get_inertias(copy: bool = True) Any#
Get link inertias.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_links, 9).
- get_inv_inertias(
- copy: bool = True,
Get link inverse inertias.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_links, 9).
- get_inv_masses(
- copy: bool = True,
Get link inverse masses (1/mass).
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_links).
- get_jacobians(copy: bool = True) Any#
Get Jacobian matrices.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, num_links_effective, 6, num_dofs).
- get_link_incoming_joint_force(
- copy: bool = True,
Get incoming joint forces for each link.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_links, 6).
- get_masses(copy: bool = True) Any#
Get link masses.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, max_links).
- get_metatype(index: int) Any#
Get metadata type for a specific articulation.
- Parameters:
index – Index of the articulation in the view (0 to count-1).
- Returns:
ArticulationMetaType object containing link names, joint names, DOF names, etc.
- Raises:
IndexError – If index is out of range.
- get_root_transforms(
- copy: bool = True,
Get root body transforms [position(3) + quaternion(4)].
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, 7).
- get_root_velocities(
- copy: bool = True,
Get root body velocities [linear(3) + angular(3)].
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, 6).
- set_coms(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set link center of mass positions and orientations.
- Parameters:
data – Tensor of COM data, shape should be (count, max_links, 7) or flat.
indices – Articulation indices.
indices_mask – Optional mask for indices.
- set_disable_gravities(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set gravity disable flags for links.
- Parameters:
data – Gravity disable flags to set, shape (count, max_links).
indices – Articulation indices to update.
indices_mask – Optional mask for indices.
- set_dof_actuation_forces(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set joint actuation forces/torques.
Writes directly into control.joint_f which is consumed by the solver.
- Parameters:
data – Actuation force values to set.
indices – Articulation indices.
indices_mask – Optional mask for indices.
- set_dof_armatures(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set joint armatures (rotor inertias).
- Parameters:
data – Armature values to set.
indices – Articulation indices.
indices_mask – Optional mask for indices.
- set_dof_dampings(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set joint dampings.
- Parameters:
data – Damping values to set.
indices – Articulation indices.
indices_mask – Optional mask for indices.
- set_dof_drive_model_properties(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set joint drive model properties.
- Parameters:
data – Drive model properties to set, shape (count, max_dofs, 3).
indices – Articulation indices to update.
indices_mask – Optional mask for indices.
- set_dof_friction_properties(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set joint friction properties.
- Parameters:
data – Friction properties to set, shape (count, max_dofs, 3).
indices – Articulation indices to update.
indices_mask – Optional mask for indices.
- set_dof_limits(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set joint limits (lower and upper bounds).
- Parameters:
data – Joint limits to set, shape (count, max_dofs, 2) where last dim is [lower, upper].
indices – Articulation indices to update.
indices_mask – Optional mask for indices.
- set_dof_max_forces(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set joint maximum forces/torques (effort limits).
- Parameters:
data – Maximum forces to set, shape (count, max_dofs).
indices – Articulation indices to update.
indices_mask – Optional mask for indices.
- set_dof_max_velocities(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set joint maximum velocities.
- Parameters:
data – Maximum velocities to set, shape (count, max_dofs).
indices – Articulation indices to update.
indices_mask – Optional mask for indices.
- set_dof_position_targets(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set joint position targets.
- Parameters:
data – Position target values to set.
indices – Articulation indices.
indices_mask – Optional mask for indices.
- set_dof_positions(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set joint positions.
- Parameters:
data – Position values to set.
indices – Articulation indices.
indices_mask – Optional mask for indices.
- set_dof_stiffnesses(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set joint stiffnesses.
- Parameters:
data – Stiffness values to set.
indices – Articulation indices.
indices_mask – Optional mask for indices.
- set_dof_velocities(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set joint velocities.
- Parameters:
data – Velocity values to set.
indices – Articulation indices.
indices_mask – Optional mask for indices.
- set_dof_velocity_targets(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set joint velocity targets.
- Parameters:
data – Velocity target values to set.
indices – Articulation indices.
indices_mask – Optional mask for indices.
- set_inertias(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set link inertias.
- Parameters:
data – Inertia values to set.
indices – Articulation indices.
indices_mask – Optional mask for indices.
- set_masses(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set link masses.
- Parameters:
data – Mass values to set.
indices – Articulation indices.
indices_mask – Optional mask for indices.
- set_root_transforms(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set root body transforms.
Automatically detects whether each articulation is fixed-base or floating-base and handles them appropriately: - Fixed-base: Updates Model’s joint_X_p (parent transforms) - Floating-base: Updates State’s joint coordinates After setting transforms, forward kinematics is evaluated to update all link positions.
- Parameters:
data – Root transforms to set (dtype=wp.transform).
indices – Indices of articulations to update.
indices_mask – Optional mask for the indices.
- set_root_velocities(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set root body velocities.
Automatically detects whether each articulation is fixed-base or floating-base: - Fixed-base: Sets body velocities directly (no joint coordinate updates needed) - Floating-base: Updates State’s joint velocity coordinates After setting velocities, forward kinematics may be evaluated if needed.
- Parameters:
data – Root velocities to set (dtype=wp.spatial_vector).
indices – Indices of articulations to update.
indices_mask – Optional mask for the indices.
- update_joints(
- indices: Any,
- indices_mask: Any | None = None,
Update joint states after setting positions/velocities.
This evaluates forward kinematics to update body transforms from joint states.
- Parameters:
indices – Articulation indices to update.
indices_mask – Optional mask for indices.
- property count: int#
Number of articulations in this view.
- Returns:
Number of articulations.
- property dof_names: list[list[str]]#
Degree of freedom (DOF) names for all articulations in the view.
- Returns:
List of DOF name lists, one per articulation.
- property dof_paths: Any#
DOF paths for all articulations in the view.
- Returns:
List of DOF path lists, one per articulation.
- property generalized_mass_matrix_shape: tuple[int, int]#
Generalized mass matrix shape for articulations.
- Returns:
Fixed base: n = max_dofs
Floating base: n = max_dofs + 6
- Return type:
Tuple (n, n) where
- property is_homogeneous: bool#
Whether all articulations in the view have the same structure.
- Returns:
True if all articulations have the same number of DOFs, links, and joints.
- property jacobian_shape: tuple[int, int]#
Jacobian matrix shape for articulations.
- Returns:
Fixed base: rows = (max_links - 1) * 6, cols = max_dofs
Floating base: rows = max_links * 6, cols = max_dofs + 6
- Return type:
Tuple (rows, cols) where
- property joint_names: list[list[str]]#
Joint names for all articulations in the view.
- Returns:
List of joint name lists, one per articulation.
- property joint_paths: list[list[str]]#
Joint paths for all articulations in the view.
- Returns:
List of joint path lists, one per articulation.
- property link_names: list[list[str]]#
Link names for all articulations in the view.
- Returns:
List of link name lists, one per articulation.
- property link_paths: list[list[str]]#
Link paths for all articulations in the view.
- Returns:
List of link path lists, one per articulation.
- property max_dofs: int#
Maximum number of DOFs across all articulations.
- Returns:
Maximum DOF count.
- property max_fixed_tendons: int#
Maximum number of fixed tendons across all articulations.
- Returns:
Maximum fixed tendon count.
- property max_links: int#
Maximum number of links across all articulations.
- Returns:
Maximum link count.
- property max_shapes: int#
Maximum number of shapes across all articulations.
- Returns:
Maximum shape count.
- property prim_paths: list[str]#
Articulation root prim paths.
- Returns:
List of articulation root paths.
Shared metadata type for articulations (if all same type).
- Returns:
ArticulationMetaType object if all articulations have the same structure, None if different types or no articulations.
- class NewtonRigidBodyView(backend: Any, frontend: Any)#
Bases:
objectView for rigid bodies in Newton physics simulation.
Provides tensor-based access to rigid body properties like transforms, velocities, masses, etc.
- Parameters:
backend – RigidBodySet backend instance from NewtonSimView.
frontend – Tensor framework frontend.
- apply_forces(
- force_data: Any,
- indices: Any | None = None,
- is_global: bool = True,
- indices_mask: Any | None = None,
Apply forces to rigid bodies (deprecated, use apply_forces_and_torques_at_position).
- Parameters:
force_data – Forces to apply, shape (count, 3).
indices – Indices of bodies to apply forces to. If None, applies to all bodies.
is_global – If True, forces are in global frame. If False, in body local frame.
indices_mask – Optional mask for the indices.
- apply_forces_and_torques_at_position(
- force_data: Any | None,
- torque_data: Any | None,
- position_data: Any | None,
- indices: Any,
- is_global: bool = True,
- indices_mask: Any | None = None,
Apply forces and torques to rigid bodies at specified positions.
This function provides flexible force application with the following capabilities: - Apply forces at body center or at specified positions - Apply torques directly - Work in global or local coordinate frames - When position is specified with force, automatically computes induced torque
- Parameters:
force_data – Forces to apply, shape (count, 3). Can be None.
torque_data – Torques to apply, shape (count, 3). Can be None.
position_data – Positions where forces are applied, shape (count, 3). Can be None. If specified with force_data, the force is applied at this position relative to the body’s center of mass, generating additional torque.
indices – Indices of bodies to apply forces to.
is_global – If True, force/torque/position are in global frame. If False, in body local frame.
indices_mask – Optional mask for the indices.
- check() bool#
Check if the rigid body view is valid and has bodies.
- Returns:
True if the view has a valid backend with at least one body.
- get_accelerations(
- copy: bool = True,
Get body accelerations [linear(3) + angular(3)].
Requires
body_qddto be allocated on the state viamodel.request_state_attributes("body_qdd")before state creation.- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, 6), or None if body_qdd is not available.
- get_coms(copy: bool = True) Any#
Get body centers of mass [position(3) + orientation(4)].
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, 7). Newton stores COM as offset in body frame. Position is read from Newton, orientation is cached.
- get_disable_gravities(
- copy: bool = True,
Get disable gravity flags for bodies.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, 1) with uint8 values (0=gravity enabled, 1=gravity disabled). Newton doesn’t have per-body gravity flags; returns zeros (all enabled).
- get_disable_simulations(
- copy: bool = True,
Get disable simulation flags for bodies.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, 1) with uint8 values (0=enabled, 1=disabled). Newton doesn’t have a direct equivalent; returns zeros (all enabled).
- get_inertias(copy: bool = True) Any#
Get body inertias as flattened 3x3 matrices.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, 9).
- get_inv_inertias(copy: bool = True) Any#
Get body inverse inertias as flattened 3x3 matrices.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, 9).
- get_inv_masses(copy: bool = True) Any#
Get body inverse masses.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count,).
- get_masses(copy: bool = True) Any#
Get body masses.
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count,).
- get_transforms(copy: bool = True) Any#
Get body transforms [position(3) + quaternion(4)].
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, 7).
- get_velocities(copy: bool = True) Any#
Get body velocities [linear(3) + angular(3)].
- Parameters:
copy – Whether to return a copy.
- Returns:
Tensor of shape (count, 6).
- set_coms(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set body centers of mass.
Position is written to Newton’s body_com. Orientation is cached in _coms buffer since Newton doesn’t support COM orientation.
- Parameters:
data – COM data to set.
indices – Body indices.
indices_mask – Optional mask for indices.
- set_disable_gravities(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set disable gravity flags for bodies.
Newton doesn’t support per-body gravity disabling; this is a no-op.
- Parameters:
data – Disable gravity flags to set.
indices – Body indices.
indices_mask – Optional mask for indices.
- set_disable_simulations(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set disable simulation flags for bodies.
Newton doesn’t support disabling individual bodies; this is a no-op.
- Parameters:
data – Disable simulation flags to set.
indices – Body indices.
indices_mask – Optional mask for indices.
- set_inertias(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set body inertias.
- Parameters:
data – Inertia data to set.
indices – Body indices.
indices_mask – Optional mask for indices.
- set_masses(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set body masses.
- Parameters:
data – Mass data to set.
indices – Body indices.
indices_mask – Optional mask for indices.
- set_transforms(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set body transforms.
For free rigid bodies, this also updates their FREE joint coordinates.
- Parameters:
data – Transform data to set.
indices – Body indices.
indices_mask – Optional mask for indices.
- set_velocities(
- data: Any,
- indices: Any,
- indices_mask: Any | None = None,
Set body velocities.
- Parameters:
data – Velocity data to set.
indices – Body indices.
indices_mask – Optional mask for indices.
- property body_names: list[str]#
List of names for the bodies.
- Returns:
The names for the bodies.
- property body_paths: list[str]#
List of USD paths for the bodies.
- Returns:
The USD paths for the bodies.
- property count: int#
Number of rigid bodies in this view.
- Returns:
The count of rigid bodies.
- property max_shapes: int#
Maximum number of shapes across all bodies.
- Returns:
The maximum number of shapes.
- class NewtonRigidContactView(
- backend: RigidContactSet,
- frontend: NumpyFrontend | TorchFrontend | WarpFrontend,
Bases:
objectView for contact sensors in Newton physics simulation.
Provides tensor-based access to contact forces and contact data, matching PhysX IRigidContactView interface.
- Parameters:
backend – RigidContactSet backend instance from NewtonSimView.
frontend – Tensor framework frontend.
- check() bool#
Check if the view is valid and has sensors.
- Returns:
True if view has a valid backend and at least one sensor.
- get_actor_paths_from_ids(
- actor_ids: warp.array,
Convert body indices (from get_raw_contact_data) to USD paths.
For Newton, actor IDs are body indices stored as uint64.
- Parameters:
actor_ids – Tensor of body indices (uint64), or a slice of it.
- Returns:
List of USD paths. Empty string for invalid indices.
- get_contact_data(
- dt: float,
- max_contact_data_count: int = 0,
- copy: bool = True,
Get detailed contact data (forces, points, normals, separations).
- Parameters:
dt – Time step for force calculation.
max_contact_data_count – Maximum number of contact points to store.
copy – Whether to return copies.
- Returns:
A tuple of (contact_forces, contact_points, contact_normals, contact_separations, contact_counts, contact_start_indices) where:
contact_forces: shape (max_contact_data_count, 1) - normal force magnitudes
contact_points: shape (max_contact_data_count, 3) - world space contact positions
contact_normals: shape (max_contact_data_count, 3) - contact normals
contact_separations: shape (max_contact_data_count, 1) - penetration depths
contact_counts: shape (sensor_count, filter_count) - number of contacts per pair
contact_start_indices: shape (sensor_count, filter_count) - buffer start indices
- get_contact_force_matrix(
- dt: float,
- copy: bool = True,
Get contact force matrix (sensor x filter).
- Parameters:
dt – Time step for force calculation.
copy – Whether to return a copy.
- Returns:
A tensor of shape (sensor_count, filter_count, 3).
- get_net_contact_forces(
- dt: float,
- copy: bool = True,
Get net contact forces for each sensor.
- Parameters:
dt – Time step for force calculation.
copy – Whether to return a copy.
- Returns:
A tensor of shape (sensor_count, 3) with net contact forces.
- get_raw_contact_data(
- dt: float,
- copy: bool = True,
Get raw contact data for all contacts per sensor without filter matching.
- Parameters:
dt – Time step for force calculation.
copy – Whether to return copies.
- Returns:
A tuple of (force_buffer, point_buffer, normal_buffer, separation_buffer, count_buffer, start_indices_buffer, other_actor_ids_buffer) where:
force_buffer: shape (max_contact_data_count, 1) - force magnitudes
point_buffer: shape (max_contact_data_count, 3) - world contact positions
normal_buffer: shape (max_contact_data_count, 3) - contact normals
separation_buffer: shape (max_contact_data_count, 1) - penetration depths
count_buffer: shape (sensor_count,) - contacts per sensor
start_indices_buffer: shape (sensor_count,) - start index per sensor
other_actor_ids_buffer: shape (max_contact_data_count,) - uint64 body IDs
- property count: int#
Number of contact sensors in this view.
- Returns:
Number of contact sensors.
- property filter_count: int#
Maximum number of filter bodies per sensor.
- Returns:
Maximum number of filter bodies per sensor.
- property filter_names: list[list[str]]#
List of filter names.
- Returns:
List of filter names.
- property filter_paths: list[list[str]]#
List of filter paths (list of lists, one list per sensor).
- Returns:
List of filter paths with nested lists for each sensor.
- property max_contact_data_count: int#
Maximum number of contact data entries.
- Returns:
Maximum contact data buffer size.
- property sensor_count: int#
Number of contact sensors.
- Returns:
Number of contact sensors.
- property sensor_names: list[str]#
List of sensor names.
- Returns:
List of sensor names.
- property sensor_paths: list[str]#
List of USD paths for sensors.
- Returns:
List of USD paths for sensors.