newton.solvers.SolverBase#
- class newton.solvers.SolverBase(model)#
Generic base class for solvers.
The implementation provides helper kernels to integrate rigid bodies and particles. Concrete solver back-ends should derive from this class and override
step()
as well asnotify_model_changed()
where necessary.Methods
__init__
(model)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.step
(model, state_in, state_out, control, ...)Simulate the model for a given time step using the given control input.
Attributes
Get the device used by the solver.
- __init__(model)#
- 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.
- integrate_particles(model, state_in, state_out, dt)#
Integrate the particles of the model.
- 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).
- 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 innewton.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.