newton.solvers.XPBDSolver#

class newton.solvers.XPBDSolver(model, iterations=2, soft_body_relaxation=0.9, soft_contact_relaxation=0.9, joint_linear_relaxation=0.7, joint_angular_relaxation=0.4, joint_linear_compliance=0.0, joint_angular_compliance=0.0, rigid_contact_relaxation=0.8, rigid_contact_con_weighting=True, angular_damping=0.0, enable_restitution=False)#

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

After constructing Model, State, and Control (optional) objects, this time-integrator may be used to advance the simulation state forward in time.

Example

solver = newton.XPBDSolver(model)

# simulation loop
for i in range(100):
    solver.step(model, state_in, state_out, control, contacts, dt)

Methods

__init__(model[, iterations, ...])

integrate_bodies(model, state_in, state_out, dt)

Integrate the rigid bodies of the model.

integrate_particles(model, state_in, ...)

Integrate the particles of the model.

notify_model_changed(flags)

Notify the solver that parts of the Model were modified.

Attributes

device

Get the device used by the solver.

__init__(model, iterations=2, soft_body_relaxation=0.9, soft_contact_relaxation=0.9, joint_linear_relaxation=0.7, joint_angular_relaxation=0.4, joint_linear_compliance=0.0, joint_angular_compliance=0.0, rigid_contact_relaxation=0.8, rigid_contact_con_weighting=True, angular_damping=0.0, enable_restitution=False)#
step(model, state_in, state_out, control, contacts, dt)#

Simulate the model for a given time step using the given control input.

Parameters:
  • model (Model) – The model to simulate.

  • state_in (State) – The input state.

  • state_out (State) – The output state.

  • control (Control) – The control input. Defaults to None which means the control values from the Model are used.

  • contacts (Contact) – The contact information.

  • dt (float) – The time step (typically in seconds).

property device: Device#

Get the device used by the solver.

Returns:

The device used by the solver.

Return type:

wp.Device

integrate_bodies(model, state_in, state_out, dt, angular_damping=0.0)#

Integrate the rigid bodies of the model.

Parameters:
  • model (Model) – The model to integrate.

  • state_in (State) – The input state.

  • state_out (State) – The output state.

  • dt (float) – The time step (typically in seconds).

  • angular_damping (float, optional) – The angular damping factor. Defaults to 0.0.

integrate_particles(model, state_in, state_out, dt)#

Integrate the particles of the model.

Parameters:
  • model (Model) – The model to integrate.

  • state_in (State) – The input state.

  • state_out (State) – The output state.

  • dt (float) – The time step (typically in seconds).

notify_model_changed(flags)#

Notify the solver that parts of the Model were modified.

The flags argument is a bit-mask composed of the NOTIFY_FLAG_* constants defined in newton.core.types. Each flag represents a category of model data that may have been updated after the solver was created. Passing the appropriate combination of flags enables a solver implementation to refresh its internal buffers without having to recreate the whole solver object. Valid flags are:

Constant

Description

NOTIFY_FLAG_JOINT_PROPERTIES

Joint transforms or coordinates have changed.

NOTIFY_FLAG_JOINT_AXIS_PROPERTIES

Joint axis limits, targets, or modes have changed.

NOTIFY_FLAG_DOF_PROPERTIES

Joint DOF state or force buffers have changed.

NOTIFY_FLAG_BODY_PROPERTIES

Rigid-body pose or velocity buffers have changed.

NOTIFY_FLAG_BODY_INERTIAL_PROPERTIES

Rigid-body mass or inertia tensors have changed.

NOTIFY_FLAG_SHAPE_PROPERTIES

Shape transforms or geometry have changed.

Parameters:

flags (int) – Bit-mask of model-update flags indicating which model properties changed.