warp.sim#

Warp includes a simulation module warp.sim that includes many common physical simulation models and integrators for explicit and implicit time-stepping.

Model#

class warp.sim.ModelBuilder(up_vector=(0.0, 1.0, 0.0), gravity=-9.80665)[source]#

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 warp as wp
import warp.sim

builder = wp.sim.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("cuda")

state = model.state()
control = model.control()  # optional, to support time-varying control inputs
integrator = wp.sim.SemiImplicitIntegrator()

for i in range(100):
    state.clear_forces()
    integrator.simulate(model, state, state, dt=1.0 / 60.0, control=control)

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.

default_particle_radius = 0.1#
default_tri_ke = 100.0#
default_tri_ka = 100.0#
default_tri_kd = 10.0#
default_tri_drag = 0.0#
default_tri_lift = 0.0#
default_spring_ke = 100.0#
default_spring_kd = 0.0#
default_edge_ke = 100.0#
default_edge_kd = 0.0#
default_shape_ke = 100000.0#
default_shape_kd = 1000.0#
default_shape_kf = 1000.0#
default_shape_ka = 0.0#
default_shape_mu = 0.5#
default_shape_restitution = 0.0#
default_shape_density = 1000.0#
default_shape_thickness = 1e-05#
default_joint_limit_ke = 100.0#
default_joint_limit_kd = 1.0#
__init__(up_vector=(0.0, 1.0, 0.0), gravity=-9.80665)[source]#
property shape_count[source]#
property body_count[source]#
property joint_count[source]#
property joint_axis_count[source]#
property particle_count[source]#
property tri_count[source]#
property tet_count[source]#
property edge_count[source]#
property spring_count[source]#
property muscle_count[source]#
property articulation_count[source]#
add_articulation()[source]#
add_builder(
builder,
xform=None,
update_num_env_count=True,
separate_collision_group=True,
)[source]#

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(
origin=None,
armature=0.0,
com=None,
I_m=None,
m=0.0,
name=None,
)[source]#

Adds a rigid body to the model.

Parameters:
  • origin (Tuple[List[float], List[float]] | None) – The location of the body in the world frame

  • armature (float) – Artificial inertia added to the body

  • com (List[float] | None) – The center of mass of the body w.r.t its origin

  • I_m (List[float] | None) – The 3x3 inertia tensor of the body (specified relative to the center of mass)

  • m (float) – Mass of the body

  • name (str | None) – Name of the body (optional)

Returns:

The index of the body in the model

Return type:

int

Note

If the mass (m) is zero then the body is treated as kinematic with no dynamics

add_joint(
joint_type,
parent,
child,
linear_axes=None,
angular_axes=None,
name=None,
parent_xform=None,
child_xform=None,
linear_compliance=0.0,
angular_compliance=0.0,
armature=1e-2,
collision_filter_parent=True,
enabled=True,
)[source]#

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

Parameters:
  • joint_type (constant) – The type of joint to add (see 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(JointAxis)) – The linear axes (see JointAxis) of the joint

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

  • name (str) – The name of the joint (optional)

  • 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

  • linear_compliance (float) – The linear compliance of the joint

  • angular_compliance (float) – The angular compliance of the joint

  • armature (float) – Artificial inertia added around the joint axes (only considered by FeatherstoneIntegrator)

  • 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 FeatherstoneIntegrator)

Returns:

The index of the added joint

Return type:

int

add_joint_revolute(
parent,
child,
parent_xform=None,
child_xform=None,
axis=(1.0, 0.0, 0.0),
target=None,
target_ke=0.0,
target_kd=0.0,
mode=JOINT_MODE_FORCE,
limit_lower=-2 * math.pi,
limit_upper=2 * math.pi,
limit_ke=default_joint_limit_ke,
limit_kd=default_joint_limit_kd,
linear_compliance=0.0,
angular_compliance=0.0,
armature=1e-2,
name=None,
collision_filter_parent=True,
enabled=True,
)[source]#

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 (3D vector or 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 (if None, the joint is considered to be in force control mode)

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

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

  • limit_lower (float) – The lower limit of the joint

  • limit_upper (float) – The upper limit of the joint

  • limit_ke (float) – The stiffness of the joint limit

  • limit_kd (float) – The damping of the joint limit

  • linear_compliance (float) – The linear compliance of the joint

  • angular_compliance (float) – The angular compliance of the joint

  • armature (float) – Artificial inertia added around the joint axis

  • name (str | None) – The name 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

  • mode (int)

Returns:

The index of the added joint

Return type:

int

add_joint_prismatic(
parent,
child,
parent_xform=None,
child_xform=None,
axis=(1.0, 0.0, 0.0),
target=None,
target_ke=0.0,
target_kd=0.0,
mode=JOINT_MODE_FORCE,
limit_lower=-1e4,
limit_upper=1e4,
limit_ke=default_joint_limit_ke,
limit_kd=default_joint_limit_kd,
linear_compliance=0.0,
angular_compliance=0.0,
armature=1e-2,
name=None,
collision_filter_parent=True,
enabled=True,
)[source]#

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 (3D vector or 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 position or velocity of the joint (if None, the joint is considered to be in force control mode)

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

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

  • limit_lower (float) – The lower limit of the joint

  • limit_upper (float) – The upper limit of the joint

  • limit_ke (float) – The stiffness of the joint limit

  • limit_kd (float) – The damping of the joint limit

  • linear_compliance (float) – The linear compliance of the joint

  • angular_compliance (float) – The angular compliance of the joint

  • armature (float) – Artificial inertia added around the joint axis

  • name (str | None) – The name 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

  • mode (int)

Returns:

The index of the added joint

Return type:

int

add_joint_ball(
parent,
child,
parent_xform=None,
child_xform=None,
linear_compliance=0.0,
angular_compliance=0.0,
armature=1e-2,
name=None,
collision_filter_parent=True,
enabled=True,
)[source]#

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

  • linear_compliance (float) – The linear compliance of the joint

  • angular_compliance (float) – The angular compliance of the joint

  • armature (float) – Artificial inertia added around the joint axis (only considered by FeatherstoneIntegrator)

  • name (str | None) – The name 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,
linear_compliance=0.0,
angular_compliance=0.0,
armature=1e-2,
name=None,
collision_filter_parent=True,
enabled=True,
)[source]#

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

  • linear_compliance (float) – The linear compliance of the joint

  • angular_compliance (float) – The angular compliance of the joint

  • armature (float) – Artificial inertia added around the joint axis (only considered by FeatherstoneIntegrator)

  • name (str | None) – The name 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,
armature=0.0,
parent=-1,
name=None,
collision_filter_parent=True,
enabled=True,
)[source]#

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 (first 3 angular and then 3 linear velocity dimensions).

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

  • armature (float) – Artificial inertia added around the joint axis (only considered by FeatherstoneIntegrator)

  • 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)

  • name (str | None) – The name 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,
compliance=0.0,
collision_filter_parent=True,
enabled=True,
)[source]#

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)

  • compliance (float) – The compliance 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

Distance joints are currently only supported in the XPBDIntegrator at the moment.

add_joint_universal(
parent,
child,
axis_0,
axis_1,
parent_xform=None,
child_xform=None,
linear_compliance=0.0,
angular_compliance=0.0,
armature=1e-2,
name=None,
collision_filter_parent=True,
enabled=True,
)[source]#

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 (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

  • 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

  • linear_compliance (float) – The linear compliance of the joint

  • angular_compliance (float) – The angular compliance of the joint

  • armature (float) – Artificial inertia added around the joint axes

  • name (str | None) – The name 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_compound(
parent,
child,
axis_0,
axis_1,
axis_2,
parent_xform=None,
child_xform=None,
linear_compliance=0.0,
angular_compliance=0.0,
armature=1e-2,
name=None,
collision_filter_parent=True,
enabled=True,
)[source]#

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

  • linear_compliance (float) – The linear compliance of the joint

  • angular_compliance (float) – The angular compliance of the joint

  • armature (float) – Artificial inertia added around the joint axes

  • name (str | None) – The name 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_d6(
parent,
child,
linear_axes=None,
angular_axes=None,
name=None,
parent_xform=None,
child_xform=None,
linear_compliance=0.0,
angular_compliance=0.0,
armature=1e-2,
collision_filter_parent=True,
enabled=True,
)[source]#

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 (List[JointAxis] | None) – A list of linear axes

  • angular_axes (List[JointAxis] | None) – A list of angular axes

  • name (str | None) – The name 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

  • linear_compliance (float) – The linear compliance of the joint

  • angular_compliance (float) – The angular compliance of the joint

  • armature (float) – Artificial inertia added around the joint axes

  • 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

plot_articulation(
show_body_names=True,
show_joint_names=True,
show_joint_types=True,
plot_shapes=True,
show_shape_types=True,
show_legend=True,
)[source]#

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_names (bool) – Whether to show the body names or indices

  • show_joint_names (bool) – Whether to show the joint names 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)[source]#

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)[source]#

Adds a muscle-tendon activation unit.

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

  • positions (List[List[float]]) – 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

  • pen (float)

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_plane(
plane=(0.0, 1.0, 0.0, 0.0),
pos=None,
rot=None,
width=10.0,
length=10.0,
body=-1,
ke=None,
kd=None,
kf=None,
ka=None,
mu=None,
restitution=None,
thickness=None,
has_ground_collision=False,
has_shape_collision=True,
is_visible=True,
collision_group=-1,
)[source]#

Adds a plane collision shape. If pos and rot are defined, the plane is assumed to have its normal as (0, 1, 0). Otherwise, the plane equation defined through the plane argument is used.

Parameters:
  • plane (List[float]) – The plane equation in form a*x + b*y + c*z + d = 0

  • pos (List[float] | None) – The position of the plane in world coordinates

  • rot (List[float] | None) – The rotation of the plane in world coordinates

  • width (float) – The extent along x of the plane (infinite if 0)

  • length (float) – The extent along z of the plane (infinite if 0)

  • body (int) – The body index to attach the shape to (-1 by default to keep the plane static)

  • ke (float | None) – The contact elastic stiffness (None to use the default value default_shape_ke)

  • kd (float | None) – The contact damping stiffness (None to use the default value default_shape_kd)

  • kf (float | None) – The contact friction stiffness (None to use the default value default_shape_kf)

  • ka (float | None) – The contact adhesion distance (None to use the default value default_shape_ka)

  • mu (float | None) – The coefficient of friction (None to use the default value default_shape_mu)

  • restitution (float | None) – The coefficient of restitution (None to use the default value default_shape_restitution)

  • thickness (float | None) – The thickness of the plane (0 by default) for collision handling (None to use the default value default_shape_thickness)

  • has_ground_collision (bool) – If True, the shape will collide with the ground plane if Model.ground is True

  • has_shape_collision (bool) – If True, the shape will collide with other shapes

  • is_visible (bool) – Whether the plane is visible

  • collision_group (int) – The collision group of the shape

Returns:

The index of the added shape

add_shape_sphere(
body,
pos=(0.0, 0.0, 0.0),
rot=(0.0, 0.0, 0.0, 1.0),
radius=1.0,
density=None,
ke=None,
kd=None,
kf=None,
ka=None,
mu=None,
restitution=None,
is_solid=True,
thickness=None,
has_ground_collision=True,
has_shape_collision=True,
collision_group=-1,
is_visible=True,
)[source]#

Adds a sphere collision shape to a body.

Parameters:
  • body – The index of the parent body this shape belongs to (use -1 for static shapes)

  • pos (List[float]) – The location of the shape with respect to the parent frame

  • rot (List[float]) – The rotation of the shape with respect to the parent frame

  • radius (float) – The radius of the sphere

  • density (float | None) – The density of the shape (None to use the default value default_shape_density)

  • ke (float | None) – The contact elastic stiffness (None to use the default value default_shape_ke)

  • kd (float | None) – The contact damping stiffness (None to use the default value default_shape_kd)

  • kf (float | None) – The contact friction stiffness (None to use the default value default_shape_kf)

  • ka (float | None) – The contact adhesion distance (None to use the default value default_shape_ka)

  • mu (float | None) – The coefficient of friction (None to use the default value default_shape_mu)

  • restitution (float | None) – The coefficient of restitution (None to use the default value default_shape_restitution)

  • is_solid (bool) – Whether the sphere is solid or hollow

  • thickness (float | None) – Thickness to use for computing inertia of a hollow sphere, and for collision handling (None to use the default value default_shape_thickness)

  • has_ground_collision (bool) – If True, the shape will collide with the ground plane if Model.ground is True

  • has_shape_collision (bool) – If True, the shape will collide with other shapes

  • collision_group (int) – The collision group of the shape

  • is_visible (bool) – Whether the sphere is visible

Returns:

The index of the added shape

add_shape_box(
body,
pos=(0.0, 0.0, 0.0),
rot=(0.0, 0.0, 0.0, 1.0),
hx=0.5,
hy=0.5,
hz=0.5,
density=None,
ke=None,
kd=None,
kf=None,
ka=None,
mu=None,
restitution=None,
is_solid=True,
thickness=None,
has_ground_collision=True,
has_shape_collision=True,
collision_group=-1,
is_visible=True,
)[source]#

Adds a box collision shape to a body.

Parameters:
  • body (int) – The index of the parent body this shape belongs to (use -1 for static shapes)

  • pos (List[float]) – The location of the shape with respect to the parent frame

  • rot (List[float]) – The rotation of the shape with respect to the parent frame

  • hx (float) – The half-extent along the x-axis

  • hy (float) – The half-extent along the y-axis

  • hz (float) – The half-extent along the z-axis

  • density (float | None) – The density of the shape (None to use the default value default_shape_density)

  • ke (float | None) – The contact elastic stiffness (None to use the default value default_shape_ke)

  • kd (float | None) – The contact damping stiffness (None to use the default value default_shape_kd)

  • kf (float | None) – The contact friction stiffness (None to use the default value default_shape_kf)

  • ka (float | None) – The contact adhesion distance (None to use the default value default_shape_ka)

  • mu (float | None) – The coefficient of friction (None to use the default value default_shape_mu)

  • restitution (float | None) – The coefficient of restitution (None to use the default value default_shape_restitution)

  • is_solid (bool) – Whether the box is solid or hollow

  • thickness (float | None) – Thickness to use for computing inertia of a hollow box, and for collision handling (None to use the default value default_shape_thickness)

  • has_ground_collision (bool) – If True, the shape will collide with the ground plane if Model.ground is True

  • has_shape_collision (bool) – If True, the shape will collide with other shapes

  • collision_group (int) – The collision group of the shape

  • is_visible (bool) – Whether the box is visible

Returns:

The index of the added shape

add_shape_capsule(
body,
pos=(0.0, 0.0, 0.0),
rot=(0.0, 0.0, 0.0, 1.0),
radius=1.0,
half_height=0.5,
up_axis=1,
density=None,
ke=None,
kd=None,
kf=None,
ka=None,
mu=None,
restitution=None,
is_solid=True,
thickness=None,
has_ground_collision=True,
has_shape_collision=True,
collision_group=-1,
is_visible=True,
)[source]#

Adds a capsule collision shape to a body.

Parameters:
  • body (int) – The index of the parent body this shape belongs to (use -1 for static shapes)

  • pos (List[float]) – The location of the shape with respect to the parent frame

  • rot (List[float]) – The rotation of the shape with respect to the parent frame

  • radius (float) – The radius of the capsule

  • half_height (float) – The half length of the center cylinder along the up axis

  • up_axis (int) – The axis along which the capsule is aligned (0=x, 1=y, 2=z)

  • density (float | None) – The density of the shape (None to use the default value default_shape_density)

  • ke (float | None) – The contact elastic stiffness (None to use the default value default_shape_ke)

  • kd (float | None) – The contact damping stiffness (None to use the default value default_shape_kd)

  • kf (float | None) – The contact friction stiffness (None to use the default value default_shape_kf)

  • ka (float | None) – The contact adhesion distance (None to use the default value default_shape_ka)

  • mu (float | None) – The coefficient of friction (None to use the default value default_shape_mu)

  • restitution (float | None) – The coefficient of restitution (None to use the default value default_shape_restitution)

  • is_solid (bool) – Whether the capsule is solid or hollow

  • thickness (float | None) – Thickness to use for computing inertia of a hollow capsule, and for collision handling (None to use the default value default_shape_thickness)

  • has_ground_collision (bool) – If True, the shape will collide with the ground plane if Model.ground is True

  • has_shape_collision (bool) – If True, the shape will collide with other shapes

  • collision_group (int) – The collision group of the shape

  • is_visible (bool) – Whether the capsule is visible

Returns:

The index of the added shape

add_shape_cylinder(
body,
pos=(0.0, 0.0, 0.0),
rot=(0.0, 0.0, 0.0, 1.0),
radius=1.0,
half_height=0.5,
up_axis=1,
density=None,
ke=None,
kd=None,
kf=None,
ka=None,
mu=None,
restitution=None,
is_solid=True,
thickness=None,
has_ground_collision=True,
has_shape_collision=True,
collision_group=-1,
is_visible=True,
)[source]#

Adds a cylinder collision shape to a body.

Parameters:
  • body (int) – The index of the parent body this shape belongs to (use -1 for static shapes)

  • pos (List[float]) – The location of the shape with respect to the parent frame

  • rot (List[float]) – The rotation of the shape with respect to the parent frame

  • radius (float) – The radius of the cylinder

  • half_height (float) – The half length of the cylinder along the up axis

  • up_axis (int) – The axis along which the cylinder is aligned (0=x, 1=y, 2=z)

  • density (float | None) – The density of the shape (None to use the default value default_shape_density)

  • ke (float | None) – The contact elastic stiffness (None to use the default value default_shape_ke)

  • kd (float | None) – The contact damping stiffness (None to use the default value default_shape_kd)

  • kf (float | None) – The contact friction stiffness (None to use the default value default_shape_kf)

  • ka (float | None) – The contact adhesion distance (None to use the default value default_shape_ka)

  • mu (float | None) – The coefficient of friction (None to use the default value default_shape_mu)

  • restitution (float | None) – The coefficient of restitution (None to use the default value default_shape_restitution)

  • is_solid (bool) – Whether the cylinder is solid or hollow

  • thickness (float | None) – Thickness to use for computing inertia of a hollow cylinder, and for collision handling (None to use the default value default_shape_thickness)

  • has_ground_collision (bool) – If True, the shape will collide with the ground plane if Model.ground is True

  • has_shape_collision (bool) – If True, the shape will collide with other shapes

  • collision_group (int) – The collision group of the shape

  • is_visible (bool) – Whether the cylinder is visible

Note

Cylinders are currently not supported in rigid body collision handling.

Returns:

The index of the added shape

Parameters:
add_shape_cone(
body,
pos=(0.0, 0.0, 0.0),
rot=(0.0, 0.0, 0.0, 1.0),
radius=1.0,
half_height=0.5,
up_axis=1,
density=None,
ke=None,
kd=None,
kf=None,
ka=None,
mu=None,
restitution=None,
is_solid=True,
thickness=None,
has_ground_collision=True,
has_shape_collision=True,
collision_group=-1,
is_visible=True,
)[source]#

Adds a cone collision shape to a body.

Parameters:
  • body (int) – The index of the parent body this shape belongs to (use -1 for static shapes)

  • pos (List[float]) – The location of the shape with respect to the parent frame

  • rot (List[float]) – The rotation of the shape with respect to the parent frame

  • radius (float) – The radius of the cone

  • half_height (float) – The half length of the cone along the up axis

  • up_axis (int) – The axis along which the cone is aligned (0=x, 1=y, 2=z)

  • density (float | None) – The density of the shape (None to use the default value default_shape_density)

  • ke (float | None) – The contact elastic stiffness (None to use the default value default_shape_ke)

  • kd (float | None) – The contact damping stiffness (None to use the default value default_shape_kd)

  • kf (float | None) – The contact friction stiffness (None to use the default value default_shape_kf)

  • ka (float | None) – The contact adhesion distance (None to use the default value default_shape_ka)

  • mu (float | None) – The coefficient of friction (None to use the default value default_shape_mu)

  • restitution (float | None) – The coefficient of restitution (None to use the default value default_shape_restitution)

  • is_solid (bool) – Whether the cone is solid or hollow

  • thickness (float | None) – Thickness to use for computing inertia of a hollow cone, and for collision handling (None to use the default value default_shape_thickness)

  • has_ground_collision (bool) – If True, the shape will collide with the ground plane if Model.ground is True

  • has_shape_collision (bool) – If True, the shape will collide with other shapes

  • collision_group (int) – The collision group of the shape

  • is_visible (bool) – Whether the cone is visible

Note

Cones are currently not supported in rigid body collision handling.

Returns:

The index of the added shape

Parameters:
add_shape_mesh(
body,
pos=None,
rot=None,
mesh=None,
scale=None,
density=None,
ke=None,
kd=None,
kf=None,
ka=None,
mu=None,
restitution=None,
is_solid=True,
thickness=None,
has_ground_collision=True,
has_shape_collision=True,
collision_group=-1,
is_visible=True,
)[source]#

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 static shapes)

  • pos (List[float] | None) – The location of the shape with respect to the parent frame (None to use the default value wp.vec3(0.0, 0.0, 0.0))

  • rot (List[float] | None) – The rotation of the shape with respect to the parent frame (None to use the default value wp.quat(0.0, 0.0, 0.0, 1.0))

  • mesh (Mesh | None) – The mesh object

  • scale (List[float] | None) – Scale to use for the collider. (None to use the default value wp.vec3(1.0, 1.0, 1.0))

  • density (float | None) – The density of the shape (None to use the default value default_shape_density)

  • ke (float | None) – The contact elastic stiffness (None to use the default value default_shape_ke)

  • kd (float | None) – The contact damping stiffness (None to use the default value default_shape_kd)

  • kf (float | None) – The contact friction stiffness (None to use the default value default_shape_kf)

  • ka (float | None) – The contact adhesion distance (None to use the default value default_shape_ka)

  • mu (float | None) – The coefficient of friction (None to use the default value default_shape_mu)

  • restitution (float | None) – The coefficient of restitution (None to use the default value default_shape_restitution)

  • is_solid (bool) – If True, the mesh is solid, otherwise it is a hollow surface with the given wall thickness

  • thickness (float | None) – Thickness to use for computing inertia of a hollow mesh, and for collision handling (None to use the default value default_shape_thickness)

  • has_ground_collision (bool) – If True, the shape will collide with the ground plane if Model.ground is True

  • has_shape_collision (bool) – If True, the shape will collide with other shapes

  • collision_group (int) – The collision group of the shape

  • is_visible (bool) – Whether the mesh is visible

Returns:

The index of the added shape

add_shape_sdf(
body,
pos=(0.0, 0.0, 0.0),
rot=(0.0, 0.0, 0.0, 1.0),
sdf=None,
scale=(1.0, 1.0, 1.0),
density=None,
ke=None,
kd=None,
kf=None,
ka=None,
mu=None,
restitution=None,
is_solid=True,
thickness=None,
has_ground_collision=True,
has_shape_collision=True,
collision_group=-1,
is_visible=True,
)[source]#

Adds SDF collision shape to a body.

Parameters:
  • body (int) – The index of the parent body this shape belongs to (use -1 for static shapes)

  • pos (List[float]) – The location of the shape with respect to the parent frame

  • rot (List[float]) – The rotation of the shape with respect to the parent frame

  • sdf (SDF | None) – The sdf object

  • scale (List[float]) – Scale to use for the collider

  • density (float | None) – The density of the shape (None to use the default value default_shape_density)

  • ke (float | None) – The contact elastic stiffness (None to use the default value default_shape_ke)

  • kd (float | None) – The contact damping stiffness (None to use the default value default_shape_kd)

  • kf (float | None) – The contact friction stiffness (None to use the default value default_shape_kf)

  • ka (float | None) – The contact adhesion distance (None to use the default value default_shape_ka)

  • mu (float | None) – The coefficient of friction (None to use the default value default_shape_mu)

  • restitution (float | None) – The coefficient of restitution (None to use the default value default_shape_restitution)

  • is_solid (bool) – If True, the SDF is solid, otherwise it is a hollow surface with the given wall thickness

  • thickness (float | None) – Thickness to use for collision handling (None to use the default value default_shape_thickness)

  • has_ground_collision (bool) – If True, the shape will collide with the ground plane if Model.ground is True

  • has_shape_collision (bool) – If True, the shape will collide with other shapes

  • collision_group (int) – The collision group of the shape

  • is_visible (bool) – Whether the shape is visible

Returns:

The index of the added shape

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

Adds a single particle to the model

Parameters:
  • pos (List[float]) – The initial position of the particle

  • vel (List[float]) – 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

Return type:

int

Note

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

Returns:

The index of the particle in the system

Parameters:
Return type:

int

add_spring(i, j, ke, kd, control)[source]#

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=default_tri_ke,
tri_ka=default_tri_ka,
tri_kd=default_tri_kd,
tri_drag=default_tri_drag,
tri_lift=default_tri_lift,
)[source]#

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

  • tri_ke (float)

  • tri_ka (float)

  • tri_kd (float)

  • tri_drag (float)

  • tri_lift (float)

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,
)[source]#

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:
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,
)[source]#

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=default_edge_ke,
edge_kd=default_edge_kd,
)[source]#

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

  • edge_ke (float)

  • edge_kd (float)

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,
)[source]#

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

  • edge_ke (List[float] | None)

  • edge_kd (List[float] | None)

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=default_tri_ke,
tri_ka=default_tri_ka,
tri_kd=default_tri_kd,
tri_drag=default_tri_drag,
tri_lift=default_tri_lift,
edge_ke=default_edge_ke,
edge_kd=default_edge_kd,
add_springs=False,
spring_ke=default_spring_ke,
spring_kd=default_spring_kd,
particle_radius=default_particle_radius,
)[source]#

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]) – The position of the cloth in world space

  • rot (List[float]) – The orientation of the cloth in world space

  • vel (List[float]) – 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

  • tri_ke (float)

  • tri_ka (float)

  • tri_kd (float)

  • tri_drag (float)

  • tri_lift (float)

  • edge_ke (float)

  • edge_kd (float)

  • add_springs (bool)

  • spring_ke (float)

  • spring_kd (float)

  • particle_radius (float)

add_cloth_mesh(
pos,
rot,
scale,
vel,
vertices,
indices,
density,
edge_callback=None,
face_callback=None,
tri_ke=default_tri_ke,
tri_ka=default_tri_ka,
tri_kd=default_tri_kd,
tri_drag=default_tri_drag,
tri_lift=default_tri_lift,
edge_ke=default_edge_ke,
edge_kd=default_edge_kd,
add_springs=False,
spring_ke=default_spring_ke,
spring_kd=default_spring_kd,
particle_radius=default_particle_radius,
)[source]#

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]) – The position of the cloth in world space

  • rot (List[float]) – The orientation of the cloth in world space

  • vel (List[float]) – The velocity of the cloth in world space

  • vertices (List[List[float]]) – 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) – The particle_radius which controls particle based collisions.

  • scale (float)

  • tri_ke (float)

  • tri_ka (float)

  • tri_kd (float)

  • tri_drag (float)

  • tri_lift (float)

  • edge_ke (float)

  • edge_kd (float)

  • add_springs (bool)

  • spring_ke (float)

  • spring_kd (float)

Note

The mesh should be two manifold.

add_particle_grid(
pos,
rot,
vel,
dim_x,
dim_y,
dim_z,
cell_x,
cell_y,
cell_z,
mass,
jitter,
radius_mean=default_particle_radius,
radius_std=0.0,
)[source]#
Parameters:
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=default_tri_ke,
tri_ka=default_tri_ka,
tri_kd=default_tri_kd,
tri_drag=default_tri_drag,
tri_lift=default_tri_lift,
)[source]#

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]) – The position of the solid in world space

  • rot (List[float]) – The orientation of the solid in world space

  • vel (List[float]) – 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

  • tri_ke (float)

  • tri_ka (float)

  • tri_kd (float)

  • tri_drag (float)

  • tri_lift (float)

add_soft_mesh(
pos,
rot,
scale,
vel,
vertices,
indices,
density,
k_mu,
k_lambda,
k_damp,
tri_ke=default_tri_ke,
tri_ka=default_tri_ka,
tri_kd=default_tri_kd,
tri_drag=default_tri_drag,
tri_lift=default_tri_lift,
)[source]#

Helper to create a tetrahedral model from an input tetrahedral mesh

Parameters:
  • pos (List[float]) – The position of the solid in world space

  • rot (List[float]) – The orientation of the solid in world space

  • vel (List[float]) – The velocity of the solid in world space

  • vertices (List[List[float]]) – A list of vertex positions, array of 3D points

  • indices (List[int]) – A list of tetrahedron indices, 4 entries per-element, flattened array

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

  • k_mu (float) – The first elastic Lame parameter

  • k_lambda (float) – The second elastic Lame parameter

  • k_damp (float) – The damping stiffness

  • scale (float)

  • tri_ke (float)

  • tri_ka (float)

  • tri_kd (float)

  • tri_drag (float)

  • tri_lift (float)

set_ground_plane(
normal=None,
offset=0.0,
ke=default_shape_ke,
kd=default_shape_kd,
kf=default_shape_kf,
mu=default_shape_mu,
restitution=default_shape_restitution,
)[source]#

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

Parameters:
set_coloring(particle_coloring)[source]#

Set coloring information with user-provided coloring.

Parameters:

particle_coloring – 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,
)[source]#

Run 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 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 stage.e.

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)[source]#

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 – The simulation device to use, e.g.: ‘cpu’, ‘cuda’

  • requires_grad – Whether to enable gradient computation for the model

Returns:

A model object.

Return type:

Model

class warp.sim.Model(device=None)[source]#

Holds the definition of the simulation model

This class holds the non-time varying description of the system, i.e.: all geometry, constraints, and parameters used to describe the simulation.

requires_grad#

Indicates whether the model was finalized (see ModelBuilder.finalize()) with gradient computation enabled

Type:

float

num_envs#

Number of articulation environments that were added to the ModelBuilder via add_builder

Type:

int

particle_q#

Particle positions, shape [particle_count, 3], float

Type:

array

particle_qd#

Particle velocities, shape [particle_count, 3], float

Type:

array

particle_mass#

Particle mass, shape [particle_count], float

Type:

array

particle_inv_mass#

Particle inverse mass, shape [particle_count], float

Type:

array

particle_radius#

Particle radius, shape [particle_count], float

Type:

array

particle_max_radius#

Maximum particle radius (useful for HashGrid construction)

Type:

float

particle_ke#

Particle normal contact stiffness (used by SemiImplicitIntegrator), shape [particle_count], float

Type:

array

particle_kd#

Particle normal contact damping (used by SemiImplicitIntegrator), shape [particle_count], float

Type:

array

particle_kf#

Particle friction force stiffness (used by SemiImplicitIntegrator), shape [particle_count], float

Type:

array

particle_mu#

Particle friction coefficient, shape [particle_count], float

Type:

array

particle_cohesion#

Particle cohesion strength, shape [particle_count], float

Type:

array

particle_adhesion#

Particle adhesion strength, shape [particle_count], float

Type:

array

particle_grid#

HashGrid instance used for accelerated simulation of particle interactions

Type:

HashGrid

particle_flags#

Particle enabled state, shape [particle_count], bool

Type:

array

particle_max_velocity#

Maximum particle velocity (to prevent instability)

Type:

float

shape_transform#

Rigid shape transforms, shape [shape_count, 7], float

Type:

array

shape_visible#

Rigid shape visibility, shape [shape_count], bool

Type:

array

shape_body#

Rigid shape body index, shape [shape_count], int

Type:

array

body_shapes#

Mapping from body index to list of attached shape indices

Type:

dict

shape_materials#

Rigid shape contact materials, shape [shape_count], float

Type:

ModelShapeMaterials

shape_shape_geo#

Shape geometry properties (geo type, scale, thickness, etc.), shape [shape_count, 3], float

Type:

ModelShapeGeometry

shape_geo_src#

List of wp.Mesh instances used for rendering of mesh geometry

Type:

list

shape_collision_group#

Collision group of each shape, shape [shape_count], int

Type:

list

shape_collision_group_map#

Mapping from collision group to list of shape indices

Type:

dict

shape_collision_filter_pairs#

Pairs of shape indices that should not collide

Type:

set

shape_collision_radius#

Collision radius of each shape used for bounding sphere broadphase collision checking, shape [shape_count], float

Type:

array

shape_ground_collision#

Indicates whether each shape should collide with the ground, shape [shape_count], bool

Type:

list

shape_shape_collision#

Indicates whether each shape should collide with any other shape, shape [shape_count], bool

Type:

list

shape_contact_pairs#

Pairs of shape indices that may collide, shape [contact_pair_count, 2], int

Type:

array

shape_ground_contact_pairs#

Pairs of shape, ground indices that may collide, shape [ground_contact_pair_count, 2], int

Type:

array

spring_indices#

Particle spring indices, shape [spring_count*2], int

Type:

array

spring_rest_length#

Particle spring rest length, shape [spring_count], float

Type:

array

spring_stiffness#

Particle spring stiffness, shape [spring_count], float

Type:

array

spring_damping#

Particle spring damping, shape [spring_count], float

Type:

array

spring_control#

Particle spring activation, shape [spring_count], float

Type:

array

tri_indices#

Triangle element indices, shape [tri_count*3], int

Type:

array

tri_poses#

Triangle element rest pose, shape [tri_count, 2, 2], float

Type:

array

tri_activations#

Triangle element activations, shape [tri_count], float

Type:

array

tri_materials#

Triangle element materials, shape [tri_count, 5], float

Type:

array

tri_areas#

Triangle element rest areas, shape [tri_count], float

Type:

array

edge_indices#

Bending edge indices, shape [edge_count*4], int, each row is [o0, o1, v1, v2], where v1, v2 are on the edge

Type:

array

edge_rest_angle#

Bending edge rest angle, shape [edge_count], float

Type:

array

edge_bending_properties#

Bending edge stiffness and damping parameters, shape [edge_count, 2], float

Type:

array

tet_indices#

Tetrahedral element indices, shape [tet_count*4], int

Type:

array

tet_poses#

Tetrahedral rest poses, shape [tet_count, 3, 3], float

Type:

array

tet_activations#

Tetrahedral volumetric activations, shape [tet_count], float

Type:

array

tet_materials#

Tetrahedral elastic parameters in form \(k_{mu}, k_{lambda}, k_{damp}\), shape [tet_count, 3]

Type:

array

muscle_start#

Start index of the first muscle point per muscle, shape [muscle_count], int

Type:

array

muscle_params#

Muscle parameters, shape [muscle_count, 5], float

Type:

array

muscle_bodies#

Body indices of the muscle waypoints, int

Type:

array

muscle_points#

Local body offset of the muscle waypoints, float

Type:

array

muscle_activations#

Muscle activations, shape [muscle_count], float

Type:

array

body_q#

Poses of rigid bodies used for state initialization, shape [body_count, 7], float

Type:

array

body_qd#

Velocities of rigid bodies used for state initialization, shape [body_count, 6], float

Type:

array

body_com#

Rigid body center of mass (in local frame), shape [body_count, 7], float

Type:

array

body_inertia#

Rigid body inertia tensor (relative to COM), shape [body_count, 3, 3], float

Type:

array

body_inv_inertia#

Rigid body inverse inertia tensor (relative to COM), shape [body_count, 3, 3], float

Type:

array

body_mass#

Rigid body mass, shape [body_count], float

Type:

array

body_inv_mass#

Rigid body inverse mass, shape [body_count], float

Type:

array

body_name#

Rigid body names, shape [body_count], str

Type:

list

joint_q#

Generalized joint positions used for state initialization, shape [joint_coord_count], float

Type:

array

joint_qd#

Generalized joint velocities used for state initialization, shape [joint_dof_count], float

Type:

array

joint_act#

Generalized joint control inputs, shape [joint_axis_count], float

Type:

array

joint_type#

Joint type, shape [joint_count], int

Type:

array

joint_parent#

Joint parent body indices, shape [joint_count], int

Type:

array

joint_child#

Joint child body indices, shape [joint_count], int

Type:

array

joint_ancestor#

Maps from joint index to the index of the joint that has the current joint parent body as child (-1 if no such joint ancestor exists), shape [joint_count], int

Type:

array

joint_X_p#

Joint transform in parent frame, shape [joint_count, 7], float

Type:

array

joint_X_c#

Joint mass frame in child frame, shape [joint_count, 7], float

Type:

array

joint_axis#

Joint axis in child frame, shape [joint_axis_count, 3], float

Type:

array

joint_armature#

Armature for each joint axis (only used by FeatherstoneIntegrator), shape [joint_dof_count], float

Type:

array

joint_target_ke#

Joint stiffness, shape [joint_axis_count], float

Type:

array

joint_target_kd#

Joint damping, shape [joint_axis_count], float

Type:

array

joint_axis_start#

Start index of the first axis per joint, shape [joint_count], int

Type:

array

joint_axis_dim#

Number of linear and angular axes per joint, shape [joint_count, 2], int

Type:

array

joint_axis_mode#

Joint axis mode, shape [joint_axis_count], int. See Joint modes.

Type:

array

joint_linear_compliance#

Joint linear compliance, shape [joint_count], float

Type:

array

joint_angular_compliance#

Joint linear compliance, shape [joint_count], float

Type:

array

joint_enabled#

Controls which joint is simulated (bodies become disconnected if False), shape [joint_count], int

Note

This setting is not supported by FeatherstoneIntegrator.

Type:

array

joint_limit_lower#

Joint lower position limits, shape [joint_count], float

Type:

array

joint_limit_upper#

Joint upper position limits, shape [joint_count], float

Type:

array

joint_limit_ke#

Joint position limit stiffness (used by the Euler integrators), shape [joint_count], float

Type:

array

joint_limit_kd#

Joint position limit damping (used by the Euler integrators), shape [joint_count], float

Type:

array

joint_twist_lower#

Joint lower twist limit, shape [joint_count], float

Type:

array

joint_twist_upper#

Joint upper twist limit, shape [joint_count], float

Type:

array

joint_q_start#

Start index of the first position coordinate per joint, shape [joint_count], int

Type:

array

joint_qd_start#

Start index of the first velocity coordinate per joint, shape [joint_count], int

Type:

array

articulation_start#

Articulation start index, shape [articulation_count], int

Type:

array

joint_name#

Joint names, shape [joint_count], str

Type:

list

joint_attach_ke#

Joint attachment force stiffness (used by SemiImplicitIntegrator)

Type:

float

joint_attach_kd#

Joint attachment force damping (used by SemiImplicitIntegrator)

Type:

float

soft_contact_margin#

Contact margin for generation of soft contacts

Type:

float

soft_contact_ke#

Stiffness of soft contacts (used by the Euler integrators)

Type:

float

soft_contact_kd#

Damping of soft contacts (used by the Euler integrators)

Type:

float

soft_contact_kf#

Stiffness of friction force in soft contacts (used by the Euler integrators)

Type:

float

soft_contact_mu#

Friction coefficient of soft contacts

Type:

float

soft_contact_restitution#

Restitution coefficient of soft contacts (used by XPBDIntegrator)

Type:

float

soft_contact_count#

Number of active particle-shape contacts, shape [1], int

Type:

array

soft_contact_particle#
Type:

array

soft_contact_shape#
Type:

array

soft_contact_body_pos#
Type:

array

soft_contact_body_vel#
Type:

array

soft_contact_normal#
Type:

array

rigid_contact_max#

Maximum number of potential rigid body contact points to generate ignoring the rigid_mesh_contact_max limit.

Type:

int

rigid_contact_max_limited#

Maximum number of potential rigid body contact points to generate respecting the rigid_mesh_contact_max limit.

Type:

int

rigid_mesh_contact_max#

Maximum number of rigid body contact points to generate per mesh (0 = unlimited, default)

Type:

int

rigid_contact_margin#

Contact margin for generation of rigid body contacts

Type:

float

rigid_contact_torsional_friction#

Torsional friction coefficient for rigid body contacts (used by XPBDIntegrator)

Type:

float

rigid_contact_rolling_friction#

Rolling friction coefficient for rigid body contacts (used by XPBDIntegrator)

Type:

float

rigid_contact_count#

Number of active shape-shape contacts, shape [1], int

Type:

array

rigid_contact_point0#

Contact point relative to frame of body 0, shape [rigid_contact_max], vec3

Type:

array

rigid_contact_point1#

Contact point relative to frame of body 1, shape [rigid_contact_max], vec3

Type:

array

rigid_contact_offset0#

Contact offset due to contact thickness relative to body 0, shape [rigid_contact_max], vec3

Type:

array

rigid_contact_offset1#

Contact offset due to contact thickness relative to body 1, shape [rigid_contact_max], vec3

Type:

array

rigid_contact_normal#

Contact normal in world space, shape [rigid_contact_max], vec3

Type:

array

rigid_contact_thickness#

Total contact thickness, shape [rigid_contact_max], float

Type:

array

rigid_contact_shape0#

Index of shape 0 per contact, shape [rigid_contact_max], int

Type:

array

rigid_contact_shape1#

Index of shape 1 per contact, shape [rigid_contact_max], int

Type:

array

ground#

Whether the ground plane and ground contacts are enabled

Type:

bool

ground_plane#

Ground plane 3D normal and offset, shape [4], float

Type:

array

up_vector#

Up vector of the world, shape [3], float

Type:

np.ndarray

up_axis#

Up axis, 0 for x, 1 for y, 2 for z

Type:

int

gravity#

Gravity vector, shape [3], float

Type:

np.ndarray

particle_count#

Total number of particles in the system

Type:

int

body_count#

Total number of bodies in the system

Type:

int

shape_count#

Total number of shapes in the system

Type:

int

joint_count#

Total number of joints in the system

Type:

int

tri_count#

Total number of triangles in the system

Type:

int

tet_count#

Total number of tetrahedra in the system

Type:

int

edge_count#

Total number of edges in the system

Type:

int

spring_count#

Total number of springs in the system

Type:

int

contact_count#

Total number of contacts in the system

Type:

int

muscle_count#

Total number of muscles in the system

Type:

int

articulation_count#

Total number of articulations in the system

Type:

int

joint_dof_count#

Total number of velocity degrees of freedom of all joints in the system

Type:

int

joint_coord_count#

Total number of position degrees of freedom of all joints in the system

Type:

int

particle_coloring#

The coloring of all the particles, used for VBD’s Gauss-Seidel iteration.

Type:

list of array

device#

Device on which the Model was allocated

Type:

wp.Device

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.

__init__(device=None)[source]#
state(requires_grad=None)[source]#

Returns a state object for the model

The returned state will be initialized with the initial configuration given in the model description.

Parameters:

requires_grad (bool) – Manual overwrite whether the state variables should have requires_grad enabled (defaults to None to use the model’s setting requires_grad)

Returns:

The state object

Return type:

State

control(requires_grad=None, clone_variables=True)[source]#

Returns a control object for the model.

The returned control object will be initialized with the control inputs given in the model description.

Parameters:
  • requires_grad (bool) – Manual overwrite whether the control variables should have requires_grad enabled (defaults to None to use the model’s setting requires_grad)

  • clone_variables (bool) – Whether to clone the control inputs or use the original data

Returns:

The control object

Return type:

Control

allocate_soft_contacts(count, requires_grad=False)[source]#
find_shape_contact_pairs()[source]#
count_contact_points()[source]#

Counts the maximum number of rigid contact points that need to be allocated. This function returns two values corresponding to the maximum number of potential contacts excluding the limiting from Model.rigid_mesh_contact_max and the maximum number of contact points that may be generated when considering the Model.rigid_mesh_contact_max limit.

Returns:

  • potential_count (int): Potential number of contact points

  • actual_count (int): Actual number of contact points

allocate_rigid_contacts(
target=None,
count=None,
limited_contact_count=None,
requires_grad=False,
)[source]#
property soft_contact_max[source]#

Maximum number of soft contacts that can be registered

class warp.sim.ModelShapeMaterials#
cls[source]#

alias of ModelShapeMaterials

ctype[source]#

alias of StructType

default_constructor = <Function ModelShapeMaterials_bcc267f8()>#
hash = b'\xbc\xc2g\xf8l\x04\xd9\x0e\xa6\xcb\x1e\xf3\xd6\x98\xd4\x9dr\xb5\xd5\xc3WX\x14XRRW\x93\xc7]\x0c\xed'#
key = 'ModelShapeMaterials'#
module = <warp.context.Module object>#
native_name = 'ModelShapeMaterials_bcc267f8'#
value_constructor = <Function ModelShapeMaterials_bcc267f8(ke: array(ndim=1, dtype=<class 'warp.types.float32'>), kd: array(ndim=1, dtype=<class 'warp.types.float32'>), kf: array(ndim=1, dtype=<class 'warp.types.float32'>), ka: array(ndim=1, dtype=<class 'warp.types.float32'>), mu: array(ndim=1, dtype=<class 'warp.types.float32'>), restitution: array(ndim=1, dtype=<class 'warp.types.float32'>))>#
vars = {'ka': <warp.codegen.Var object>, 'kd': <warp.codegen.Var object>, 'ke': <warp.codegen.Var object>, 'kf': <warp.codegen.Var object>, 'mu': <warp.codegen.Var object>, 'restitution': <warp.codegen.Var object>}#
class warp.sim.ModelShapeGeometry#
cls[source]#

alias of ModelShapeGeometry

ctype[source]#

alias of StructType

default_constructor = <Function ModelShapeGeometry_a9b47f7f()>#
hash = b'\xa9\xb4\x7f\x7f\xfb8\x10.\xb28\xd7\x0b-\x01\xd9<\x98\xe0\x81\x08\xef\x13\xc0\xa0=%B\xf5\xff\xbb\xf4a'#
key = 'ModelShapeGeometry'#
module = <warp.context.Module object>#
native_name = 'ModelShapeGeometry_a9b47f7f'#
value_constructor = <Function ModelShapeGeometry_a9b47f7f(type: array(ndim=1, dtype=<class 'warp.types.int32'>), is_solid: array(ndim=1, dtype=<class 'warp.types.uint8'>), thickness: array(ndim=1, dtype=<class 'warp.types.float32'>), source: array(ndim=1, dtype=<class 'warp.types.uint64'>), scale: array(ndim=1, dtype=<class 'warp.types.vec3f'>))>#
vars = {'is_solid': <warp.codegen.Var object>, 'scale': <warp.codegen.Var object>, 'source': <warp.codegen.Var object>, 'thickness': <warp.codegen.Var object>, 'type': <warp.codegen.Var object>}#
class warp.sim.JointAxis(
axis,
limit_lower=-math.inf,
limit_upper=math.inf,
limit_ke=100.0,
limit_kd=10.0,
action=None,
target_ke=0.0,
target_kd=0.0,
mode=JOINT_MODE_FORCE,
)[source]#

Describes a joint axis that can have limits and be driven towards a target.

axis#

The 3D axis that this JointAxis object describes, or alternatively another JointAxis object to copy from

Type:

3D vector or JointAxis

limit_lower#

The lower position limit of the joint axis

Type:

float

limit_upper#

The upper position limit of the joint axis

Type:

float

limit_ke#

The elastic stiffness of the joint axis limits, only respected by SemiImplicitIntegrator and FeatherstoneIntegrator

Type:

float

limit_kd#

The damping stiffness of the joint axis limits, only respected by SemiImplicitIntegrator and FeatherstoneIntegrator

Type:

float

action#

The force applied by default to this joint axis, or the target position or velocity (depending on the mode, see Joint modes) of the joint axis

Type:

float

target_ke#

The proportional gain of the joint axis target drive PD controller

Type:

float

target_kd#

The derivative gain of the joint axis target drive PD controller

Type:

float

mode#

The mode of the joint axis, see Joint modes

Type:

int

__init__(
axis,
limit_lower=-math.inf,
limit_upper=math.inf,
limit_ke=100.0,
limit_kd=10.0,
action=None,
target_ke=0.0,
target_kd=0.0,
mode=JOINT_MODE_FORCE,
)[source]#
class warp.sim.Mesh(vertices, indices, compute_inertia=True, is_solid=True)[source]#

Describes a triangle collision mesh for simulation

Example mesh creation from a triangle OBJ mesh file:#

See load_mesh() which is provided as a utility function.

import numpy as np
import warp as wp
import warp.sim
import openmesh

m = openmesh.read_trimesh("mesh.obj")
mesh_points = np.array(m.points())
mesh_indices = np.array(m.face_vertex_indices(), dtype=np.int32).flatten()
mesh = wp.sim.Mesh(mesh_points, mesh_indices)
vertices#

Mesh 3D vertices points

Type:

List[Vec3]

indices#

Mesh indices as a flattened list of vertex indices describing triangles

Type:

List[int]

I#

3x3 inertia matrix of the mesh assuming density of 1.0 (around the center of mass)

Type:

Mat33

mass#

The total mass of the body assuming density of 1.0

Type:

float

com#

The center of mass of the body

Type:

Vec3

__init__(vertices, indices, compute_inertia=True, is_solid=True)[source]#

Construct a Mesh object from a triangle mesh

The mesh center of mass and inertia tensor will automatically be calculated using a density of 1.0. This computation is only valid if the mesh is closed (two-manifold).

Parameters:
  • vertices (List[List[float]]) – List of vertices in the mesh

  • indices (List[int]) – List of triangle indices, 3 per-element

  • compute_inertia – If True, the mass, inertia tensor and center of mass will be computed assuming density of 1.0

  • is_solid – If True, the mesh is assumed to be a solid during inertia computation, otherwise it is assumed to be a hollow surface

finalize(device=None)[source]#

Constructs a simulation-ready Mesh object from the mesh data and returns its ID.

Parameters:

device – The device on which to allocate the mesh buffers

Returns:

The ID of the simulation-ready Mesh

Parameters:
class warp.sim.SDF(volume=None, I=None, mass=1.0, com=None)[source]#

Describes a signed distance field for simulation

volume#

The volume defining the SDF

Type:

Volume

I#

3x3 inertia matrix of the SDF

Type:

Mat33

mass#

The total mass of the SDF

Type:

float

com#

The center of mass of the SDF

Type:

Vec3

__init__(volume=None, I=None, mass=1.0, com=None)[source]#
finalize(device=None)[source]#

Joint types#

warp.sim.JOINT_PRISMATIC#

Prismatic (slider) joint

warp.sim.JOINT_REVOLUTE#

Revolute (hinge) joint

warp.sim.JOINT_BALL#

Ball (spherical) joint with quaternion state representation

warp.sim.JOINT_FIXED#

Fixed (static) joint

warp.sim.JOINT_FREE#

Free (floating) joint

warp.sim.JOINT_COMPOUND#

Compound joint with 3 rotational degrees of freedom

warp.sim.JOINT_UNIVERSAL#

Universal joint with 2 rotational degrees of freedom

warp.sim.JOINT_DISTANCE#

Distance joint that keeps two bodies at a distance within its joint limits (only supported in XPBDIntegrator at the moment)

warp.sim.JOINT_D6#

Generic D6 joint with up to 3 translational and 3 rotational degrees of freedom

Joint control modes#

Joint modes control the behavior of how the joint control input Control.joint_act affects the torque applied at a given joint axis. By default, it behaves as a direct force application via JOINT_MODE_FORCE. Other modes can be used to implement joint position or velocity drives:

warp.sim.JOINT_MODE_FORCE#

This is the default control mode where the control input is the torque \(\tau\) applied at the joint axis.

warp.sim.JOINT_MODE_TARGET_POSITION#

The control input is the target position \(\mathbf{q}_{\text{target}}\) which is achieved via PD control of torque \(\tau\) where the proportional and derivative gains are set by Model.joint_target_ke and Model.joint_target_kd:

\[\tau = k_e (\mathbf{q}_{\text{target}} - \mathbf{q}) - k_d \mathbf{\dot{q}}\]
warp.sim.JOINT_MODE_TARGET_VELOCITY#

The control input is the target velocity \(\mathbf{\dot{q}}_{\text{target}}\) which is achieved via a controller of torque \(\tau\) that brings the velocity at the joint axis to the target through proportional gain Model.joint_target_ke:

\[\tau = k_e (\mathbf{\dot{q}}_{\text{target}} - \mathbf{\dot{q}})\]

State#

class warp.sim.State[source]#

The State object holds all time-varying data for a model.

Time-varying data includes particle positions, velocities, rigid body states, and anything that is output from the integrator as derived data, e.g.: forces.

The exact attributes depend on the contents of the model. State objects should generally be created using the Model.state() function.

particle_q#

Array of 3D particle positions, shape [particle_count], vec3

Type:

array

particle_qd#

Array of 3D particle velocities, shape [particle_count], vec3

Type:

array

particle_f#

Array of 3D particle forces, shape [particle_count], vec3

Type:

array

body_q#

Array of body coordinates (7-dof transforms) in maximal coordinates, shape [body_count], transform

Type:

array

body_qd#

Array of body velocities in maximal coordinates (first 3 entries represent angular velocity, last 3 entries represent linear velocity), shape [body_count], spatial_vector

Type:

array

body_f#

Array of body forces in maximal coordinates (first 3 entries represent torque, last 3 entries represent linear force), shape [body_count], spatial_vector

Note

body_f represents external wrenches in world frame and denotes wrenches measured w.r.t. to the body’s center of mass for all integrators except FeatherstoneIntegrator which assumes the wrenches are measured w.r.t. world origin.

Type:

array

joint_q#

Array of generalized joint coordinates, shape [joint_coord_count], float

Type:

array

joint_qd#

Array of generalized joint velocities, shape [joint_dof_count], float

Type:

array

__init__()[source]#
clear_forces()[source]#

Clears all forces (for particles and bodies) in the state object.

property requires_grad[source]#

Indicates whether the state arrays have gradient computation enabled.

property body_count[source]#

The number of bodies represented in the state.

property particle_count[source]#

The number of particles represented in the state.

property joint_coord_count[source]#

The number of generalized joint position coordinates represented in the state.

property joint_dof_count[source]#

The number of generalized joint velocity coordinates represented in the state.

Control#

class warp.sim.Control(model)[source]#

The Control object holds all time-varying control data for a model.

Time-varying control data includes joint control inputs, muscle activations, and activation forces for triangle and tetrahedral elements.

The exact attributes depend on the contents of the model. Control objects should generally be created using the Model.control() function.

joint_act#

Array of joint control inputs, shape [joint_axis_count], float

Type:

array

tri_activations#

Array of triangle element activations, shape [tri_count], float

Type:

array

tet_activations#

Array of tetrahedral element activations, shape [tet_count], float

Type:

array

muscle_activations#

Array of muscle activations, shape [muscle_count], float

Type:

array

__init__(model)[source]#
Parameters:

model (Model) – The model to use as a reference for the control inputs

reset()[source]#

Resets the control inputs to their initial state defined in Model.

Forward / Inverse Kinematics#

Articulated rigid-body mechanisms are kinematically described by the joints that connect the bodies as well as the relative relative transform from the parent and child body to the respective anchor frames of the joint in the parent and child body:

../_images/joint_transforms.png
Variable names in the kernels from articulation.py#

Symbol

Description

x_wp

World transform of the parent body (stored at State.body_q)

x_wc

World transform of the child body (stored at State.body_q)

x_pj

Transform from the parent body to the joint parent anchor frame (defined by Model.joint_X_p)

x_cj

Transform from the child body to the joint child anchor frame (defined by Model.joint_X_c)

x_j

Joint transform from the joint parent anchor frame to the joint child anchor frame

In the forward kinematics, the joint transform is determined by the joint coordinates (generalized joint positions State.joint_q and velocities State.joint_qd). Given the parent body’s world transform \(x_{wp}\) and the joint transform \(x_{j}\), the child body’s world transform \(x_{wc}\) is computed as:

\[x_{wc} = x_{wp} \cdot x_{pj} \cdot x_{j} \cdot x_{cj}^{-1}.\]
warp.sim.eval_fk(model, joint_q, joint_qd, mask, state)[source]#

Evaluates the model’s forward kinematics given the joint coordinates and updates the state’s body information (State.body_q and State.body_qd).

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

  • joint_q (array) – Generalized joint position coordinates, shape [joint_coord_count], float

  • joint_qd (array) – Generalized joint velocity coordinates, shape [joint_dof_count], float

  • mask (array) – The mask to use to enable / disable FK for an articulation. If None then treat all as enabled, shape [articulation_count], int/bool

  • state (State) – The state to update.

warp.sim.eval_ik(model, state, joint_q, joint_qd)[source]#

Evaluates the model’s inverse kinematics given the state’s body information (State.body_q and State.body_qd) and updates the generalized joint coordinates joint_q and joint_qd.

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

  • state (State) – The state with the body’s maximal coordinates (positions State.body_q and velocities State.body_qd) to use.

  • joint_q (array) – Generalized joint position coordinates, shape [joint_coord_count], float

  • joint_qd (array) – Generalized joint velocity coordinates, shape [joint_dof_count], float

Integrators#

class warp.sim.Integrator[source]#

Generic base class for integrators. Provides methods to integrate rigid bodies and particles.

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

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)[source]#

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).

simulate(model, state_in, state_out, dt, control=None)[source]#

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.

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

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

class warp.sim.SemiImplicitIntegrator(angular_damping=0.05)[source]#

A semi-implicit integrator using symplectic Euler

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

Semi-implicit time integration is a variational integrator that preserves energy, however it not unconditionally stable, and requires a time-step small enough to support the required stiffness and damping forces.

See: https://en.wikipedia.org/wiki/Semi-implicit_Euler_method

Example

integrator = wp.SemiImplicitIntegrator()

# simulation loop
for i in range(100):
    state = integrator.simulate(model, state_in, state_out, dt)
Parameters:

angular_damping (float)

__init__(angular_damping=0.05)[source]#
Parameters:

angular_damping (float, optional) – Angular damping factor. Defaults to 0.05.

simulate(
model,
state_in,
state_out,
dt,
control=None,
)[source]#

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.

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

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

class warp.sim.XPBDIntegrator(
iterations=2,
soft_body_relaxation=0.9,
soft_contact_relaxation=0.9,
joint_linear_relaxation=0.7,
joint_angular_relaxation=0.4,
rigid_contact_relaxation=0.8,
rigid_contact_con_weighting=True,
angular_damping=0.0,
enable_restitution=False,
)[source]#

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

integrator = wp.XPBDIntegrator()

# simulation loop
for i in range(100):
    state = integrator.simulate(model, state_in, state_out, dt, control)
__init__(
iterations=2,
soft_body_relaxation=0.9,
soft_contact_relaxation=0.9,
joint_linear_relaxation=0.7,
joint_angular_relaxation=0.4,
rigid_contact_relaxation=0.8,
rigid_contact_con_weighting=True,
angular_damping=0.0,
enable_restitution=False,
)[source]#
apply_particle_deltas(
model,
state_in,
state_out,
particle_deltas,
dt,
)[source]#
Parameters:
apply_body_deltas(
model,
state_in,
state_out,
body_deltas,
dt,
rigid_contact_inv_weight=None,
)[source]#
Parameters:
simulate(model, state_in, state_out, dt, control=None)[source]#

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.

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

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

class warp.sim.FeatherstoneIntegrator(
model,
angular_damping=0.05,
update_mass_matrix_every=1,
use_tile_gemm=False,
)[source]#

A semi-implicit integrator using symplectic Euler that operates on reduced (also called generalized) coordinates to simulate articulated rigid body dynamics based on Featherstone’s composite rigid body algorithm (CRBA).

See: Featherstone, Roy. Rigid Body Dynamics Algorithms. Springer US, 2014.

Instead of maximal coordinates State.body_q (rigid body positions) and State.body_qd (rigid body velocities) as is the case SemiImplicitIntegrator, FeatherstoneIntegrator uses State.joint_q and State.joint_qd to represent the positions and velocities of joints without allowing any redundant degrees of freedom.

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

Note

Unlike SemiImplicitIntegrator and XPBDIntegrator, FeatherstoneIntegrator does not simulate rigid bodies with nonzero mass as floating bodies if they are not connected through any joints. Floating-base systems require an explicit free joint with which the body is connected to the world, see ModelBuilder.add_joint_free().

Semi-implicit time integration is a variational integrator that preserves energy, however it not unconditionally stable, and requires a time-step small enough to support the required stiffness and damping forces.

See: https://en.wikipedia.org/wiki/Semi-implicit_Euler_method

Example

integrator = wp.FeatherstoneIntegrator(model)

# simulation loop
for i in range(100):
    state = integrator.simulate(model, state_in, state_out, dt)

Note

The FeatherstoneIntegrator requires the Model to be passed in as a constructor argument.

__init__(
model,
angular_damping=0.05,
update_mass_matrix_every=1,
use_tile_gemm=False,
)[source]#
Parameters:
  • model (Model) – the model to be simulated.

  • angular_damping (float, optional) – Angular damping factor. Defaults to 0.05.

  • update_mass_matrix_every (int, optional) – How often to update the mass matrix (every n-th time the simulate() function gets called). Defaults to 1.

compute_articulation_indices(model)[source]#
allocate_model_aux_vars(model)[source]#
allocate_state_aux_vars(
model,
target,
requires_grad,
)[source]#
simulate(
model,
state_in,
state_out,
dt,
control=None,
)[source]#

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.

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

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

class warp.sim.VBDIntegrator(
model,
iterations=10,
body_particle_contact_buffer_pre_alloc=4,
friction_epsilon=1e-2,
)[source]#

An implicit integrator using Vertex Block Descent (VBD) for cloth simulation.

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 that VBDIntegrator’s constructor requires a Model object as input, so that it can do some precomputation and preallocate the space. After construction, you must provide the same Model object that you used that was used during construction. Currently, you must manually provide particle coloring and assign it to model.particle_coloring to make VBD work.

VBDIntegrator.simulate accepts three arguments: class:Model, State, and Control (optional) objects, this time-integrator may be used to advance the simulation state forward in time.

Example

model.particle_coloring = # load or generate particle coloring
integrator = wp.VBDIntegrator(model)

# simulation loop
for i in range(100):
    state = integrator.simulate(model, state_in, state_out, dt, control)
Parameters:

model (Model)

__init__(
model,
iterations=10,
body_particle_contact_buffer_pre_alloc=4,
friction_epsilon=1e-2,
)[source]#
Parameters:

model (Model)

compute_force_element_adjacency(model)[source]#
simulate(model, state_in, state_out, dt, control=None)[source]#

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.

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

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

convert_body_particle_contact_data()[source]#
count_num_adjacent_edges = <warp.context.Kernel object>#
fill_adjacent_edges = <warp.context.Kernel object>#
count_num_adjacent_faces = <warp.context.Kernel object>#
fill_adjacent_faces = <warp.context.Kernel object>#

Importers#

Warp sim supports the loading of simulation models from URDF, MuJoCo (MJCF), and USD Physics files.

warp.sim.parse_urdf(
urdf_filename,
builder,
xform=None,
floating=False,
base_joint=None,
density=1000.0,
stiffness=100.0,
damping=10.0,
armature=0.0,
contact_ke=1.0e4,
contact_kd=1.0e3,
contact_kf=1.0e2,
contact_ka=0.0,
contact_mu=0.25,
contact_restitution=0.5,
contact_thickness=0.0,
limit_ke=100.0,
limit_kd=10.0,
joint_limit_lower=-1e6,
joint_limit_upper=1e6,
scale=1.0,
parse_visuals_as_colliders=False,
force_show_colliders=False,
enable_self_collisions=True,
ignore_inertial_definitions=True,
ensure_nonstatic_links=True,
static_link_mass=1e-2,
collapse_fixed_joints=False,
)[source]#

Parses a URDF file and adds the bodies and joints to the given ModelBuilder.

Parameters:
  • urdf_filename (str) – The filename of the URDF file to parse.

  • builder (ModelBuilder) – The ModelBuilder to add the bodies and joints to.

  • xform (transform) – The transform to apply to the root body.

  • floating (bool) – If True, the root body is a free joint. If False, the root body is connected via a fixed joint to the world, unless a base_joint is defined.

  • base_joint (Union[str, dict]) – The joint by which the root body is connected to the world. This can be either a string defining the joint axes of a D6 joint with comma-separated positional and angular axis names (e.g. “px,py,rz” for a D6 joint with linear axes in x, y and an angular axis in z) or a dict with joint parameters (see ModelBuilder.add_joint()).

  • density (float) – The density of the shapes in kg/m^3 which will be used to calculate the body mass and inertia.

  • stiffness (float) – The stiffness of the joints.

  • damping (float) – The damping of the joints.

  • armature (float) – The armature of the joints (bias to add to the inertia diagonals that may stabilize the simulation).

  • contact_ke (float) – The stiffness of the shape contacts (used by the Euler integrators).

  • contact_kd (float) – The damping of the shape contacts (used by the Euler integrators).

  • contact_kf (float) – The friction stiffness of the shape contacts (used by the Euler integrators).

  • contact_ka (float) – The adhesion distance of the shape contacts (used by the Euler integrators).

  • contact_mu (float) – The friction coefficient of the shape contacts.

  • contact_restitution (float) – The restitution coefficient of the shape contacts.

  • contact_thickness (float) – The thickness to add to the shape geometry.

  • limit_ke (float) – The stiffness of the joint limits (used by the Euler integrators).

  • limit_kd (float) – The damping of the joint limits (used by the Euler integrators).

  • joint_limit_lower (float) – The default lower joint limit if not specified in the URDF.

  • joint_limit_upper (float) – The default upper joint limit if not specified in the URDF.

  • scale (float) – The scaling factor to apply to the imported mechanism.

  • parse_visuals_as_colliders (bool) – If True, the geometry defined under the <visual> tags is used for collision handling instead of the <collision> geometries.

  • force_show_colliders (bool) – If True, the collision shapes are always shown, even if there are visual shapes.

  • enable_self_collisions (bool) – If True, self-collisions are enabled.

  • ignore_inertial_definitions (bool) – If True, the inertial parameters defined in the URDF are ignored and the inertia is calculated from the shape geometry.

  • ensure_nonstatic_links (bool) – If True, links with zero mass are given a small mass (see static_link_mass) to ensure they are dynamic.

  • static_link_mass (float) – The mass to assign to links with zero mass (if ensure_nonstatic_links is set to True).

  • collapse_fixed_joints (bool) – If True, fixed joints are removed and the respective bodies are merged.

warp.sim.parse_mjcf(
mjcf_filename,
builder,
xform=None,
density=1000.0,
stiffness=0.0,
damping=0.0,
contact_ke=1000.0,
contact_kd=100.0,
contact_kf=100.0,
contact_ka=0.0,
contact_mu=0.5,
contact_restitution=0.5,
contact_thickness=0.0,
limit_ke=100.0,
limit_kd=10.0,
scale=1.0,
armature=0.0,
armature_scale=1.0,
parse_meshes=True,
enable_self_collisions=False,
up_axis='Z',
ignore_classes=None,
collapse_fixed_joints=False,
)[source]#

Parses MuJoCo XML (MJCF) file and adds the bodies and joints to the given ModelBuilder.

Parameters:
  • mjcf_filename (str) – The filename of the MuJoCo file to parse.

  • builder (ModelBuilder) – The ModelBuilder to add the bodies and joints to.

  • xform (transform) – The transform to apply to the imported mechanism.

  • density (float) – The density of the shapes in kg/m^3 which will be used to calculate the body mass and inertia.

  • stiffness (float) – The stiffness of the joints.

  • damping (float) – The damping of the joints.

  • contact_ke (float) – The stiffness of the shape contacts.

  • contact_kd (float) – The damping of the shape contacts.

  • contact_kf (float) – The friction stiffness of the shape contacts.

  • contact_ka (float) – The adhesion distance of the shape contacts.

  • contact_mu (float) – The friction coefficient of the shape contacts.

  • contact_restitution (float) – The restitution coefficient of the shape contacts.

  • contact_thickness (float) – The thickness to add to the shape geometry.

  • limit_ke (float) – The stiffness of the joint limits.

  • limit_kd (float) – The damping of the joint limits.

  • scale (float) – The scaling factor to apply to the imported mechanism.

  • armature (float) – Default joint armature to use if armature has not been defined for a joint in the MJCF.

  • armature_scale (float) – Scaling factor to apply to the MJCF-defined joint armature values.

  • parse_meshes (bool) – Whether geometries of type “mesh” should be parsed. If False, geometries of type “mesh” are ignored.

  • enable_self_collisions (bool) – If True, self-collisions are enabled.

  • up_axis (str) – The up axis of the mechanism. Can be either “X”, “Y” or “Z”. The default is “Z”.

  • ignore_classes (List[str]) – A list of regular expressions. Bodies and joints with a class matching one of the regular expressions will be ignored.

  • collapse_fixed_joints (bool) – If True, fixed joints are removed and the respective bodies are merged.

Note

The inertia and masses of the bodies are calculated from the shape geometry and the given density. The values defined in the MJCF are not respected at the moment.

The handling of advanced features, such as MJCF classes, is still experimental.

warp.sim.parse_usd(
source,
builder,
default_density=1.0e3,
only_load_enabled_rigid_bodies=False,
only_load_enabled_joints=True,
contact_ke=1e5,
contact_kd=250.0,
contact_kf=500.0,
contact_ka=0.0,
contact_mu=0.6,
contact_restitution=0.0,
contact_thickness=0.0,
joint_limit_ke=100.0,
joint_limit_kd=10.0,
armature=0.0,
invert_rotations=False,
verbose=False,
ignore_paths=None,
)[source]#

Parses a Universal Scene Description (USD) stage containing UsdPhysics schema definitions for rigid-body articulations and adds the bodies, shapes and joints to the given ModelBuilder.

The USD description has to be either a path (file name or URL), or an existing USD stage instance that implements the UsdStage interface.

Parameters:
  • source (str | pxr.UsdStage) – The file path to the USD file, or an existing USD stage instance.

  • builder (ModelBuilder) – The ModelBuilder to add the bodies and joints to.

  • default_density (float) – The default density to use for bodies without a density attribute.

  • only_load_enabled_rigid_bodies (bool) – If True, only rigid bodies which do not have physics:rigidBodyEnabled set to False are loaded.

  • only_load_enabled_joints (bool) – If True, only joints which do not have physics:jointEnabled set to False are loaded.

  • contact_ke (float) – The default contact stiffness to use, only considered by the Euler integrators.

  • contact_kd (float) – The default contact damping to use, only considered by the Euler integrators.

  • contact_kf (float) – The default friction stiffness to use, only considered by the Euler integrators.

  • contact_ka (float) – The default adhesion distance to use, only considered by the Euler integrators.

  • contact_mu (float) – The default friction coefficient to use if a shape has not friction coefficient defined.

  • contact_restitution (float) – The default coefficient of restitution to use if a shape has not coefficient of restitution defined.

  • contact_thickness (float) – The thickness to add to the shape geometry.

  • joint_limit_ke (float) – The default stiffness to use for joint limits, only considered by the Euler integrators.

  • joint_limit_kd (float) – The default damping to use for joint limits, only considered by the Euler integrators.

  • armature (float) – The armature to use for the bodies.

  • invert_rotations (bool) – If True, inverts any rotations defined in the shape transforms.

  • verbose (bool) – If True, print additional information about the parsed USD file.

  • ignore_paths (List[str]) – A list of regular expressions matching prim paths to ignore.

Returns:

Dictionary with the following entries:

”fps”

USD stage frames per second

”duration”

Difference between end time code and start time code of the USD stage

”up_axis”

Upper-case string of the stage’s up axis (“X”, “Y”, or “Z”)

”path_shape_map”

Mapping from prim path (str) of the UsdGeom to the respective shape index in ModelBuilder

”path_body_map”

Mapping from prim path (str) of a rigid body prim (e.g. that implements the PhysicsRigidBodyAPI) to the respective body index in ModelBuilder

”path_shape_scale”

Mapping from prim path (str) of the UsdGeom to its respective 3D world scale

”mass_unit”

The stage’s Kilograms Per Unit (KGPU) definition (1.0 by default)

”linear_unit”

The stage’s Meters Per Unit (MPU) definition (1.0 by default)

Return type:

dict

Note

This importer is experimental and only supports a subset of the USD Physics schema. Please report any issues you encounter.

warp.sim.resolve_usd_from_url(url, target_folder_name=None, export_usda=False)[source]#

Downloads a USD file from a URL and resolves all references to other USD files to be downloaded to the given target folder.

Parameters:
  • url (str) – URL to the USD file.

  • target_folder_name (str) – Target folder name. If None, a timestamped folder will be created in the current directory.

  • export_usda (bool) – If True, converts each downloaded USD file to USDA and saves the additional USDA file in the target folder with the same base name as the original USD file.

Returns:

File path to the downloaded USD file.

Return type:

str

Utility Functions#

Common utility functions used in simulators.

warp.sim.velocity_at_point(qd, r)#

Returns the velocity of a point relative to the frame with the given spatial velocity.

Parameters:
  • qd (spatial_vector) – The spatial velocity of the frame.

  • r (vec3) – The position of the point relative to the frame.

Returns:

The velocity of the point.

Return type:

vec3

warp.sim.quat_to_euler(q, i, j, k)#

Convert a quaternion into Euler angles.

\(i, j, k\) are the indices in \([0, 1, 2]\) of the axes to use (\(i \neq j, j \neq k\)).

Reference: https://journals.plos.org/plosone/article?id=10.1371/journal.pone.0276302

Parameters:
  • q (quat) – The quaternion to convert

  • i (int) – The index of the first axis

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

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

Returns:

The Euler angles (in radians)

Return type:

vec3

warp.sim.quat_from_euler(e, i, j, k)#

Convert Euler angles to a quaternion.

\(i, j, k\) are the indices in \([0, 1, 2]\) of the axes in which the Euler angles are provided (\(i \neq j, j \neq k\)), e.g. (0, 1, 2) for Euler sequence XYZ.

Parameters:
  • e (vec3) – The Euler angles (in radians)

  • i (int) – The index of the first axis

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

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

Returns:

The quaternion

Return type:

quat

warp.sim.load_mesh(filename, method=None)[source]#

Loads a 3D triangular surface mesh from a file.

Parameters:
  • filename (str) – The path to the 3D model file (obj, and other formats supported by the different methods) to load.

  • method (str) – The method to use for loading the mesh (default None). Can be either “trimesh”, “meshio”, “pcu”, or “openmesh”. If None, every method is tried and the first successful mesh import where the number of vertices is greater than 0 is returned.

Returns:

Tuple of (mesh_points, mesh_indices), where mesh_points is a Nx3 numpy array of vertex positions (float32), and mesh_indices is a Mx3 numpy array of vertex indices (int32) for the triangular faces.