newton.solvers.SolverVBD#

class newton.solvers.SolverVBD(model, iterations=10, friction_epsilon=1e-2, integrate_with_external_rigid_solver=False, particle_enable_self_contact=False, particle_self_contact_radius=0.2, particle_self_contact_margin=0.2, particle_conservative_bound_relaxation=0.85, particle_vertex_contact_buffer_size=32, particle_edge_contact_buffer_size=64, particle_collision_detection_interval=0, particle_edge_parallel_epsilon=1e-5, particle_enable_tile_solve=True, particle_topological_contact_filter_threshold=2, particle_rest_shape_contact_exclusion_radius=0.0, particle_external_vertex_contact_filtering_map=None, particle_external_edge_contact_filtering_map=None, rigid_avbd_beta=1.0e5, rigid_avbd_gamma=0.99, rigid_contact_k_start=1.0e2, rigid_joint_linear_k_start=1.0e4, rigid_joint_angular_k_start=1.0e1, rigid_joint_linear_ke=1.0e9, rigid_joint_angular_ke=1.0e9, rigid_joint_linear_kd=0.0, rigid_joint_angular_kd=0.0, rigid_body_contact_buffer_size=64, rigid_body_particle_contact_buffer_size=256, rigid_enable_dahl_friction=False)[source]#

Bases: SolverBase

An implicit solver using Vertex Block Descent (VBD) for particles and Augmented VBD (AVBD) for rigid bodies.

This unified solver supports:
  • Particle simulation (cloth, soft bodies) using the VBD algorithm

  • Rigid body simulation (joints, contacts) using the AVBD algorithm

  • Coupled particle-rigid body systems

For rigid bodies, the AVBD algorithm uses soft constraints with adaptive penalty parameters for joints and contacts. Hard constraints are not currently enforced.

Joint limitations:

See Joint Feature Support for the full comparison across solvers.

References

  • Anka He Chen, Ziheng Liu, Yin Yang, and Cem Yuksel. 2024. Vertex Block Descent. ACM Trans. Graph. 43, 4, Article 116 (July 2024), 16 pages. https://doi.org/10.1145/3658179

Note

SolverVBD requires coloring information for both particles and rigid bodies:

Call newton.ModelBuilder.color() to automatically color both particles and rigid bodies.

Example

# Automatically color both particles and rigid bodies
builder.color()

model = builder.finalize()

solver = newton.solvers.SolverVBD(model)

# Initialize states and contacts
state_in = model.state()
state_out = model.state()
control = model.control()
contacts = model.contacts()

# Simulation loop
for i in range(100):
    model.collide(state_in, contacts)  # Update contacts
    solver.step(state_in, state_out, control, contacts, dt)
    state_in, state_out = state_out, state_in
classmethod register_custom_attributes(builder)#

Register solver-specific custom Model attributes for SolverVBD.

Currently used for cable bending plasticity/hysteresis (Dahl friction model).

Attributes are declared in the vbd namespace so they can be authored in scenes and in USD as newton:vbd:<attr>.

__init__(model, iterations=10, friction_epsilon=1e-2, integrate_with_external_rigid_solver=False, particle_enable_self_contact=False, particle_self_contact_radius=0.2, particle_self_contact_margin=0.2, particle_conservative_bound_relaxation=0.85, particle_vertex_contact_buffer_size=32, particle_edge_contact_buffer_size=64, particle_collision_detection_interval=0, particle_edge_parallel_epsilon=1e-5, particle_enable_tile_solve=True, particle_topological_contact_filter_threshold=2, particle_rest_shape_contact_exclusion_radius=0.0, particle_external_vertex_contact_filtering_map=None, particle_external_edge_contact_filtering_map=None, rigid_avbd_beta=1.0e5, rigid_avbd_gamma=0.99, rigid_contact_k_start=1.0e2, rigid_joint_linear_k_start=1.0e4, rigid_joint_angular_k_start=1.0e1, rigid_joint_linear_ke=1.0e9, rigid_joint_angular_ke=1.0e9, rigid_joint_linear_kd=0.0, rigid_joint_angular_kd=0.0, rigid_body_contact_buffer_size=64, rigid_body_particle_contact_buffer_size=256, rigid_enable_dahl_friction=False)#
Parameters:
  • model (Model) – The Model object used to initialize the integrator. Must be identical to the Model object passed to the step function.

  • parameters (Rigid body)

  • iterations (int) – Number of VBD iterations per step.

  • friction_epsilon (float) – Threshold to smooth small relative velocities in friction computation (used for both particle and rigid body contacts).

  • parameters

  • particle_enable_self_contact (bool) – Whether to enable self-contact detection for particles.

  • particle_self_contact_radius (float) – The radius used for self-contact detection. This is the distance at which vertex-triangle pairs and edge-edge pairs will start to interact with each other.

  • particle_self_contact_margin (float) – The margin used for self-contact detection. This is the distance at which vertex-triangle pairs and edge-edge will be considered in contact generation. It should be larger than particle_self_contact_radius to avoid missing contacts.

  • integrate_with_external_rigid_solver (bool) – Indicator for coupled rigid body-cloth simulation. When set to True, the solver assumes rigid bodies are integrated by an external solver (one-way coupling).

  • particle_conservative_bound_relaxation (float) – Relaxation factor for conservative penetration-free projection.

  • particle_vertex_contact_buffer_size (int) – Preallocation size for each vertex’s vertex-triangle collision buffer.

  • particle_edge_contact_buffer_size (int) – Preallocation size for edge’s edge-edge collision buffer.

  • particle_collision_detection_interval (int) – Controls how frequently particle self-contact detection is applied during the simulation. If set to a value < 0, collision detection is only performed once before the initialization step. If set to 0, collision detection is applied twice: once before and once immediately after initialization. If set to a value n >= 1, collision detection is applied before every n VBD iterations.

  • particle_edge_parallel_epsilon (float) – Threshold to detect near-parallel edges in edge-edge collision handling.

  • particle_enable_tile_solve (bool) – Whether to accelerate the particle solver using tile API.

  • particle_topological_contact_filter_threshold (int) – Maximum topological distance (measured in rings) under which candidate self-contacts are discarded. Set to a higher value to tolerate contacts between more closely connected mesh elements. Only used when particle_enable_self_contact is True. Note that setting this to a value larger than 3 will result in a significant increase in computation time.

  • particle_rest_shape_contact_exclusion_radius (float) – Additional world-space distance threshold for filtering topologically close primitives. Candidate contacts with a rest separation shorter than this value are ignored. The distance is evaluated in the rest configuration conveyed by model.particle_q. Only used when particle_enable_self_contact is True.

  • particle_external_vertex_contact_filtering_map (dict | None) – Optional dictionary used to exclude additional vertex-triangle pairs during contact generation. Keys must be vertex primitive ids (integers), and each value must be a list or set containing the triangle primitives to be filtered out. Only used when particle_enable_self_contact is True.

  • particle_external_edge_contact_filtering_map (dict | None) – Optional dictionary used to exclude additional edge-edge pairs during contact generation. Keys must be edge primitive ids (integers), and each value must be a list or set containing the edges to be filtered out. Only used when particle_enable_self_contact is True.

  • parameters

  • rigid_avbd_beta (float) – Penalty ramp rate for rigid body constraints (how fast k grows with constraint violation).

  • rigid_avbd_gamma (float) – Warmstart decay for penalty k (cross-step decay factor for rigid body constraints).

  • rigid_contact_k_start (float) – Initial penalty stiffness for all body contact constraints, including both body-body (rigid-rigid) and body-particle (rigid-particle) contacts (AVBD).

  • rigid_joint_linear_k_start (float) – Initial penalty seed for linear joint constraints (e.g., cable stretch, BALL linear). Used to seed the per-constraint adaptive penalties for all linear joint constraints.

  • rigid_joint_angular_k_start (float) – Initial penalty seed for angular joint constraints (e.g., cable bend, FIXED angular). Used to seed the per-constraint adaptive penalties for all angular joint constraints.

  • rigid_joint_linear_ke (float) – Stiffness cap used by AVBD for non-cable linear joint constraint scalars (e.g., BALL and the linear part of FIXED). Cable joints use the per-joint caps in model.joint_target_ke instead (cable interprets joint_target_ke/kd as constraint tuning).

  • rigid_joint_angular_ke (float) – Stiffness cap used by AVBD for non-cable angular joint constraint scalars (e.g., FIXED).

  • rigid_joint_linear_kd (float) – Rayleigh damping coefficient for non-cable linear joint constraints (paired with rigid_joint_linear_ke).

  • rigid_joint_angular_kd (float) – Rayleigh damping coefficient for non-cable angular joint constraints (paired with rigid_joint_angular_ke).

  • rigid_body_contact_buffer_size (int) – Max body-body (rigid-rigid) contacts per rigid body for per-body contact lists (tune based on expected body-body contact density).

  • rigid_body_particle_contact_buffer_size (int) – Max body-particle (rigid-particle) contacts per rigid body for per-body soft-contact lists (tune based on expected body-particle contact density).

  • rigid_enable_dahl_friction (bool) – Enable Dahl hysteresis friction model for cable bending (default: False). Configure per-joint Dahl parameters via the solver-registered custom model attributes model.vbd.dahl_eps_max and model.vbd.dahl_tau.

Note

  • The integrate_with_external_rigid_solver argument enables one-way coupling between rigid body and soft body solvers. If set to True, the rigid states should be integrated externally, with state_in passed to step representing the previous rigid state and state_out representing the current one. Frictional forces are computed accordingly.

  • particle_vertex_contact_buffer_size, particle_edge_contact_buffer_size, rigid_body_contact_buffer_size, and rigid_body_particle_contact_buffer_size are fixed and will not be dynamically resized during runtime. Setting them too small may result in undetected collisions (particles) or contact overflow (rigid body contacts). Setting them excessively large may increase memory usage and degrade performance.

collect_rigid_contact_forces(state, contacts, dt)#

Collect per-contact rigid contact forces and world-space application points.

This produces a contact-specific buffer that coupling code can filter (e.g., proxy contacts only).

Parameters:
  • state (State) – Simulation state containing rigid body transforms/velocities used for contact-force evaluation.

  • contacts (Optional[Contacts]) – Contact data buffers containing rigid contact geometry/material references. If None, the function returns default zero/sentinel outputs.

  • dt (float) – Time step size [s].

Returns:

tuple[

wp.array(dtype=wp.int32), wp.array(dtype=wp.int32), wp.array(dtype=wp.vec3), wp.array(dtype=wp.vec3), wp.array(dtype=wp.vec3), wp.array(dtype=wp.int32),

]: Tuple of per-contact outputs:
  • body0: Body index for shape0, int32.

  • body1: Body index for shape1, int32.

  • point0_world: World-space contact point on body0, wp.vec3 [m].

  • point1_world: World-space contact point on body1, wp.vec3 [m].

  • force_on_body1: Contact force applied to body1 in world frame, wp.vec3 [N].

  • rigid_contact_count: Length-1 active rigid-contact count, int32.

Return type:

tuple[array, array, array, array, array, array]

rebuild_bvh(state)#

This function will rebuild the BVHs used for detecting self-contacts using the input state.

When the simulated object deforms significantly, simply refitting the BVH can lead to deterioration of the BVH’s quality. In these cases, rebuilding the entire tree is necessary to achieve better querying efficiency.

Parameters:

state (newton.State) – The state whose particle positions (State.particle_q) will be used for rebuilding the BVHs.

set_rigid_history_update(update)#

Set whether the next step() should update rigid solver history (warmstarts).

This setting applies only to the next call to step() and is then reset to True. This is useful for substepping, where history update frequency might differ from the simulation step frequency (e.g. updating only on the first substep).

Parameters:

update (bool) – If True, update rigid warmstart state. If False, reuse previous.

step(state_in, state_out, control, contacts, dt)#

Execute one simulation timestep using VBD (particles) and AVBD (rigid bodies).

The solver follows a 3-phase structure: 1. Initialize: Forward integrate particles and rigid bodies, detect collisions, warmstart penalties 2. Iterate: Interleave particle VBD iterations and rigid body AVBD iterations 3. Finalize: Update velocities and persistent state (Dahl friction)

To control rigid substepping behavior (warmstart history), call set_rigid_history_update() before calling this method. It defaults to True and is reset to True after each call.

Parameters:
  • state_in (State) – Input state.

  • state_out (State) – Output state.

  • control (Control) – Control inputs.

  • contacts (Contacts | None) – Contact data produced by Model.collide() (rigid-rigid and rigid-particle contacts). If None, rigid contact handling is skipped. Note that particle self-contact (if enabled) does not depend on this argument.

  • dt (float) – Time step size.