Collisions#
Newton provides a flexible collision detection system for rigid-rigid and soft-rigid contacts. The pipeline handles broad phase culling, narrow phase contact generation, and filtering.
Newton’s collision system is also compatible with MuJoCo-imported models via MJWarp, enabling advanced contact models (SDF, hydroelastic) for MuJoCo scenes. See examples/mjwarp/ for usage.
Collision Pipelines#
Newton provides two collision pipeline implementations:
- CollisionPipeline (Standard)
Uses precomputed shape pairs determined during model finalization. Efficient when the number of potentially colliding pairs is limited (NxN minus filtering rules). For scenes with many shapes where most pairs are filtered out, this avoids runtime broad phase overhead.
- CollisionPipelineUnified
Supports multiple broad phase algorithms. Use this when the number of potential collision pairs would be large (e.g., hundreds of shapes that could all collide). Also required for advanced contact models like SDF-based and hydroelastic contacts. See Unified Pipeline for details.
Basic usage:
# Default: uses CollisionPipeline with precomputed pairs
contacts = model.collide(state)
# Or explicitly create a pipeline
from newton import CollisionPipelineUnified, BroadPhaseMode
pipeline = CollisionPipelineUnified.from_model(
model,
broad_phase_mode=BroadPhaseMode.SAP,
)
contacts = model.collide(state, collision_pipeline=pipeline)
Supported Shape Types#
Newton supports the following geometry types via GeoType:
Type |
Description |
|---|---|
|
Infinite plane (ground) |
|
Sphere primitive |
|
Cylinder with hemispherical ends |
|
Axis-aligned box |
|
Cylinder |
|
Cone |
|
Ellipsoid |
|
Triangle mesh (arbitrary, including non-convex) |
|
Convex hull mesh |
Note
Heightfields (HFIELD) are not implemented. Convert heightfield terrain to a triangle mesh.
Note
SDF is a collision option, not a standalone shape type. Enable SDF generation on any shape
via sdf_max_resolution or sdf_target_voxel_size to precompute a signed distance field
from the shape’s geometry. The SDF provides O(1) distance queries that accelerate collision
detection, especially for mesh-mesh pairs. The collision pipeline decides when to use SDF data
based on efficiency.
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. Usebody=-1for 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.Thickness (
shape_thickness): Surface thickness used in contact generation (see Shape Configuration).Source geometry (
shape_source): Reference to the underlying geometry object (e.g.,Mesh,SDF).
During collision detection, shapes are transformed to world space using their parent body’s pose:
# 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#
Both pipelines use the same filtering rules based on world indices and collision groups.
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
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 begin_world() and end_world().
Note
MJWarp does not currently support heterogeneous environments (different models per world).
World indices are stored in Model.shape_world, Model.body_world, etc.
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
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 |
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.
# 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.
# 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:
Collision Groups - Group-based filtering using
UsdPhysicsCollisionGroupPairwise 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.
# 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 = </CollisionGroup_Robot>
}
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.
# Exclude specific shape pairs in USD
def Sphere "ShapeA" (
prepend apiSchemas = ["PhysicsCollisionAPI"]
) {
rel physics:filteredPairs = [</ShapeB>]
}
Newton reads these relationships during USD import and converts them to
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 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).
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=FalseUSD filtered pairs: Pairs defined by
physics:filteredPairsrelationships in USD filesUSD collision disabled: Shapes with
physics:collisionEnabled=false(filtered against all other shapes)
The resulting filter pairs are stored in shape_collision_filter_pairs as a set of
(shape_index_a, shape_index_b) tuples (canonical order: a < b).
USD Import Example
# 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()
Standard Pipeline#
CollisionPipeline is the default implementation. Shape pairs are precomputed during finalize() based on filtering rules.
When to use:
Limited number of potential collision pairs (filtering rules eliminate most NxN combinations)
Static collision topology (pairs don’t change at runtime)
Scenes with <100 potentially colliding shapes
Limitations:
Does not support advanced contact models (SDF-based, hydroelastic, cylinder, cone primitives)
Pairs fixed at finalization - inefficient if NxN minus filtering is still large
Note
Development is focused on CollisionPipelineUnified, which will replace the standard
CollisionPipeline in the future once feature and performance parity is achieved.
New contact models (SDF, hydroelastic, cylinder/cone primitives) are only being added to
the unified pipeline. Consider using CollisionPipelineUnified with
BroadPhaseMode.EXPLICIT if you need static pairs with advanced contact models.
Standard Pipeline Shape Compatibility#
Plane |
Sphere |
Capsule |
Box |
Cylinder |
Cone |
Mesh |
SDF |
Particle |
|
|---|---|---|---|---|---|---|---|---|---|
Plane |
✅ |
✅ |
✅ |
✅ |
✅ |
||||
Sphere |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
|||
Capsule |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
|||
Box |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
|||
Cylinder |
✅ |
||||||||
Cone |
✅ |
||||||||
Mesh |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
|||
SDF |
✅ |
||||||||
Particle |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
Empty cells indicate unsupported pairs. Use CollisionPipelineUnified for cylinder, cone, SDF, and hydroelastic contact generation.
The pipeline is created automatically when calling collide() without arguments:
contacts = model.collide(state) # Uses CollisionPipeline internally
Unified Pipeline#
CollisionPipelineUnified provides configurable broad phase algorithms:
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 like standard pipeline, but with unified pipeline’s contact algorithms. Combines static pair efficiency with advanced contact models. |
from newton import CollisionPipelineUnified, BroadPhaseMode
# NxN for small scenes
pipeline = CollisionPipelineUnified.from_model(model, broad_phase_mode=BroadPhaseMode.NXN)
# SAP for larger scenes
pipeline = CollisionPipelineUnified.from_model(model, broad_phase_mode=BroadPhaseMode.SAP)
contacts = model.collide(state, collision_pipeline=pipeline)
Unified Pipeline Shape Compatibility#
The unified pipeline supports collision detection between all shape type combinations:
Plane |
Sphere |
Capsule |
Box |
Cylinder |
Cone |
Mesh |
SDF |
Particle |
|
|---|---|---|---|---|---|---|---|---|---|
Plane |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
||
Sphere |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
|
Capsule |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
|
Box |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
|
Cylinder |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
|
Cone |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
|
Mesh |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
✅⚠️ |
✅⚠️ |
|
SDF |
✅ |
✅ |
✅ |
✅ |
✅ |
✅ |
✅⚠️ |
✅ |
|
Particle |
Legend: ⚠️ = Can be slow for meshes with high triangle counts
Ellipsoid and ConvexMesh are also fully supported. The only unsupported type is HFIELD (heightfield) - convert to mesh instead.
Note
SDF in this table refers to shapes with precomputed SDF data (via sdf_max_resolution or sdf_target_voxel_size). SDFs are generated from a shape’s primary geometry and provide O(1) distance queries.
Note
CollisionPipelineUnified does not currently support particle (soft body) collisions. Use the standard pipeline for particle-shape contacts. The unified pipeline is under active development.
Narrow Phase Algorithms#
After broad phase identifies candidate pairs, the narrow phase generates contact points.
MPR (Minkowski Portal Refinement)
The primary algorithm for convex shape pairs. 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.
Multi-contact Generation
For shape pairs, multiple contact points are generated for stable stacking and resting contacts. For the standard collision pipeline, the maximum contacts per shape pair is controlled by rigid_contact_max_per_pair in Model.collide(). The unified collision pipeline automatically estimates buffer sizes based on the model.
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:
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.
SDF-based (recommended): Uses precomputed signed distance fields for fast queries. Enable by setting
sdf_max_resolutionorsdf_target_voxel_sizeon shapes.
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, configure SDF
via sdf_max_resolution or sdf_target_voxel_size:
cfg = builder.ShapeConfig(
sdf_max_resolution=64, # Precompute SDF for fast mesh-mesh collision
)
builder.add_shape_mesh(body, mesh=my_mesh, cfg=cfg)
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:
Contacts are binned by normal direction (20 icosahedron face directions)
Within each bin, contacts are scored by spatial distribution and penetration depth
Representative contacts are selected using configurable depth thresholds (betas)
To disable reduction, set reduce_contacts=False when creating the pipeline.
Configuring contact reduction (SDFHydroelasticConfig):
For hydroelastic and SDF-based contacts, use SDFHydroelasticConfig to tune reduction behavior:
from newton import SDFHydroelasticConfig
config = SDFHydroelasticConfig(
reduce_contacts=True, # Enable contact reduction
betas=(10.0, -0.5), # Scoring thresholds (default)
sticky_contacts=0.0, # Temporal persistence (0 = disabled)
normal_matching=True, # Align reduced normals with aggregate force
moment_matching=False, # Match friction moments (experimental)
)
pipeline = CollisionPipelineUnified.from_model(model, sdf_hydroelastic_config=config)
Understanding betas:
The betas tuple controls how contacts are scored for selection. Each beta value (first element, second element, etc.) produces a separate set of representative contacts per normal bin:
Positive beta (e.g.,
10.0): Score =spatial_position + depth * beta. Higher values favor deeper contacts.Negative beta (e.g.,
-0.5): Score =spatial_position * depth^(-beta)for penetrating contacts. This weighs spatial distribution more heavily for shallow contacts.
The default (10.0, -0.5) provides a balance: one set prioritizes penetration depth,
another prioritizes spatial coverage. More betas = more contacts retained but better coverage.
Note
The beta scoring behavior is subject to refinement. The unified collision pipeline is under active development and these parameters may change in future releases.
Other reduction options:
Parameter |
Description |
|---|---|
|
Temporal persistence threshold. When > 0, contacts from previous frames within this distance are preserved to prevent jittering. Default: 0.0 (disabled). |
|
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. |
|
Preserves torsional friction by adding an anchor contact at the depth-weighted centroid and scaling friction coefficients. This ensures the reduced contact set produces similar resistance to rotational sliding as the original contacts. Experimental. Default: False. |
|
Lower bound on contact area. Hydroelastic stiffness is |
Shape Configuration#
Shape collision behavior is controlled via ShapeConfig:
Collision control:
Parameter |
Description |
|---|---|
|
Collision group ID. 0 disables collisions. Default: 1. |
|
Filter collisions with adjacent body (parent in articulation or connected via joint). Default: True. |
|
Whether shape collides with other shapes. Default: True. |
|
Whether shape collides with particles. Default: True. |
Geometry parameters:
Parameter |
Description |
|---|---|
|
Surface thickness. Pairwise: summed ( |
|
AABB expansion for early contact detection. Pairwise: max. The margin only affects contact generation; effective rest distance is not affected and is only governed by |
|
Whether shape is solid or hollow. Affects inertia and SDF sign. Default: True. |
|
Whether the shape uses SDF-based hydroelastic contacts. Both shapes in a pair must have this enabled. See Hydroelastic Contacts. Default: False. |
|
Contact stiffness for hydroelastic collisions. Used by MuJoCo, Featherstone, SemiImplicit when |
Note
Contact generation: A contact is created when d < max(margin_a, margin_b), where
d = surface_distance - (thickness_a + thickness_b). The solver enforces d >= 0,
so objects at rest settle with surfaces separated by thickness_a + thickness_b.
SDF configuration (generates SDF from shape geometry):
Parameter |
Description |
|---|---|
|
Maximum SDF grid dimension (must be divisible by 8). Either this or |
|
Target voxel size for SDF. Takes precedence over |
|
SDF narrow band distance range (inner, outer). Default: (-0.1, 0.1). |
Example:
cfg = builder.ShapeConfig(
collision_group=-1, # Collide with everything
thickness=0.001, # 1mm thickness
contact_margin=0.01, # 1cm margin
sdf_max_resolution=64, # Enable SDF for mesh
)
builder.add_shape_mesh(body, mesh=my_mesh, cfg=cfg)
Builder default margin:
The builder’s rigid_contact_margin (default 0.1) applies to shapes without explicit contact_margin. Alternatively, use builder.default_shape_cfg.contact_margin.
Common Patterns#
Creating static/ground geometry
Use body=-1 to attach shapes to the static world frame:
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
builder.add_shape_mesh(body=-1, mesh=terrain_mesh) # Static terrain
Setting default shape configuration
Use builder.default_shape_cfg to set defaults for all shapes:
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
Running collision less frequently
For performance, you can run collision detection less often than simulation substeps:
collide_every_n_substeps = 2
for frame in range(num_frames):
for substep in range(sim_substeps):
if substep % collide_every_n_substeps == 0:
contacts = model.collide(state, collision_pipeline=pipeline)
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:
# Add particles
builder.add_particle(pos=wp.vec3(0, 0, 1), vel=wp.vec3(0, 0, 0), mass=1.0)
# Soft contact margin is set at collision time
contacts = model.collide(state, soft_contact_margin=0.01)
# 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 Data#
The Contacts class stores the results from the collision detection step
and is consumed by the solver step() method for contact handling.
Note
Contact forces are not part of the Contacts class - it only stores geometric
contact information. See SensorContact for computing contact forces.
Rigid contacts:
Attribute |
Description |
|---|---|
|
Number of active rigid contacts (scalar). |
|
Indices of colliding shapes. |
|
World-space contact points on each shape. |
|
Contact point offsets in body-local space. |
|
Contact normal direction (from shape0 to shape1). |
|
Shape thickness at each contact point. |
Soft contacts (particle-shape):
Attribute |
Description |
|---|---|
|
Number of active soft contacts. |
|
Particle indices. |
|
Shape indices. |
|
Contact position and velocity on shape. |
|
Contact normal. |
Example usage:
contacts = model.collide(state)
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]
Model.collide() Parameters#
The Model.collide() method accepts the following parameters:
Parameter |
Description |
|---|---|
|
Current simulation state (required). |
|
Optional custom collision pipeline. If None, creates/reuses default. |
|
Maximum contacts per shape pair. None = no limit. |
|
Maximum soft contacts to allocate. |
|
Margin for soft contact generation. Default: 0.01. |
|
Iterations for edge-SDF contact search. Default: 10. |
|
Enable gradient computation. Default: model.requires_grad. |
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=TrueShapes must have SDF enabled (
sdf_max_resolutionorsdf_target_voxel_size)Only volumetric shapes supported (not planes, heightfields, or non-watertight meshes)
cfg = builder.ShapeConfig(
is_hydroelastic=True, # Opt-in to hydroelastic contacts
sdf_max_resolution=64, # Required for hydroelastic
k_hydro=1.0e11, # Contact stiffness
)
builder.add_shape_box(body, hx=0.5, hy=0.5, hz=0.5, cfg=cfg)
How it works:
SDF intersection finds overlapping regions between shapes
Marching cubes extracts the contact iso-surface
Contact points are distributed across the surface area
Optional contact reduction selects representative points
Hydroelastic stiffness (k_hydro):
The k_hydro 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 SDFHydroelasticConfig (see Contact Reduction).
Contact Materials#
Shape material properties control contact resolution. Configure via ShapeConfig:
Property |
Description |
Solvers |
ShapeConfig |
Model Array |
|---|---|---|---|---|
|
Dynamic friction coefficient |
All |
||
|
Contact elastic stiffness |
SemiImplicit, Featherstone, MuJoCo |
||
|
Contact damping |
SemiImplicit, Featherstone, MuJoCo |
||
|
Friction damping coefficient |
SemiImplicit, Featherstone |
||
|
Adhesion distance |
SemiImplicit, Featherstone |
||
|
Bounciness (requires |
XPBD |
||
|
Resistance to spinning at contact |
XPBD, MuJoCo |
||
|
Resistance to rolling motion |
XPBD, MuJoCo |
||
|
Hydroelastic stiffness |
SemiImplicit, Featherstone, MuJoCo |
Example:
cfg = builder.ShapeConfig(
mu=0.8, # High friction
ke=1.0e6, # Stiff contact
kd=1000.0, # Damping
restitution=0.5, # Bouncy (XPBD only)
)
USD Integration#
Custom collision properties can be authored in USD:
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:contact_thickness = 0.00001
}
See Custom Attributes and USD Parsing and Schema Resolver System for details.
Performance#
Use EXPLICIT or standard pipeline 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
Adjust
rigid_contact_max_per_pairto limit memory usage in complex scenes
See Also#
Imports:
import newton
from newton import (
CollisionPipeline,
CollisionPipelineUnified,
BroadPhaseMode,
Contacts,
GeoType,
)
from newton.geometry import SDFHydroelasticConfig
API Reference:
CollisionPipeline- Standard collision pipelineCollisionPipelineUnified- Unified pipeline with broad phase optionsBroadPhaseMode- Broad phase algorithm selectionContacts- Contact data containerGeoType- Shape geometry typesShapeConfig- Shape configuration optionscollide()- Collision detection methodSDFHydroelasticConfig- Hydroelastic contact configuration
Model attributes:
shape_collision_group- Per-shape collision groupsshape_world- Per-shape world indicesshape_contact_margin- Per-shape contact marginsshape_thickness- Per-shape thickness values
Related documentation:
Custom Attributes - USD custom attributes for collision properties
USD Parsing and Schema Resolver System - USD import options including collision settings
Sites (Abstract Markers) - Non-colliding reference points