newton.ModelBuilder#

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

Bases: object

A helper class for building simulation models at runtime.

Use the ModelBuilder to construct a simulation scene. The ModelBuilder represents the scene using standard Python data structures like lists, which are convenient but unsuitable for efficient simulation. Call finalize() to construct a simulation-ready Model.

Example

import newton
from newton.solvers import SolverXPBD

builder = newton.ModelBuilder()

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

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

# create model
model = builder.finalize()

state_0, state_1 = model.state(), model.state()
control = model.control()
solver = SolverXPBD(model)

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

Environment Grouping#

ModelBuilder supports environment grouping to organize entities for multi-environment simulations. Each entity (particle, body, shape, joint, articulation) has an associated group index:

  • Group -1: Global entities shared across all environments (e.g., ground plane)

  • Group 0, 1, 2, …: Environment-specific entities

There are two ways to assign environment groups:

  1. Direct entity creation: Entities inherit the builder’s current_env_group value:

    builder = ModelBuilder()
    builder.current_env_group = -1  # Following entities will be global
    builder.add_ground_plane()
    builder.current_env_group = 0  # Following entities will be in environment 0
    builder.add_body(...)
    
  2. Using add_builder(): ALL entities from the sub-builder are assigned to the specified group:

    robot = ModelBuilder()
    robot.add_body(...)  # Group assignments here will be overridden
    
    main = ModelBuilder()
    main.add_builder(robot, environment=0)  # All robot entities -> group 0
    main.add_builder(robot, environment=1)  # All robot entities -> group 1
    

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.

class JointDofConfig(axis=Axis.X, limit_lower=-1e6, limit_upper=1e6, limit_ke=1e4, limit_kd=1e1, target=0.0, target_ke=0.0, target_kd=0.0, mode=JointMode.TARGET_POSITION, armature=1e-2, effort_limit=1e6, velocity_limit=1e6, friction=0.0)#

Bases: object

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

classmethod create_unlimited(axis)#

Creates a JointDofConfig with no limits.

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

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

axis#

The 3D axis that this JointDofConfig object describes.

effort_limit#

Maximum effort (force or torque) the joint axis can exert. Defaults to 1e6.

friction#

Friction coefficient for the joint axis. Defaults to 0.0.

limit_kd#

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

limit_ke#

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

limit_lower#

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

limit_upper#

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

mode#

The mode of the joint axis (e.g., JointMode.TARGET_POSITION or JointMode.TARGET_VELOCITY). Defaults to JointMode.TARGET_POSITION.

target#

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

target_kd#

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

target_ke#

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

velocity_limit#

Maximum velocity the joint axis can achieve. Defaults to 1e6.

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

Bases: object

Represents the properties of a collision shape used in simulation.

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

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

collision_group: int = -1#

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

density: float = 1000.0#

The density of the shape material.

property flags: int#

Returns the flags for the shape.

has_particle_collision: bool = True#

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

has_shape_collision: bool = True#

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

is_solid: bool = True#

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

is_visible: bool = True#

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

ka: float = 0.0#

The contact adhesion distance.

kd: float = 1000.0#

The contact damping stiffness.

ke: float = 100000.0#

The contact elastic stiffness.

kf: float = 1000.0#

The contact friction stiffness.

mu: float = 0.5#

The coefficient of friction.

restitution: float = 0.0#

The coefficient of restitution.

thickness: float = 1e-05#

The thickness of the shape.

__init__(up_axis=Axis.Z, gravity=-9.81)#

Initializes a new ModelBuilder instance for constructing simulation models.

Parameters:
  • up_axis (AxisType, optional) – The axis to use as the “up” direction in the simulation. Defaults to Axis.Z.

  • gravity (float, optional) – The magnitude of gravity to apply along the up axis. Defaults to -9.81.

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

Adds a rigid body to the model.

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

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

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

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

  • mass (float) – Mass of the body.

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

Returns:

The index of the body in the model.

Return type:

int

Note

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

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

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

Environment Group Behavior: When adding a builder, ALL entities from the source builder will be assigned to the same environment group, overriding any group assignments that existed in the source builder. This ensures that all entities from a sub-builder are grouped together as a single environment.

Environment groups automatically handle collision filtering between different environments: - Entities from different environments (except -1) do not collide with each other - Global entities (group -1) collide with all environments - Collision groups from the source builder are preserved as-is for fine-grained collision control within each environment

To create global entities that are shared across all environments, set the main builder’s current_env_group to -1 before adding entities directly (not via add_builder).

Example:

main_builder = ModelBuilder()
# Create global ground plane
main_builder.current_env_group = -1
main_builder.add_ground_plane()

# Create robot builder
robot_builder = ModelBuilder()
robot_builder.add_body(...)  # These group assignments will be overridden

# Add multiple robot instances
main_builder.add_builder(robot_builder, environment=0)  # All entities -> group 0
main_builder.add_builder(robot_builder, environment=1)  # All entities -> group 1
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 updated appropriately. For non-global entities (environment >= 0), this either increments num_envs (when environment is None) or ensures num_envs is at least environment+1. Global entities (environment=-1) do not affect num_envs.

  • environment (int | None) – environment group index to assign to ALL entities from this builder. If None, uses the current environment count as the group index. Use -1 for global entities. Note: environment=-1 does not increase num_envs even when update_num_env_count=True.

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

Helper to create a regular planar cloth grid

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

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

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

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

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

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

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

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

  • mass (float) – The mass of each particle

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

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

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

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

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

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

Helper to create a cloth model from a regular triangle mesh

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

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

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

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

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

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

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

  • edge_callback – A user callback when an edge is created

  • face_callback – A user callback when a face is created

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

Note

The mesh should be two manifold.

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

Adds a bending edge element between two adjacent triangles in the cloth mesh, defined by four vertices.

The bending energy model follows the discrete shell formulation from [Grinspun et al. 2003]. The bending stiffness is controlled by the edge_ke parameter, and the bending damping by the edge_kd 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 | None) – The bending stiffness coefficient

  • edge_kd (float | None) – The bending damping coefficient

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 counterclockwise winding: (i, k, l), (j, l, k).

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

Adds bending edge elements between two adjacent triangles in the cloth mesh, defined by four vertices.

The bending energy model follows the discrete shell formulation from [Grinspun et al. 2003]. The bending stiffness is controlled by the edge_ke parameter, and the bending damping by the edge_kd 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) – The bending stiffness coefficient

  • edge_kd (list[float] | None) – The bending damping coefficient

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 counterclockwise winding: (i, k, l), (j, l, k).

add_equality_constraint(constraint_type, body1=-1, body2=-1, anchor=None, torquescale=None, relpose=None, joint1=-1, joint2=-1, polycoef=None, key=None, enabled=True)#

Generic method to add any type of equality constraint to this ModelBuilder.

Parameters:
  • constraint_type (constant) – Type of constraint (‘connect’, ‘weld’, ‘joint’)

  • body1 (int) – Index of the first body participating in the constraint (-1 for world)

  • body2 (int) – Index of the second body participating in the constraint (-1 for world)

  • anchor (Vec3) – Anchor point on body1

  • torquescale (float) – Scales the angular residual for weld

  • relpose (Transform) – Relative pose of body2 for weld. If None, the identity transform is used.

  • joint1 (int) – Index of the first joint for joint coupling

  • joint2 (int) – Index of the second joint for joint coupling

  • polycoef (list[float]) – Polynomial coefficients for joint coupling

  • key (str) – Optional constraint name

  • enabled (bool) – Whether constraint is active

Returns:

Constraint index

Return type:

int

add_equality_constraint_connect(body1=-1, body2=-1, anchor=None, key=None, enabled=True)#

Adds a connect equality constraint to the model. This constraint connects two bodies at a point. It effectively defines a ball joint outside the kinematic tree.

Parameters:
  • body1 (int) – Index of the first body participating in the constraint (-1 for world)

  • body2 (int) – Index of the second body participating in the constraint (-1 for world)

  • anchor (list[float] | tuple[float, float, float] | vec3f | None) – Anchor point on body1

  • key (str | None) – Optional constraint name

  • enabled (bool) – Whether constraint is active

Returns:

Constraint index

Return type:

int

add_equality_constraint_joint(joint1=-1, joint2=-1, polycoef=None, key=None, enabled=True)#

Adds a joint equality constraint to the model. Constrains the position or angle of one joint to be a quartic polynomial of another joint. Only scalar joint types (prismatic and revolute) can be used.

Parameters:
  • joint1 (int) – Index of the first joint

  • joint2 (int) – Index of the second joint

  • polycoef (list[float] | None) – Polynomial coefficients for joint coupling

  • key (str | None) – Optional constraint name

  • enabled (bool) – Whether constraint is active

Returns:

Constraint index

Return type:

int

add_equality_constraint_weld(body1=-1, body2=-1, anchor=None, torquescale=None, relpose=None, key=None, enabled=True)#

Adds a weld equality constraint to the model. Attaches two bodies to each other, removing all relative degrees of freedom between them (softly).

Parameters:
  • body1 (int) – Index of the first body participating in the constraint (-1 for world)

  • body2 (int) – Index of the second body participating in the constraint (-1 for world)

  • anchor (list[float] | tuple[float, float, float] | vec3f | None) – Coordinates of the weld point relative to body2

  • torquescale (float | None) – Scales the angular residual for weld

  • relpose (Transform) – Relative pose of body2 relative to body1. If None, the identity transform is used

  • key (str | None) – Optional constraint name

  • enabled (bool) – Whether constraint is active

Returns:

Constraint index

Return type:

int

add_free_joints_to_floating_bodies(new_bodies=None)#

Adds a free joint to every rigid body that is not a child in any joint and has positive mass.

Parameters:

new_bodies (Iterable[int] or None, optional) – The set of body indices to consider for adding free joints.

Note

  • Bodies that are already a child in any joint will be skipped.

  • Only bodies with strictly positive mass will receive a free joint.

  • This is useful for ensuring that all floating (unconnected) bodies are properly articulated.

add_ground_plane(cfg=None, key=None)#

Adds a ground plane collision shape to the model.

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

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

Returns:

The index of the newly added shape.

Return type:

int

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

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

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

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

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

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

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

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

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

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

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

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

Returns:

The index of the added joint.

Return type:

int

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

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

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

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

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

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

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

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

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

Returns:

The index of the added joint.

Return type:

int

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

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

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

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

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

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

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

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

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

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

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

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

Returns:

The index of the added joint.

Return type:

int

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

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

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

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

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

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

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

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

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

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

Returns:

The index of the added joint.

Return type:

int

Note

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

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

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

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

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

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

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

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

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

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

Returns:

The index of the added joint

Return type:

int

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

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

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

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

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

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

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

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

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

Returns:

The index of the added joint.

Return type:

int

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

  • effort_limit (float | None) – Maximum effort (force) the joint axis can exert. If None, the default value from default_joint_cfg.effort_limit is used.

  • velocity_limit (float | None) – Maximum velocity the joint axis can achieve. If None, the default value from default_joint_cfg.velocity_limit is used.

  • friction (float | None) – Friction coefficient for the joint axis. If None, the default value from default_joint_cfg.friction is used.

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

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

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

Returns:

The index of the added joint.

Return type:

int

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

  • effort_limit (float | None) – Maximum effort (force/torque) the joint axis can exert. If None, the default value from default_joint_cfg.effort_limit is used.

  • velocity_limit (float | None) – Maximum velocity the joint axis can achieve. If None, the default value from default_joint_cfg.velocity_limit is used.

  • friction (float | None) – Friction coefficient for the joint axis. If None, the default value from default_joint_cfg.friction is used.

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

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

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

Returns:

The index of the added joint.

Return type:

int

add_mjcf(source, xform=None, floating=None, base_joint=None, armature_scale=1.0, scale=1.0, hide_visuals=False, parse_visuals_as_colliders=False, parse_meshes=True, up_axis=Axis.Z, ignore_names=(), ignore_classes=(), visual_classes=('visual',), collider_classes=('collision',), no_class_as_colliders=True, force_show_colliders=False, enable_self_collisions=False, ignore_inertial_definitions=True, ensure_nonstatic_links=True, static_link_mass=1e-2, collapse_fixed_joints=False, verbose=False, skip_equality_constraints=False, mesh_maxhullvert=MESH_MAXHULLVERT)#

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

Parameters:
  • source (str) – The filename of the MuJoCo file to parse, or the MJCF XML string content.

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

  • floating (bool) – If True, the articulation is treated as a floating base. If False, the articulation is treated as a fixed base. If None, the articulation is treated as a floating base if a free joint is found in the MJCF, otherwise it is treated as a fixed base.

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

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

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

  • hide_visuals (bool) – If True, hide visual shapes.

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

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

  • up_axis (AxisType) – The up axis of the MuJoCo scene. The default is Z up.

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

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

  • visual_classes (Sequence[str]) – A list of regular expressions. Visual geometries with a class matching one of the regular expressions will be parsed.

  • collider_classes (Sequence[str]) – A list of regular expressions. Collision geometries with a class matching one of the regular expressions will be parsed.

  • no_class_as_colliders (bool) – If True, geometries without a class are parsed as collision geometries. If False, geometries without a class are parsed as visual 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 MJCF 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.

  • verbose (bool) – If True, print additional information about parsing the MJCF.

  • skip_equality_constraints (bool) – Whether <equality> tags should be parsed. If True, equality constraints are ignored.

  • mesh_maxhullvert (int) – Maximum vertices for convex hull approximation of meshes.

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

Adds a muscle-tendon activation unit.

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

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

  • f0 (float) – Force scaling

  • lm (float) – Muscle length

  • lt (float) – Tendon length

  • lmax (float) – Maximally efficient muscle length

Returns:

The index of the muscle in the model

Return type:

float

Note

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

add_particle(pos, vel, mass, radius=None, flags=ParticleFlags.ACTIVE)#

Adds a single particle to the model.

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

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

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

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

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

Note

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

Returns:

The index of the particle in the system.

Return type:

int

add_particle_grid(pos, rot, vel, dim_x, dim_y, dim_z, cell_x, cell_y, cell_z, mass, jitter, radius_mean=None, radius_std=0.0)#

Adds a regular 3D grid of particles to the model.

This helper function creates a grid of particles arranged in a rectangular lattice, with optional random jitter and per-particle radius variation. The grid is defined by its dimensions along each axis and the spacing between particles.

Parameters:
  • pos (Vec3) – The world-space position of the grid origin.

  • rot (Quat) – The rotation to apply to the grid (as a quaternion).

  • vel (Vec3) – The initial velocity to assign to each particle.

  • dim_x (int) – Number of particles along the X axis.

  • dim_y (int) – Number of particles along the Y axis.

  • dim_z (int) – Number of particles along the Z axis.

  • cell_x (float) – Spacing between particles along the X axis.

  • cell_y (float) – Spacing between particles along the Y axis.

  • cell_z (float) – Spacing between particles along the Z axis.

  • mass (float) – Mass to assign to each particle.

  • jitter (float) – Maximum random offset to apply to each particle position.

  • radius_mean (float, optional) – Mean radius for particles. If None, uses the builder’s default.

  • radius_std (float, optional) – Standard deviation for particle radii. If > 0, radii are sampled from a normal distribution.

Returns:

None

add_particles(pos, vel, mass, radius=None, flags=None)#

Adds a group particles to the model.

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

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

  • mass (list[float]) – The mass of the particles.

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

  • flags (list[uint32] | None) – The flags that control the dynamical behavior of the particles, see PARTICLE_FLAG_* constants.

Note

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

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

Adds a generic collision shape to the model.

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

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

  • type (int) – The geometry type of the shape (e.g., GeoType.BOX, GeoType.SPHERE).

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

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

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

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

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

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

Returns:

The index of the newly added shape.

Return type:

int

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

Adds a box collision shape to a body.

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

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

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

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

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

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

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

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

Returns:

The index of the newly added shape.

Return type:

int

add_shape_capsule(body, xform=None, radius=1.0, half_height=0.5, cfg=None, key=None)#

Adds a capsule collision shape to a body.

The capsule is centered at its local origin as defined by xform. Its length extends along the Z-axis.

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

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

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

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

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

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

Returns:

The index of the newly added shape.

Return type:

int

add_shape_cone(body, xform=None, radius=1.0, half_height=0.5, cfg=None, key=None)#

Adds a cone collision shape to a body.

The cone’s origin is at its geometric center, with the base at -half_height and apex at +half_height along the Z-axis. The center of mass is located at -half_height/2 from the origin (1/4 of the total height from the base toward the apex).

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

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

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

  • half_height (float) – The half-height of the cone (distance from the geometric center to either the base or apex). The total height is 2*half_height. Defaults to 0.5.

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

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

Returns:

The index of the newly added shape.

Return type:

int

add_shape_cylinder(body, xform=None, radius=1.0, half_height=0.5, cfg=None, key=None)#

Adds a cylinder collision shape to a body.

The cylinder is centered at its local origin as defined by xform. Its length extends along the Z-axis.

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

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

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

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

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

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

Returns:

The index of the newly added shape.

Return type:

int

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

Adds a triangle mesh collision shape to a body.

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

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

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

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

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

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

Returns:

The index of the newly added shape.

Return type:

int

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

Adds a plane collision shape to the model.

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

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

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

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

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

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

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

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

Returns:

The index of the newly added shape.

Return type:

int

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

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

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

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

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

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

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

Returns:

The index of the newly added shape.

Return type:

int

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

Adds a sphere collision shape to a body.

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

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

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

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

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

Returns:

The index of the newly added shape.

Return type:

int

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

Helper to create a rectangular tetrahedral FEM grid

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

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

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

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

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

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

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

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

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

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

  • density (float) – The density of each particle

  • k_mu (float) – The first elastic Lame parameter

  • k_lambda (float) – The second elastic Lame parameter

  • k_damp (float) – The damping stiffness

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

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

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

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

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

Helper to create a tetrahedral model from an input tetrahedral mesh

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

Adds a spring between two particles in the system

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

  • j – The index of the second particle

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

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

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

Note

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

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

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

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

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

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

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

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

  • k_mu (float) – The first elastic Lame parameter

  • k_lambda (float) – The second elastic Lame parameter

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

Returns:

The volume of the tetrahedron

Return type:

float

Note

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

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

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

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

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

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

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

Returns:

The area of the triangle

Return type:

float

Note

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

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

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

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

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

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

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

Returns:

The areas of the triangles

Return type:

list[float]

Note

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

add_urdf(source, xform=None, floating=False, base_joint=None, scale=1.0, hide_visuals=False, parse_visuals_as_colliders=False, up_axis=Axis.Z, 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, mesh_maxhullvert=MESH_MAXHULLVERT)#

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

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

  • xform (Transform) – The transform to apply to the root body. If None, the transform is set to identity.

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

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

  • hide_visuals (bool) – If True, hide visual shapes.

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

  • up_axis (AxisType) – The up axis of the URDF. This is used to transform the URDF to the builder’s up axis. It also determines the up axis of capsules and cylinders in the URDF. The default is Z.

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

  • mesh_maxhullvert (int) – Maximum vertices for convex hull approximation of meshes.

add_usd(source, xform=None, only_load_enabled_rigid_bodies=False, only_load_enabled_joints=True, joint_drive_gains_scaling=1.0, invert_rotations=True, verbose=False, ignore_paths=None, cloned_env=None, collapse_fixed_joints=False, enable_self_collisions=True, apply_up_axis_from_stage=False, root_path='/', joint_ordering='dfs', bodies_follow_joint_ordering=True, skip_mesh_approximation=False, load_non_physics_prims=True, hide_collision_shapes=False, mesh_maxhullvert=MESH_MAXHULLVERT)#

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 Stage interface.

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

  • xform (Transform) – The transform to apply to the entire scene.

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

  • joint_drive_gains_scaling (float) – The default scaling of the PD control gains (stiffness and damping), if not set in the PhysicsScene with as “newton:joint_drive_gains_scaling”.

  • 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. Default is False.

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

  • cloned_env (str) – The prim path of an environment which is cloned within this USD file. Siblings of this environment prim will not be parsed but instead be replicated via ModelBuilder.add_builder(builder, xform) to speed up the loading of many instantiated environments.

  • collapse_fixed_joints (bool) – If True, fixed joints are removed and the respective bodies are merged. Only considered if not set on the PhysicsScene as “newton:collapse_fixed_joints”.

  • enable_self_collisions (bool) – Determines the default behavior of whether self-collisions are enabled for all shapes within an articulation. If an articulation has the attribute physxArticulation:enabledSelfCollisions defined, this attribute takes precedence.

  • apply_up_axis_from_stage (bool) – If True, the up axis of the stage will be used to set newton.ModelBuilder.up_axis. Otherwise, the stage will be rotated such that its up axis aligns with the builder’s up axis. Default is False.

  • root_path (str) – The USD path to import, defaults to “/”.

  • joint_ordering (str) – The ordering of the joints in the simulation. Can be either “bfs” or “dfs” for breadth-first or depth-first search, or None to keep joints in the order in which they appear in the USD. Default is “dfs”.

  • bodies_follow_joint_ordering (bool) – If True, the bodies are added to the builder in the same order as the joints (parent then child body). Otherwise, bodies are added in the order they appear in the USD. Default is True.

  • skip_mesh_approximation (bool) – If True, mesh approximation is skipped. Otherwise, meshes are approximated according to the physics:approximation attribute defined on the UsdPhysicsMeshCollisionAPI (if it is defined). Default is False.

  • load_non_physics_prims (bool) – If True, prims that are children of a rigid body that do not have a UsdPhysics schema applied are loaded as visual shapes in a separate pass (may slow down the loading process). Otherwise, non-physics prims are ignored. Default is True.

  • hide_collision_shapes (bool) – If True, collision shapes are hidden. Default is False.

  • mesh_maxhullvert (int) – Maximum vertices for convex hull approximation of meshes.

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”

Axis representing 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)

”scene_attributes”

Dictionary of all attributes applied to the PhysicsScene prim

”collapse_results”

Dictionary returned by newton.ModelBuilder.collapse_fixed_joints() if collapse_fixed_joints is True, otherwise None.

Return type:

dict

approximate_meshes(method='convex_hull', shape_indices=None, raise_on_failure=False, **remeshing_kwargs)#

Approximates the mesh shapes of the model.

The following methods are supported:

Method

Description

"coacd"

Convex decomposition using CoACD

"vhacd"

Convex decomposition using V-HACD

"bounding_sphere"

Approximate the mesh with a sphere

"bounding_box"

Approximate the mesh with an oriented bounding box

"convex_hull"

Approximate the mesh with a convex hull (default)

<remeshing_method>

Any remeshing method supported by newton.geometry.remesh_mesh()

Note

The coacd and vhacd methods require additional dependencies (coacd or trimesh and vhacdx respectively) to be installed. The convex hull approximation requires scipy to be installed.

The raise_on_failure parameter controls the behavior when the remeshing fails:
  • If True, an exception is raised when the remeshing fails.

  • If False, a warning is logged, and the method falls back to the next available method in the order of preference:
    • If convex decomposition via CoACD or V-HACD fails or dependencies are not available, the method will fall back to using the convex_hull method.

    • If convex hull approximation fails, it will fall back to the bounding_box method.

Parameters:
  • method (Literal['coacd', 'vhacd', 'bounding_sphere', 'bounding_box', 'ftetwild', 'alphashape', 'quadratic', 'convex_hull']) – The method to use for approximating the mesh shapes.

  • shape_indices (list[int] | None) – The indices of the shapes to simplify. If None, all mesh shapes that have the ShapeFlags.COLLIDE_SHAPES flag set are simplified.

  • raise_on_failure (bool) – If True, raises an exception if the remeshing fails. If False, it will log a warning and continue with the fallback method.

  • **remeshing_kwargs (dict[str, Any]) – Additional keyword arguments passed to the remeshing function.

Returns:

A set of indices of the shapes that were successfully remeshed.

Return type:

set[int]

collapse_fixed_joints(verbose=wp.config.verbose)#

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

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

Runs coloring algorithm to generate coloring information.

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

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

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

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

Note

References to the coloring algorithm:

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

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

finalize(device=None, requires_grad=False)#

Finalize the builder and create a concrete Model for simulation.

This method transfers all simulation data from the builder to device memory, returning a Model object ready for simulation. It should be called after all elements (particles, bodies, shapes, joints, etc.) have been added to the builder.

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

  • requires_grad (bool) – If True, enables gradient computation for the model (for differentiable simulation).

Returns:

A fully constructed Model object containing all simulation data on the specified device.

Return type:

Model

Notes

  • Performs validation and correction of rigid body inertia and mass properties.

  • Closes all start-index arrays (e.g., for muscles, joints, articulations) with sentinel values.

  • Sets up all arrays and properties required for simulation, including particles, bodies, shapes, joints, springs, muscles, constraints, and collision/contact data.

find_shape_contact_pairs(model)#

Identifies and stores all potential shape contact pairs for collision detection.

This method examines the collision groups and collision masks of all shapes in the model to determine which pairs of shapes should be considered for contact generation. It respects any user-specified collision filter pairs to avoid redundant or undesired contacts.

The resulting contact pairs are stored in the model as a 2D array of shape indices.

Parameters:

model (Model) – The simulation model to which the contact pairs will be assigned.

Side Effects:
  • Sets model.shape_contact_pairs to a wp.array of shape pairs (wp.vec2i).

  • Sets model.shape_contact_pair_count to the number of contact pairs found.

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

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

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

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

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

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

  • show_shape_keys (bool) – Whether to show the shape keys or indices

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

  • show_legend (bool) – Whether to show a legend

replicate(builder, num_copies, spacing=(5.0, 5.0, 0.0))#

Replicates the given builder multiple times, offsetting each copy according to the supplied spacing.

This method is useful for creating multiple instances of a sub-model (e.g., robots, environments) arranged in a regular grid or along a line. Each copy is offset in space by a multiple of the specified spacing vector, and all entities from each copy are assigned to a new environment group.

Parameters:
  • builder (ModelBuilder) – The builder to replicate. All entities from this builder will be copied.

  • num_copies (int) – The number of copies to create.

  • spacing (tuple[float, float, float], optional) – The spacing between each copy along each axis. For example, (5.0, 5.0, 0.0) arranges copies in a 2D grid in the XY plane. Defaults to (5.0, 5.0, 0.0).

set_coloring(particle_color_groups)#

Sets coloring information with user-provided coloring.

Parameters:

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

property articulation_count#

The number of articulations in the model.

balance_inertia#

Whether to automatically correct rigid body inertia tensors that violate the triangle inequality. When True, adds a scalar multiple of the identity matrix to preserve rotation structure while ensuring physical validity (I1 + I2 >= I3 for principal moments). Default: True.

property body_count#

The number of rigid bodies in the model.

bound_inertia#

Minimum allowed eigenvalue for rigid body inertia tensors. If set, ensures all principal moments of inertia are at least this value. Set to None to disable inertia eigenvalue clamping. Default: None.

bound_mass#

Minimum allowed mass value for rigid bodies. If set, any body mass below this value will be clamped to this minimum. Set to None to disable mass clamping. Default: None.

property edge_count#

The number of edges (for bending) in the model.

property joint_count#

The number of joints in the model.

property muscle_count#

The number of muscles in the model.

property particle_count#

The number of particles in the model.

property shape_count#

The number of shapes in the model.

property spring_count#

The number of springs in the model.

property tet_count#

The number of tetrahedra in the model.

property tri_count#

The number of triangles in the model.

property up_vector: list[float] | tuple[float, float, float] | vec3f#

Returns the 3D unit vector corresponding to the current up axis (read-only).

This property computes the up direction as a 3D vector based on the value of up_axis. For example, if up_axis is Axis.Z, this returns (0, 0, 1).

Returns:

The 3D up vector corresponding to the current up axis.

Return type:

Vec3

validate_inertia_detailed#

Whether to use detailed (slower) inertia validation that provides per-body warnings. When False, uses a fast GPU kernel that reports only the total number of corrected bodies and directly assigns the corrected arrays to the Model (ModelBuilder state is not updated). When True, uses a CPU implementation that reports specific issues for each body and updates the ModelBuilder’s internal state. Default: False.