newton.ModelBuilder#

class newton.ModelBuilder(up_axis=Axis.Z, gravity=-9.81)#

A helper class for building simulation models at runtime.

Use the ModelBuilder to construct a simulation scene. The ModelBuilder and builds the scene representation using standard Python data structures (lists), this means it is not differentiable. Once finalize() has been called the ModelBuilder transfers all data to Warp tensors and returns an object that may be used for simulation.

Example

import newton
from newton.solvers import XPBDSolver

builder = newton.ModelBuilder()

# anchor point (zero mass)
builder.add_particle((0, 1.0, 0.0), (0.0, 0.0, 0.0), 0.0)

# build chain
for i in range(1, 10):
    builder.add_particle((i, 1.0, 0.0), (0.0, 0.0, 0.0), 1.0)
    builder.add_spring(i - 1, i, 1.0e3, 0.0, 0)

# create model
model = builder.finalize()

state_0, state_1 = model.state(), model.state()
control = model.control()
contact = model.contact()
solver = XPBDSolver(model)

for i in range(10):
    state_0.clear_forces()
    solver.step(model, state_0, state_1, control, contact, dt=1.0 / 60.0)
    state_0, state_1 = state_1, state_0

Note

It is strongly recommended to use the ModelBuilder to construct a simulation rather than creating your own Model object directly, however it is possible to do so if desired.

Methods

__init__([up_axis, gravity])

add_body([xform, armature, com, I_m, mass, key])

Adds a rigid body to the model.

add_builder(builder[, xform, ...])

Copies the data from builder, another ModelBuilder to this ModelBuilder.

add_cloth_grid(pos, rot, vel, dim_x, dim_y, ...)

Helper to create a regular planar cloth grid

add_cloth_mesh(pos, rot, scale, vel, ...[, ...])

Helper to create a cloth model from a regular triangle mesh

add_edge(i, j, k, l[, rest, edge_ke, edge_kd])

Adds a bending edge element between four particles in the system.

add_edges(i, j, k, l[, rest, edge_ke, edge_kd])

Adds bending edge elements between groups of four particles in the system.

add_joint(joint_type, parent, child[, ...])

Generic method to add any type of joint to this ModelBuilder.

add_joint_ball(parent, child[, ...])

Adds a ball (spherical) joint to the model.

add_joint_compound(parent, child, axis_0, ...)

Adds a compound joint to the model, which has 3 degrees of freedom, one for each axis.

add_joint_d6(parent, child[, linear_axes, ...])

Adds a generic joint with custom linear and angular axes.

add_joint_distance(parent, child[, ...])

Adds a distance joint to the model.

add_joint_fixed(parent, child[, ...])

Adds a fixed (static) joint to the model.

add_joint_free(child[, parent_xform, ...])

Adds a free joint to the model.

add_joint_prismatic(parent, child[, ...])

Adds a prismatic (sliding) joint to the model.

add_joint_revolute(parent, child[, ...])

Adds a revolute (hinge) joint to the model.

add_joint_universal(parent, child, axis_0, ...)

Adds a universal joint to the model.

add_muscle(bodies, positions, f0, lm, lt, ...)

Adds a muscle-tendon activation unit.

add_particle(pos, vel, mass[, radius, flags])

Adds a single particle to the model.

add_shape(body, type[, xform, cfg, scale, ...])

Adds a generic collision shape to the model.

add_shape_box(body[, xform, hx, hy, hz, ...])

Adds a box collision shape to a body.

add_shape_capsule(body[, xform, radius, ...])

Adds a capsule collision shape to a body.

add_shape_cone(body[, xform, radius, ...])

Adds a cone collision shape to a body.

add_shape_cylinder(body[, xform, radius, ...])

Adds a cylinder collision shape to a body.

add_shape_mesh(body[, xform, mesh, scale, ...])

Adds a triangle mesh collision shape to a body.

add_shape_plane([plane, xform, width, ...])

Adds a plane collision shape to the model.

add_shape_sdf(body[, xform, sdf, cfg, key])

Adds a signed distance field (SDF) collision shape to a body.

add_shape_sphere(body[, xform, radius, cfg, key])

Adds a sphere collision shape to a body.

add_soft_grid(pos, rot, vel, dim_x, dim_y, ...)

Helper to create a rectangular tetrahedral FEM grid

add_soft_mesh(pos, rot, scale, vel, ...[, ...])

Helper to create a tetrahedral model from an input tetrahedral mesh

add_spring(i, j, ke, kd, control)

Adds a spring between two particles in the system

add_tetrahedron(i, j, k, l[, k_mu, ...])

Adds a tetrahedral FEM element between four particles in the system.

add_triangle(i, j, k[, tri_ke, tri_ka, ...])

Adds a triangular FEM element between three particles in the system.

add_triangles(i, j, k[, tri_ke, tri_ka, ...])

Adds triangular FEM elements between groups of three particles in the system.

collapse_fixed_joints([verbose])

Removes fixed joints from the model and merges the bodies they connect.

color([include_bending, balance_colors, ...])

Runs coloring algorithm to generate coloring information.

finalize([device, requires_grad])

Convert this builder object to a concrete model for simulation.

plot_articulation([show_body_keys, ...])

Visualizes the model's articulation graph using matplotlib and networkx.

set_coloring(particle_color_groups)

Sets coloring information with user-provided coloring.

set_ground_plane([normal, offset, cfg])

Creates a ground plane for the world.

Attributes

up_vector

Computes the 3D up vector from up_axis.

class ShapeConfig(density=1000.0, ke=100000.0, kd=1000.0, kf=1000.0, ka=0.0, mu=0.5, restitution=0.0, thickness=1e-05, is_solid=True, collision_group=-1, collision_filter_parent=True, has_ground_collision=True, has_shape_collision=True, has_particle_collision=True, is_visible=True)#

Represents the properties of a collision shape used in simulation.

density: float = 1000.0#

The density of the shape material.

ke: float = 100000.0#

The contact elastic stiffness.

kd: float = 1000.0#

The contact damping stiffness.

kf: float = 1000.0#

The contact friction stiffness.

ka: float = 0.0#

The contact adhesion distance.

mu: float = 0.5#

The coefficient of friction.

restitution: float = 0.0#

The coefficient of restitution.

thickness: float = 1e-05#

The thickness of the shape.

is_solid: bool = True#

Indicates whether the shape is solid or hollow. Defaults to True.

collision_group: int = -1#

The collision group ID for the shape. Defaults to -1.

collision_filter_parent: bool = True#

Whether to inherit collision filtering from the parent. Defaults to True.

has_ground_collision: bool = True#

Whether the shape can collide with the ground. Defaults to True.

has_shape_collision: bool = True#

Whether the shape can collide with other shapes. Defaults to True.

has_particle_collision: bool = True#

Whether the shape can collide with particles. Defaults to True.

is_visible: bool = True#

Indicates whether the shape is visible in the simulation. Defaults to True.

property flags: int#

Returns the flags for the shape.

__init__(density=1000.0, ke=100000.0, kd=1000.0, kf=1000.0, ka=0.0, mu=0.5, restitution=0.0, thickness=1e-05, is_solid=True, collision_group=-1, collision_filter_parent=True, has_ground_collision=True, has_shape_collision=True, has_particle_collision=True, is_visible=True)#
class JointDofConfig(axis=Axis.X, limit_lower=-1e6, limit_upper=1e6, limit_ke=1e4, limit_kd=1e1, target=0.0, target_ke=0.0, target_kd=0.0, mode=JOINT_MODE_TARGET_POSITION, armature=1e-2)#

Describes a joint axis (a single degree of freedom) that can have limits and be driven towards a target.

__init__(axis=Axis.X, limit_lower=-1e6, limit_upper=1e6, limit_ke=1e4, limit_kd=1e1, target=0.0, target_ke=0.0, target_kd=0.0, mode=JOINT_MODE_TARGET_POSITION, armature=1e-2)#
axis#

The 3D axis that this JointDofConfig object describes.

limit_lower#

The lower position limit of the joint axis. Defaults to -1e6.

limit_upper#

The upper position limit of the joint axis. Defaults to 1e6.

limit_ke#

The elastic stiffness of the joint axis limits. Defaults to 1e4.

limit_kd#

The damping stiffness of the joint axis limits. Defaults to 1e1.

target_ke#

The proportional gain of the target drive PD controller. Defaults to 0.0.

target_kd#

The derivative gain of the target drive PD controller. Defaults to 0.0.

mode#

The mode of the joint axis (e.g., JOINT_MODE_TARGET_POSITION or JOINT_MODE_TARGET_VELOCITY). Defaults to JOINT_MODE_TARGET_POSITION.

armature#

Artificial inertia added around the joint axis. Defaults to 1e-2.

target#

The target position or velocity (depending on the mode) of the joint axis. If mode is JOINT_MODE_TARGET_POSITION and the initial target is outside the limits, it defaults to the midpoint of limit_lower and limit_upper. Otherwise, defaults to 0.0.

__init__(up_axis=Axis.Z, gravity=-9.81)#
property up_vector: list[float] | tuple[float, float, float] | vec3f#

Computes the 3D up vector from up_axis.

add_builder(builder, xform=None, update_num_env_count=True, separate_collision_group=True)#

Copies the data from builder, another ModelBuilder to this ModelBuilder.

Parameters:
  • builder (ModelBuilder) – a model builder to add model data from.

  • xform (Transform) – offset transform applied to root bodies.

  • update_num_env_count (bool) – if True, the number of environments is incremented by 1.

  • separate_collision_group (bool) – if True, the shapes from the articulations in builder will all be put into a single new collision group, otherwise, only the shapes in collision group > -1 will be moved to a new group.

add_body(xform=None, armature=None, com=None, I_m=None, mass=0.0, key=None)#

Adds a rigid body to the model.

Parameters:
  • xform (tuple[list[float] | tuple[float, float, float] | vec3f, list[float] | tuple[float, float, float, float] | quatf] | transformf | None) – The location of the body in the world frame.

  • armature (float | None) – Artificial inertia added to the body. If None, the default value from default_body_armature is used.

  • com (list[float] | tuple[float, float, float] | vec3f | None) – The center of mass of the body w.r.t its origin. If None, the center of mass is assumed to be at the origin.

  • I_m (list[float] | mat33f | None) – The 3x3 inertia tensor of the body (specified relative to the center of mass). If None, the inertia tensor is assumed to be zero.

  • mass (float) – Mass of the body.

  • key (str | None) – Key of the body (optional).

Returns:

The index of the body in the model.

Return type:

int

Note

If the mass is zero then the body is treated as kinematic with no dynamics.

add_joint(joint_type, parent, child, linear_axes=None, angular_axes=None, key=None, parent_xform=None, child_xform=None, collision_filter_parent=True, enabled=True)#

Generic method to add any type of joint to this ModelBuilder.

Parameters:
  • joint_type (constant) – The type of joint to add (see :ref:’joint-types’).

  • parent (int) – The index of the parent body (-1 is the world).

  • child (int) – The index of the child body.

  • linear_axes (list(JointDofConfig)) – The linear axes (see JointDofConfig) of the joint.

  • angular_axes (list(JointDofConfig)) – The angular axes (see JointDofConfig) of the joint.

  • key (str) – The key of the joint (optional).

  • parent_xform (Transform) – The transform of the joint in the parent body’s local frame. If None, the identity transform is used.

  • child_xform (Transform) – The transform of the joint in the child body’s local frame. If None, the identity transform is used.

  • collision_filter_parent (bool) – Whether to filter collisions between shapes of the parent and child bodies.

  • enabled (bool) – Whether the joint is enabled (not considered by FeatherstoneSolver).

Returns:

The index of the added joint.

Return type:

int

add_joint_revolute(parent, child, parent_xform=None, child_xform=None, axis=None, target=None, target_ke=None, target_kd=None, mode=None, limit_lower=None, limit_upper=None, limit_ke=None, limit_kd=None, armature=None, key=None, collision_filter_parent=True, enabled=True)#

Adds a revolute (hinge) joint to the model. It has one degree of freedom.

Parameters:
  • parent (int) – The index of the parent body.

  • child (int) – The index of the child body.

  • parent_xform (Transform) – The transform of the joint in the parent body’s local frame.

  • child_xform (Transform) – The transform of the joint in the child body’s local frame.

  • axis (AxisType | Vec3 | JointDofConfig) – The axis of rotation in the parent body’s local frame, can be a JointDofConfig object whose settings will be used instead of the other arguments.

  • target (float | None) – The target angle (in radians) or target velocity of the joint.

  • target_ke (float | None) – The stiffness of the joint target.

  • target_kd (float | None) – The damping of the joint target.

  • mode (int | None) – The control mode of the joint. If None, the default value from default_joint_control_mode is used.

  • limit_lower (float | None) – The lower limit of the joint. If None, the default value from default_joint_limit_lower is used.

  • limit_upper (float | None) – The upper limit of the joint. If None, the default value from default_joint_limit_upper is used.

  • limit_ke (float | None) – The stiffness of the joint limit. If None, the default value from default_joint_limit_ke is used.

  • limit_kd (float | None) – The damping of the joint limit. If None, the default value from default_joint_limit_kd is used.

  • armature (float | None) – Artificial inertia added around the joint axis. If None, the default value from default_joint_armature is used.

  • key (str | None) – The key of the joint.

  • collision_filter_parent (bool) – Whether to filter collisions between shapes of the parent and child bodies.

  • enabled (bool) – Whether the joint is enabled.

Returns:

The index of the added joint.

Return type:

int

add_joint_prismatic(parent, child, parent_xform=None, child_xform=None, axis=Axis.X, target=None, target_ke=None, target_kd=None, mode=None, limit_lower=None, limit_upper=None, limit_ke=None, limit_kd=None, armature=None, key=None, collision_filter_parent=True, enabled=True)#

Adds a prismatic (sliding) joint to the model. It has one degree of freedom.

Parameters:
  • parent (int) – The index of the parent body.

  • child (int) – The index of the child body.

  • parent_xform (Transform) – The transform of the joint in the parent body’s local frame.

  • child_xform (Transform) – The transform of the joint in the child body’s local frame.

  • axis (AxisType | Vec3 | JointAxis) – The axis of rotation in the parent body’s local frame, can be a JointAxis object whose settings will be used instead of the other arguments.

  • target (float | None) – The target angle (in radians) or target velocity of the joint.

  • target_ke (float | None) – The stiffness of the joint target.

  • target_kd (float | None) – The damping of the joint target.

  • mode (int | None) – The control mode of the joint. If None, the default value from default_joint_control_mode is used.

  • limit_lower (float | None) – The lower limit of the joint. If None, the default value from default_joint_limit_lower is used.

  • limit_upper (float | None) – The upper limit of the joint. If None, the default value from default_joint_limit_upper is used.

  • limit_ke (float | None) – The stiffness of the joint limit. If None, the default value from default_joint_limit_ke is used.

  • limit_kd (float | None) – The damping of the joint limit. If None, the default value from default_joint_limit_kd is used.

  • armature (float | None) – Artificial inertia added around the joint axis. If None, the default value from default_joint_armature is used.

  • key (str | None) – The key of the joint.

  • collision_filter_parent (bool) – Whether to filter collisions between shapes of the parent and child bodies.

  • enabled (bool) – Whether the joint is enabled.

Returns:

The index of the added joint.

Return type:

int

add_joint_ball(parent, child, parent_xform=None, child_xform=None, key=None, collision_filter_parent=True, enabled=True)#

Adds a ball (spherical) joint to the model. Its position is defined by a 4D quaternion (xyzw) and its velocity is a 3D vector.

Parameters:
  • parent (int) – The index of the parent body.

  • child (int) – The index of the child body.

  • parent_xform (Transform) – The transform of the joint in the parent body’s local frame.

  • child_xform (Transform) – The transform of the joint in the child body’s local frame.

  • key (str | None) – The key of the joint.

  • collision_filter_parent (bool) – Whether to filter collisions between shapes of the parent and child bodies.

  • enabled (bool) – Whether the joint is enabled.

Returns:

The index of the added joint.

Return type:

int

add_joint_fixed(parent, child, parent_xform=None, child_xform=None, key=None, collision_filter_parent=True, enabled=True)#

Adds a fixed (static) joint to the model. It has no degrees of freedom. See collapse_fixed_joints() for a helper function that removes these fixed joints and merges the connecting bodies to simplify the model and improve stability.

Parameters:
  • parent (int) – The index of the parent body.

  • child (int) – The index of the child body.

  • parent_xform (Transform) – The transform of the joint in the parent body’s local frame.

  • child_xform (Transform) – The transform of the joint in the child body’s local frame.

  • key (str | None) – The key of the joint.

  • collision_filter_parent (bool) – Whether to filter collisions between shapes of the parent and child bodies.

  • enabled (bool) – Whether the joint is enabled.

Returns:

The index of the added joint

Return type:

int

add_joint_free(child, parent_xform=None, child_xform=None, parent=-1, key=None, collision_filter_parent=True, enabled=True)#

Adds a free joint to the model. It has 7 positional degrees of freedom (first 3 linear and then 4 angular dimensions for the orientation quaternion in xyzw notation) and 6 velocity degrees of freedom (see Twist conventions in Newton). The positional dofs are initialized by the child body’s transform (see body_q and the xform argument to add_body()).

Parameters:
  • child (int) – The index of the child body.

  • parent_xform (Transform) – The transform of the joint in the parent body’s local frame.

  • child_xform (Transform) – The transform of the joint in the child body’s local frame.

  • parent (int) – The index of the parent body (-1 by default to use the world frame, e.g. to make the child body and its children a floating-base mechanism).

  • key (str | None) – The key of the joint.

  • collision_filter_parent (bool) – Whether to filter collisions between shapes of the parent and child bodies.

  • enabled (bool) – Whether the joint is enabled.

Returns:

The index of the added joint.

Return type:

int

add_joint_distance(parent, child, parent_xform=None, child_xform=None, min_distance=-1.0, max_distance=1.0, collision_filter_parent=True, enabled=True)#

Adds a distance joint to the model. The distance joint constraints the distance between the joint anchor points on the two bodies (see Forward / Inverse Kinematics) it connects to the interval [min_distance, max_distance]. It has 7 positional degrees of freedom (first 3 linear and then 4 angular dimensions for the orientation quaternion in xyzw notation) and 6 velocity degrees of freedom (first 3 angular and then 3 linear velocity dimensions).

Parameters:
  • parent (int) – The index of the parent body.

  • child (int) – The index of the child body.

  • parent_xform (Transform) – The transform of the joint in the parent body’s local frame.

  • child_xform (Transform) – The transform of the joint in the child body’s local frame.

  • min_distance (float) – The minimum distance between the bodies (no limit if negative).

  • max_distance (float) – The maximum distance between the bodies (no limit if negative).

  • collision_filter_parent (bool) – Whether to filter collisions between shapes of the parent and child bodies.

  • enabled (bool) – Whether the joint is enabled.

Returns:

The index of the added joint.

Return type:

int

Note

Distance joints are currently only supported in the newton.solvers.XPBDSolver.

add_joint_universal(parent, child, axis_0, axis_1, axis_2, parent_xform=None, child_xform=None, key=None, collision_filter_parent=True, enabled=True)#

Adds a universal joint to the model. U-joints have two degrees of freedom, one for each axis.

Parameters:
  • parent (int) – The index of the parent body.

  • child (int) – The index of the child body.

  • axis_0 (JointDofConfig) – The first axis of the joint, can be a JointDofConfig object whose settings will be used instead of the other arguments.

  • axis_1 (JointDofConfig) – The second axis of the joint, can be a JointDofConfig object whose settings will be used instead of the other arguments.

  • axis_2 (JointDofConfig) – The third axis of the joint, can be a JointDofConfig object whose settings will be used instead of the other arguments.

  • parent_xform (Transform) – The transform of the joint in the parent body’s local frame.

  • child_xform (Transform) – The transform of the joint in the child body’s local frame.

  • key (str | None) – The key of the joint.

  • collision_filter_parent (bool) – Whether to filter collisions between shapes of the parent and child bodies.

  • enabled (bool) – Whether the joint is enabled.

Returns:

The index of the added joint.

Return type:

int

Note

This joint type will be deprecated in favor of the add_joint_d6() method.

add_joint_compound(parent, child, axis_0, axis_1, axis_2, parent_xform=None, child_xform=None, key=None, collision_filter_parent=True, enabled=True)#

Adds a compound joint to the model, which has 3 degrees of freedom, one for each axis. Similar to the ball joint (see add_ball_joint()), the compound joint allows bodies to move in a 3D rotation relative to each other, except that the rotation is defined by 3 axes instead of a quaternion. Depending on the choice of axes, the orientation can be specified through Euler angles, e.g. z-x-z or x-y-x, or through a Tait-Bryan angle sequence, e.g. z-y-x or x-y-z.

Parameters:
  • parent (int) – The index of the parent body.

  • child (int) – The index of the child body.

  • axis_0 (3D vector or JointAxis) – The first axis of the joint, can be a JointAxis object whose settings will be used instead of the other arguments.

  • axis_1 (3D vector or JointAxis) – The second axis of the joint, can be a JointAxis object whose settings will be used instead of the other arguments.

  • axis_2 (3D vector or JointAxis) – The third axis of the joint, can be a JointAxis object whose settings will be used instead of the other arguments.

  • parent_xform (Transform) – The transform of the joint in the parent body’s local frame.

  • child_xform (Transform) – The transform of the joint in the child body’s local frame.

  • armature – Artificial inertia added around the joint axes.

  • key (str | None) – The key of the joint.

  • collision_filter_parent (bool) – Whether to filter collisions between shapes of the parent and child bodies.

  • enabled (bool) – Whether the joint is enabled.

Returns:

The index of the added joint.

Return type:

int

Note

This joint type will be deprecated in favor of the add_joint_d6() method.

add_joint_d6(parent, child, linear_axes=None, angular_axes=None, key=None, parent_xform=None, child_xform=None, collision_filter_parent=True, enabled=True)#

Adds a generic joint with custom linear and angular axes. The number of axes determines the number of degrees of freedom of the joint.

Parameters:
  • parent (int) – The index of the parent body.

  • child (int) – The index of the child body.

  • linear_axes (Sequence[JointDofConfig] | None) – A list of linear axes.

  • angular_axes (Sequence[JointDofConfig] | None) – A list of angular axes.

  • key (str | None) – The key of the joint.

  • parent_xform (Transform) – The transform of the joint in the parent body’s local frame

  • child_xform (Transform) – The transform of the joint in the child body’s local frame

  • armature – Artificial inertia added around the joint axes. If None, the default value from default_joint_armature is used.

  • collision_filter_parent (bool) – Whether to filter collisions between shapes of the parent and child bodies.

  • enabled (bool) – Whether the joint is enabled.

Returns:

The index of the added joint.

Return type:

int

plot_articulation(show_body_keys=True, show_joint_keys=True, show_joint_types=True, plot_shapes=True, show_shape_types=True, show_legend=True)#

Visualizes the model’s articulation graph using matplotlib and networkx. Uses the spring layout algorithm from networkx to arrange the nodes. Bodies are shown as orange squares, shapes are shown as blue circles.

Parameters:
  • show_body_keys (bool) – Whether to show the body keys or indices

  • show_joint_keys (bool) – Whether to show the joint keys or indices

  • show_joint_types (bool) – Whether to show the joint types

  • plot_shapes (bool) – Whether to render the shapes connected to the rigid bodies

  • show_shape_types (bool) – Whether to show the shape geometry types

  • show_legend (bool) – Whether to show a legend

collapse_fixed_joints(verbose=wp.config.verbose)#

Removes fixed joints from the model and merges the bodies they connect. This is useful for simplifying the model for faster and more stable simulation.

add_muscle(bodies, positions, f0, lm, lt, lmax, pen)#

Adds a muscle-tendon activation unit.

Parameters:
  • bodies (list[int]) – A list of body indices for each waypoint

  • positions (list[list[float] | tuple[float, float, float] | vec3f]) – A list of positions of each waypoint in the body’s local frame

  • f0 (float) – Force scaling

  • lm (float) – Muscle length

  • lt (float) – Tendon length

  • lmax (float) – Maximally efficient muscle length

Returns:

The index of the muscle in the model

Return type:

float

Note

The simulation support for muscles is in progress and not yet fully functional.

add_shape(body, type, xform=None, cfg=None, scale=None, src=None, is_static=False, key=None)#

Adds a generic collision shape to the model.

This is the base method for adding shapes; prefer using specific helpers like add_shape_sphere() where possible.

Parameters:
  • body (int) – The index of the parent body this shape belongs to. Use -1 for shapes not attached to any specific body (e.g., static environment geometry).

  • type (int) – The geometry type of the shape (e.g., GEO_BOX, GEO_SPHERE).

  • xform (Transform | None) – The transform of the shape in the parent body’s local frame. If None, the identity transform wp.transform() is used. Defaults to None.

  • cfg (ShapeConfig | None) – The configuration for the shape’s physical and collision properties. If None, default_shape_cfg is used. Defaults to None.

  • scale (Vec3 | None) – The scale of the geometry. The interpretation depends on the shape type. Defaults to (1.0, 1.0, 1.0) if None.

  • src (SDF | Mesh | Any | None) – The source geometry data, e.g., a Mesh object for GEO_MESH or an SDF object for GEO_SDF. Defaults to None.

  • is_static (bool) – If True, the shape will have zero mass, and its density property in cfg will be effectively ignored for mass calculation. Typically used for fixed, non-movable collision geometry. Defaults to False.

  • key (str | None) – An optional unique key for identifying the shape. If None, a default key is automatically generated (e.g., “shape_N”). Defaults to None.

Returns:

The index of the newly added shape.

Return type:

int

add_shape_plane(plane=(0.0, 1.0, 0.0, 0.0), xform=None, width=10.0, length=10.0, body=-1, cfg=None, key=None)#

Adds a plane collision shape to the model.

If xform is provided, it directly defines the plane’s position and orientation. The plane’s collision normal is assumed to be along the local Y-axis of this xform. If xform is None, it will be derived from the plane equation a*x + b*y + c*z + d = 0. Plane shapes added via this method are always static (massless).

Parameters:
  • plane (Vec4 | None) – The plane equation (a, b, c, d). If xform is None, this defines the plane. The normal is (a,b,c) and d is the offset. Defaults to (0.0, 1.0, 0.0, 0.0) (an XZ ground plane at Y=0) if xform is also None.

  • xform (Transform | None) – The transform of the plane in the world or parent body’s frame. If None, transform is derived from plane. Defaults to None.

  • width (float) – The visual/collision extent of the plane along its local X-axis. If 0.0, considered infinite for collision. Defaults to 10.0.

  • length (float) – The visual/collision extent of the plane along its local Z-axis. If 0.0, considered infinite for collision. Defaults to 10.0.

  • body (int) – The index of the parent body this shape belongs to. Use -1 for world-static planes. Defaults to -1.

  • cfg (ShapeConfig | None) – The configuration for the shape’s physical and collision properties. If None, default_shape_cfg is used. Defaults to None.

  • key (str | None) – An optional unique key for identifying the shape. If None, a default key is automatically generated. Defaults to None.

Returns:

The index of the newly added shape.

Return type:

int

add_shape_sphere(body, xform=None, radius=1.0, cfg=None, key=None)#

Adds a sphere collision shape to a body.

Parameters:
  • body (int) – The index of the parent body this shape belongs to. Use -1 for shapes not attached to any specific body.

  • xform (Transform | None) – The transform of the sphere in the parent body’s local frame. The sphere is centered at this transform’s position. If None, the identity transform wp.transform() is used. Defaults to None.

  • radius (float) – The radius of the sphere. Defaults to 1.0.

  • cfg (ShapeConfig | None) – The configuration for the shape’s physical and collision properties. If None, default_shape_cfg is used. Defaults to None.

  • key (str | None) – An optional unique key for identifying the shape. If None, a default key is automatically generated. Defaults to None.

Returns:

The index of the newly added shape.

Return type:

int

add_shape_box(body, xform=None, hx=0.5, hy=0.5, hz=0.5, cfg=None, key=None)#

Adds a box collision shape to a body.

The box is centered at its local origin as defined by xform.

Parameters:
  • body (int) – The index of the parent body this shape belongs to. Use -1 for shapes not attached to any specific body.

  • xform (Transform | None) – The transform of the box in the parent body’s local frame. If None, the identity transform wp.transform() is used. Defaults to None.

  • hx (float) – The half-extent of the box along its local X-axis. Defaults to 0.5.

  • hy (float) – The half-extent of the box along its local Y-axis. Defaults to 0.5.

  • hz (float) – The half-extent of the box along its local Z-axis. Defaults to 0.5.

  • cfg (ShapeConfig | None) – The configuration for the shape’s physical and collision properties. If None, default_shape_cfg is used. Defaults to None.

  • key (str | None) – An optional unique key for identifying the shape. If None, a default key is automatically generated. Defaults to None.

Returns:

The index of the newly added shape.

Return type:

int

add_shape_capsule(body, xform=None, radius=1.0, half_height=0.5, up_axis=Axis.Z, cfg=None, key=None)#

Adds a capsule collision shape to a body.

The capsule is centered at its local origin as defined by xform. Its length extends along the specified up_axis.

Parameters:
  • body (int) – The index of the parent body this shape belongs to. Use -1 for shapes not attached to any specific body.

  • xform (Transform | None) – The transform of the capsule in the parent body’s local frame. If None, the identity transform wp.transform() is used. Defaults to None.

  • radius (float) – The radius of the capsule’s hemispherical ends and its cylindrical segment. Defaults to 1.0.

  • half_height (float) – The half-length of the capsule’s central cylindrical segment (excluding the hemispherical ends). Defaults to 0.5.

  • up_axis (AxisType) – The local axis of the capsule along which its length is aligned (typically Axis.X, Axis.Y, or Axis.Z). Defaults to Axis.Y.

  • cfg (ShapeConfig | None) – The configuration for the shape’s physical and collision properties. If None, default_shape_cfg is used. Defaults to None.

  • key (str | None) – An optional unique key for identifying the shape. If None, a default key is automatically generated. Defaults to None.

Returns:

The index of the newly added shape.

Return type:

int

add_shape_cylinder(body, xform=None, radius=1.0, half_height=0.5, up_axis=Axis.Z, cfg=None, key=None)#

Adds a cylinder collision shape to a body.

The cylinder is centered at its local origin as defined by xform. Its length extends along the specified up_axis.

Parameters:
  • body (int) – The index of the parent body this shape belongs to. Use -1 for shapes not attached to any specific body.

  • xform (Transform | None) – The transform of the cylinder in the parent body’s local frame. If None, the identity transform wp.transform() is used. Defaults to None.

  • radius (float) – The radius of the cylinder. Defaults to 1.0.

  • half_height (float) – The half-length of the cylinder along the up_axis. Defaults to 0.5.

  • up_axis (AxisType) – The local axis of the cylinder along which its length is aligned (e.g., Axis.X, Axis.Y, Axis.Z). Defaults to Axis.Y.

  • cfg (ShapeConfig | None) – The configuration for the shape’s physical and collision properties. If None, default_shape_cfg is used. Defaults to None.

  • key (str | None) – An optional unique key for identifying the shape. If None, a default key is automatically generated. Defaults to None.

Returns:

The index of the newly added shape.

Return type:

int

add_shape_cone(body, xform=None, radius=1.0, half_height=0.5, up_axis=Axis.Z, cfg=None, key=None)#

Adds a cone collision shape to a body.

The cone’s base is centered at its local origin as defined by xform and it extends along the specified up_axis towards its apex.

Parameters:
  • body (int) – The index of the parent body this shape belongs to. Use -1 for shapes not attached to any specific body.

  • xform (Transform | None) – The transform of the cone in the parent body’s local frame. If None, the identity transform wp.transform() is used. Defaults to None.

  • radius (float) – The radius of the cone’s base. Defaults to 1.0.

  • half_height (float) – The half-height of the cone (distance from the center of the base to the apex along the up_axis). Defaults to 0.5.

  • up_axis (AxisType) – The local axis of the cone along which its height is aligned, pointing from base to apex (e.g., Axis.X, Axis.Y, Axis.Z). Defaults to Axis.Y.

  • cfg (ShapeConfig | None) – The configuration for the shape’s physical and collision properties. If None, default_shape_cfg is used. Defaults to None.

  • key (str | None) – An optional unique key for identifying the shape. If None, a default key is automatically generated. Defaults to None.

Returns:

The index of the newly added shape.

Return type:

int

add_shape_mesh(body, xform=None, mesh=None, scale=None, cfg=None, key=None)#

Adds a triangle mesh collision shape to a body.

Parameters:
  • body (int) – The index of the parent body this shape belongs to. Use -1 for shapes not attached to any specific body.

  • xform (Transform | None) – The transform of the mesh in the parent body’s local frame. If None, the identity transform wp.transform() is used. Defaults to None.

  • mesh (Mesh | None) – The Mesh object containing the vertex and triangle data. Defaults to None.

  • scale (Vec3 | None) – The scale of the mesh. Defaults to None, in which case the scale is (1.0, 1.0, 1.0).

  • cfg (ShapeConfig | None) – The configuration for the shape’s physical and collision properties. If None, default_shape_cfg is used. Defaults to None.

  • key (str | None) – An optional unique key for identifying the shape. If None, a default key is automatically generated. Defaults to None.

Returns:

The index of the newly added shape.

Return type:

int

add_shape_sdf(body, xform=None, sdf=None, cfg=None, key=None)#

Adds a signed distance field (SDF) collision shape to a body.

Parameters:
  • body (int) – The index of the parent body this shape belongs to. Use -1 for shapes not attached to any specific body.

  • xform (Transform | None) – The transform of the SDF in the parent body’s local frame. If None, the identity transform wp.transform() is used. Defaults to None.

  • sdf (SDF | None) – The SDF object representing the signed distance field. Defaults to None.

  • cfg (ShapeConfig | None) – The configuration for the shape’s physical and collision properties. If None, default_shape_cfg is used. Defaults to None.

  • key (str | None) – An optional unique key for identifying the shape. If None, a default key is automatically generated. Defaults to None.

Returns:

The index of the newly added shape.

Return type:

int

add_particle(pos, vel, mass, radius=None, flags=PARTICLE_FLAG_ACTIVE)#

Adds a single particle to the model.

Parameters:
  • pos (list[float] | tuple[float, float, float] | vec3f) – The initial position of the particle.

  • vel (list[float] | tuple[float, float, float] | vec3f) – The initial velocity of the particle.

  • mass (float) – The mass of the particle.

  • radius (float | None) – The radius of the particle used in collision handling. If None, the radius is set to the default value (default_particle_radius).

  • flags (uint32) – The flags that control the dynamical behavior of the particle, see PARTICLE_FLAG_* constants.

Note

Set the mass equal to zero to create a ‘kinematic’ particle that is not subject to dynamics.

Returns:

The index of the particle in the system.

Return type:

int

add_spring(i, j, ke, kd, control)#

Adds a spring between two particles in the system

Parameters:
  • i (int) – The index of the first particle

  • j – The index of the second particle

  • ke (float) – The elastic stiffness of the spring

  • kd (float) – The damping stiffness of the spring

  • control (float) – The actuation level of the spring

Note

The spring is created with a rest-length based on the distance between the particles in their initial configuration.

add_triangle(i, j, k, tri_ke=None, tri_ka=None, tri_kd=None, tri_drag=None, tri_lift=None)#

Adds a triangular FEM element between three particles in the system.

Triangles are modeled as viscoelastic elements with elastic stiffness and damping parameters specified on the model. See model.tri_ke, model.tri_kd.

Parameters:
  • i (int) – The index of the first particle

  • j (int) – The index of the second particle

  • k (int) – The index of the third particle

Returns:

The area of the triangle

Return type:

float

Note

The triangle is created with a rest-length based on the distance between the particles in their initial configuration.

add_triangles(i, j, k, tri_ke=None, tri_ka=None, tri_kd=None, tri_drag=None, tri_lift=None)#

Adds triangular FEM elements between groups of three particles in the system.

Triangles are modeled as viscoelastic elements with elastic stiffness and damping Parameters specified on the model. See model.tri_ke, model.tri_kd.

Parameters:
  • i (list[int]) – The indices of the first particle

  • j (list[int]) – The indices of the second particle

  • k (list[int]) – The indices of the third particle

Returns:

The areas of the triangles

Return type:

list[float]

Note

A triangle is created with a rest-length based on the distance between the particles in their initial configuration.

add_tetrahedron(i, j, k, l, k_mu=1.0e3, k_lambda=1.0e3, k_damp=0.0)#

Adds a tetrahedral FEM element between four particles in the system.

Tetrahedra are modeled as viscoelastic elements with a NeoHookean energy density based on [Smith et al. 2018].

Parameters:
  • i (int) – The index of the first particle

  • j (int) – The index of the second particle

  • k (int) – The index of the third particle

  • l (int) – The index of the fourth particle

  • k_mu (float) – The first elastic Lame parameter

  • k_lambda (float) – The second elastic Lame parameter

  • k_damp (float) – The element’s damping stiffness

Returns:

The volume of the tetrahedron

Return type:

float

Note

The tetrahedron is created with a rest-pose based on the particle’s initial configuration

add_edge(i, j, k, l, rest=None, edge_ke=None, edge_kd=None)#

Adds a bending edge element between four particles in the system.

Bending elements are designed to be between two connected triangles. Then bending energy is based of [Bridson et al. 2002]. Bending stiffness is controlled by the model.tri_kb parameter.

Parameters:
  • i (int) – The index of the first particle, i.e., opposite vertex 0

  • j (int) – The index of the second particle, i.e., opposite vertex 1

  • k (int) – The index of the third particle, i.e., vertex 0

  • l (int) – The index of the fourth particle, i.e., vertex 1

  • rest (float | None) – The rest angle across the edge in radians, if not specified it will be computed

Note

The edge lies between the particles indexed by ‘k’ and ‘l’ parameters with the opposing vertices indexed by ‘i’ and ‘j’. This defines two connected triangles with counter clockwise winding: (i, k, l), (j, l, k).

add_edges(i, j, k, l, rest=None, edge_ke=None, edge_kd=None)#

Adds bending edge elements between groups of four particles in the system.

Bending elements are designed to be between two connected triangles. Then bending energy is based of [Bridson et al. 2002]. Bending stiffness is controlled by the model.tri_kb parameter.

Parameters:
  • i – The index of the first particle, i.e., opposite vertex 0

  • j – The index of the second particle, i.e., opposite vertex 1

  • k – The index of the third particle, i.e., vertex 0

  • l – The index of the fourth particle, i.e., vertex 1

  • rest (list[float] | None) – The rest angles across the edges in radians, if not specified they will be computed

Note

The edge lies between the particles indexed by ‘k’ and ‘l’ parameters with the opposing vertices indexed by ‘i’ and ‘j’. This defines two connected triangles with counter clockwise winding: (i, k, l), (j, l, k).

add_cloth_grid(pos, rot, vel, dim_x, dim_y, cell_x, cell_y, mass, reverse_winding=False, fix_left=False, fix_right=False, fix_top=False, fix_bottom=False, tri_ke=None, tri_ka=None, tri_kd=None, tri_drag=None, tri_lift=None, edge_ke=None, edge_kd=None, add_springs=False, spring_ke=None, spring_kd=None, particle_radius=None)#

Helper to create a regular planar cloth grid

Creates a rectangular grid of particles with FEM triangles and bending elements automatically.

Parameters:
  • pos (list[float] | tuple[float, float, float] | vec3f) – The position of the cloth in world space

  • rot (list[float] | tuple[float, float, float, float] | quatf) – The orientation of the cloth in world space

  • vel (list[float] | tuple[float, float, float] | vec3f) – The velocity of the cloth in world space

  • dim_x (int) – The number of rectangular cells along the x-axis

  • dim_y (int) – The number of rectangular cells along the y-axis

  • cell_x (float) – The width of each cell in the x-direction

  • cell_y (float) – The width of each cell in the y-direction

  • mass (float) – The mass of each particle

  • reverse_winding (bool) – Flip the winding of the mesh

  • fix_left (bool) – Make the left-most edge of particles kinematic (fixed in place)

  • fix_right (bool) – Make the right-most edge of particles kinematic

  • fix_top (bool) – Make the top-most edge of particles kinematic

  • fix_bottom (bool) – Make the bottom-most edge of particles kinematic

add_cloth_mesh(pos, rot, scale, vel, vertices, indices, density, edge_callback=None, face_callback=None, tri_ke=None, tri_ka=None, tri_kd=None, tri_drag=None, tri_lift=None, edge_ke=None, edge_kd=None, add_springs=False, spring_ke=None, spring_kd=None, particle_radius=None)#

Helper to create a cloth model from a regular triangle mesh

Creates one FEM triangle element and one bending element for every face and edge in the input triangle mesh

Parameters:
  • pos (list[float] | tuple[float, float, float] | vec3f) – The position of the cloth in world space

  • rot (list[float] | tuple[float, float, float, float] | quatf) – The orientation of the cloth in world space

  • vel (list[float] | tuple[float, float, float] | vec3f) – The velocity of the cloth in world space

  • vertices (list[list[float] | tuple[float, float, float] | vec3f]) – A list of vertex positions

  • indices (list[int]) – A list of triangle indices, 3 entries per-face

  • density (float) – The density per-area of the mesh

  • edge_callback – A user callback when an edge is created

  • face_callback – A user callback when a face is created

  • particle_radius (float | None) – The particle_radius which controls particle based collisions.

Note

The mesh should be two manifold.

add_soft_grid(pos, rot, vel, dim_x, dim_y, dim_z, cell_x, cell_y, cell_z, density, k_mu, k_lambda, k_damp, fix_left=False, fix_right=False, fix_top=False, fix_bottom=False, tri_ke=None, tri_ka=None, tri_kd=None, tri_drag=None, tri_lift=None)#

Helper to create a rectangular tetrahedral FEM grid

Creates a regular grid of FEM tetrahedra and surface triangles. Useful for example to create beams and sheets. Each hexahedral cell is decomposed into 5 tetrahedral elements.

Parameters:
  • pos (list[float] | tuple[float, float, float] | vec3f) – The position of the solid in world space

  • rot (list[float] | tuple[float, float, float, float] | quatf) – The orientation of the solid in world space

  • vel (list[float] | tuple[float, float, float] | vec3f) – The velocity of the solid in world space

  • dim_x (int) – The number of rectangular cells along the x-axis

  • dim_y (int) – The number of rectangular cells along the y-axis

  • dim_z (int) – The number of rectangular cells along the z-axis

  • cell_x (float) – The width of each cell in the x-direction

  • cell_y (float) – The width of each cell in the y-direction

  • cell_z (float) – The width of each cell in the z-direction

  • density (float) – The density of each particle

  • k_mu (float) – The first elastic Lame parameter

  • k_lambda (float) – The second elastic Lame parameter

  • k_damp (float) – The damping stiffness

  • fix_left (bool) – Make the left-most edge of particles kinematic (fixed in place)

  • fix_right (bool) – Make the right-most edge of particles kinematic

  • fix_top (bool) – Make the top-most edge of particles kinematic

  • fix_bottom (bool) – Make the bottom-most edge of particles kinematic

add_soft_mesh(pos, rot, scale, vel, vertices, indices, density, k_mu, k_lambda, k_damp, tri_ke=None, tri_ka=None, tri_kd=None, tri_drag=None, tri_lift=None)#

Helper to create a tetrahedral model from an input tetrahedral mesh

Parameters:
set_ground_plane(normal=None, offset=0.0, cfg=None)#

Creates a ground plane for the world. If the normal is not specified, the up_vector of the ModelBuilder is used.

set_coloring(particle_color_groups)#

Sets coloring information with user-provided coloring.

Parameters:

particle_color_groups – A list of list or np.array with dtype`=`int. The length of the list is the number of colors and each list or np.array contains the indices of vertices with this color.

color(include_bending=False, balance_colors=True, target_max_min_color_ratio=1.1, coloring_algorithm=ColoringAlgorithm.MCS)#

Runs coloring algorithm to generate coloring information.

Parameters:
  • include_bending_energy – Whether to consider bending energy for trimeshes in the coloring process. If set to True, the generated graph will contain all the edges connecting o1 and o2; otherwise, the graph will be equivalent to the trimesh.

  • balance_colors – Whether to apply the color balancing algorithm to balance the size of each color

  • target_max_min_color_ratio – the color balancing algorithm will stop when the ratio between the largest color and the smallest color reaches this value

  • algorithm – Value should be an enum type of ColoringAlgorithm, otherwise it will raise an error. ColoringAlgorithm.mcs means using the MCS coloring algorithm, while ColoringAlgorithm.ordered_greedy means using the degree-ordered greedy algorithm. The MCS algorithm typically generates 30% to 50% fewer colors compared to the ordered greedy algorithm, while maintaining the same linear complexity. Although MCS has a constant overhead that makes it about twice as slow as the greedy algorithm, it produces significantly better coloring results. We recommend using MCS, especially if coloring is only part of the preprocessing.

Note

References to the coloring algorithm:

MCS: Pereira, F. M. Q., & Palsberg, J. (2005, November). Register allocation via coloring of chordal graphs. In Asian Symposium on Programming Languages and Systems (pp. 315-329). Berlin, Heidelberg: Springer Berlin Heidelberg.

Ordered Greedy: Ton-That, Q. M., Kry, P. G., & Andrews, S. (2023). Parallel block Neo-Hookean XPBD using graph clustering. Computers & Graphics, 110, 1-10.

finalize(device=None, requires_grad=False)#

Convert this builder object to a concrete model for simulation.

After building simulation elements this method should be called to transfer all data to device memory ready for simulation.

Parameters:
  • device (Device | str | None) – The simulation device to use, e.g.: ‘cpu’, ‘cuda’

  • requires_grad (bool) – Whether to enable gradient computation for the model

Returns:

A model object.

Return type:

Model