API Reference¶
Core Data Structures¶
- class newton.Model(device=None)¶
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:
- num_envs¶
Number of articulation environments that were added to the ModelBuilder via add_builder
- Type:
- 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_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
- shape_transform¶
Rigid shape transforms, shape [shape_count, 7], float
- Type:
array
- shape_flags¶
Rigid shape flags, shape [shape_count], uint32
- Type:
array
- shape_body¶
Rigid shape body index, shape [shape_count], int
- Type:
array
- 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_collision_radius¶
Collision radius of each shape used for bounding sphere broadphase collision checking, shape [shape_count], float
- Type:
array
- 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_rest_length¶
Bending edge rest length, 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
- 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.
- 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
- Type:
array
- joint_limit_lower¶
Joint lower position limits, shape [joint_axis_count], float
- Type:
array
- joint_limit_upper¶
Joint upper position limits, shape [joint_axis_count], float
- Type:
array
- joint_limit_ke¶
Joint position limit stiffness (used by the Euler integrators), shape [joint_axis_count], float
- Type:
array
- joint_limit_kd¶
Joint position limit damping (used by the Euler integrators), shape [joint_axis_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 (note the last value is an additional sentinel entry to allow for querying the q dimensionality of joint i via
joint_q_start[i+1] - joint_q_start[i]
), shape [joint_count + 1], int- Type:
array
- joint_qd_start¶
Start index of the first velocity coordinate per joint (note the last value is an additional sentinel entry to allow for querying the qd dimensionality of joint i via
joint_qd_start[i+1] - joint_qd_start[i]
), shape [joint_count + 1], int- Type:
array
- articulation_start¶
Articulation start index, shape [articulation_count], int
- Type:
array
- soft_contact_kf¶
Stiffness of friction force in soft contacts (used by the Euler integrators)
- Type:
- 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
- soft_contact_tids¶
- Type:
array
- rigid_contact_max¶
Maximum number of potential rigid body contact points to generate ignoring the rigid_mesh_contact_max limit.
- Type:
- rigid_contact_max_limited¶
Maximum number of potential rigid body contact points to generate respecting the rigid_mesh_contact_max limit.
- Type:
- rigid_mesh_contact_max¶
Maximum number of rigid body contact points to generate per mesh (0 = unlimited, default)
- Type:
- rigid_contact_torsional_friction¶
Torsional friction coefficient for rigid body contacts (used by
XPBDSolver
)- Type:
- rigid_contact_rolling_friction¶
Rolling friction coefficient for rigid body contacts (used by
XPBDSolver
)- Type:
- 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
- rigid_contact_tids¶
Triangle indices of the contact points, shape [rigid_contact_max], int
- Type:
array
- rigid_contact_pairwise_counter¶
Pairwise counter for contact generation, shape [rigid_contact_max], int
- Type:
array
- rigid_contact_broad_shape0¶
Broadphase shape index of shape 0 per contact, shape [rigid_contact_max], int
- Type:
array
- rigid_contact_broad_shape1¶
Broadphase shape index of shape 1 per contact, shape [rigid_contact_max], int
- Type:
array
- rigid_contact_point_id¶
Contact point ID, shape [rigid_contact_max], int
- Type:
array
- rigid_contact_point_limit¶
Contact point limit, shape [rigid_contact_max], int
- Type:
array
- 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
- gravity¶
Gravity vector, shape [3], float
- Type:
np.ndarray
- joint_coord_count¶
Total number of position degrees of freedom of all joints in the system
- Type:
- particle_color_groups¶
The coloring of all the particles, used for VBD’s Gauss-Seidel iteration. Each array contains indices of particles sharing the same color.
- Type:
list of array
- particle_colors¶
Contains the color assignment for every particle
- Type:
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)¶
- state(requires_grad=None)¶
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:
- control(requires_grad=None, clone_variables=True)¶
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:
- allocate_soft_contacts(count, requires_grad=False)¶
- count_contact_points()¶
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)¶
- property soft_contact_max¶
Maximum number of soft contacts that can be registered
- class newton.ModelBuilder(up_vector=(0.0, 1.0, 0.0), gravity=-9.81)¶
A helper class for building simulation models at runtime.
Use the ModelBuilder to construct a simulation scene. The ModelBuilder and builds the scene representation using standard Python data structures (lists), this means it is not differentiable. Once
finalize()
has been called the ModelBuilder transfers all data to Warp tensors and returns an object that may be used for simulation.Example
import newton 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("cuda") state = model.state() control = model.control() contact = model.contact() integrator = newton.XPBDSolver() for i in range(100): state.clear_forces() integrator.simulate(model, state, state, control, contact, dt=1.0 / 60.0)
Note
It is strongly recommended to use the ModelBuilder to construct a simulation rather than creating your own Model object directly, however it is possible to do so if desired.
- Parameters:
up_vector (Vec3)
gravity (float)
- 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.81)¶
- property shape_count¶
- property body_count¶
- property joint_count¶
- property joint_axis_count¶
- property particle_count¶
- property tri_count¶
- property tet_count¶
- property edge_count¶
- property spring_count¶
- property muscle_count¶
- property articulation_count¶
- add_builder(builder, xform=None, update_num_env_count=True, separate_collision_group=True)¶
Copies the data from builder, another ModelBuilder to this ModelBuilder.
- Parameters:
builder (ModelBuilder) – a model builder to add model data from.
xform (transform) – offset transform applied to root bodies.
update_num_env_count (bool) – if True, the number of environments is incremented by 1.
separate_collision_group (bool) – if True, the shapes from the articulations in builder will all be put into a single new collision group, otherwise, only the shapes in collision group > -1 will be moved to a new group.
- add_body(origin=None, armature=0.0, com=None, I_m=None, mass=0.0, key=None)¶
Adds a rigid body to the model.
- Parameters:
origin (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) – Artificial inertia added to the body.
com (list[float] | tuple[float, float, float] | vec3f | None) – The center of mass of the body w.r.t its origin.
I_m (list[float] | mat33f | None) – The 3x3 inertia tensor of the body (specified relative to the center of mass).
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:
Note
If the mass is zero then the body is treated as kinematic with no dynamics.
- add_joint(joint_type, parent, child, linear_axes=None, angular_axes=None, key=None, parent_xform=None, child_xform=None, linear_compliance=0.0, angular_compliance=0.0, armature=1e-2, 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 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 (seeJointAxis
) of the jointangular_axes (list(
JointAxis
)) – The angular axes (seeJointAxis
) of the jointkey (str) – The key 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:
- 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=None, limit_kd=None, linear_compliance=0.0, angular_compliance=0.0, armature=1e-2, 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 (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 | None) – The stiffness of the joint limit (None to use the default value
default_joint_limit_ke
)limit_kd (float | None) – The damping of the joint limit (None to use the default value
default_joint_limit_kd
)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
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
mode (int)
- Returns:
The index of the added joint
- Return type:
- 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=None, limit_kd=None, linear_compliance=0.0, angular_compliance=0.0, armature=1e-2, 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 (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 | None) – The stiffness of the joint limit (None to use the default value
default_joint_limit_ke
)limit_kd (float | None) – The damping of the joint limit (None to use the default value
default_joint_limit_ke
)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
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
mode (int)
- Returns:
The index of the added joint
- Return type:
- add_joint_ball(parent, child, parent_xform=None, child_xform=None, linear_compliance=0.0, angular_compliance=0.0, armature=1e-2, 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
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)
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:
- add_joint_fixed(parent, child, parent_xform=None, child_xform=None, linear_compliance=0.0, angular_compliance=0.0, armature=1e-2, 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
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)
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:
- add_joint_free(child, parent_xform=None, child_xform=None, armature=0.0, 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 (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)
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:
- 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)¶
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:
Note
Distance joints are currently only supported in the
XPBDSolver
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, key=None, collision_filter_parent=True, enabled=True)¶
Adds a universal joint to the model. U-joints have two degrees of freedom, one for each axis.
- Parameters:
parent (int) – The index of the parent body
child (int) – The index of the child body
axis_0 (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
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:
- 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, key=None, collision_filter_parent=True, enabled=True)¶
Adds a compound joint to the model, which has 3 degrees of freedom, one for each axis. Similar to the ball joint (see
add_ball_joint()
), the compound joint allows bodies to move in a 3D rotation relative to each other, except that the rotation is defined by 3 axes instead of a quaternion. Depending on the choice of axes, the orientation can be specified through Euler angles, e.g. z-x-z or x-y-x, or through a Tait-Bryan angle sequence, e.g. z-y-x or x-y-z.- Parameters:
parent (int) – The index of the parent body
child (int) – The index of the child body
axis_0 (3D vector or JointAxis) – The first axis of the joint, can be a JointAxis object whose settings will be used instead of the other arguments
axis_1 (3D vector or JointAxis) – The second axis of the joint, can be a JointAxis object whose settings will be used instead of the other arguments
axis_2 (3D vector or JointAxis) – The third axis of the joint, can be a JointAxis object whose settings will be used instead of the other arguments
parent_xform (transform) – The transform of the joint in the parent body’s local frame
child_xform (transform) – The transform of the joint in the child body’s local frame
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
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:
- add_joint_d6(parent, child, linear_axes=None, angular_axes=None, key=None, parent_xform=None, child_xform=None, linear_compliance=0.0, angular_compliance=0.0, armature=1e-2, 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 (list[JointAxis] | None) – A list of linear axes
angular_axes (list[JointAxis] | 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
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_keys=True, show_joint_keys=True, show_joint_types=True, plot_shapes=True, show_shape_types=True, show_legend=True)¶
Visualizes the model’s articulation graph using matplotlib and networkx. Uses the spring layout algorithm from networkx to arrange the nodes. Bodies are shown as orange squares, shapes are shown as blue circles.
- Parameters:
show_body_keys (bool) – Whether to show the body keys or indices
show_joint_keys (bool) – Whether to show the joint keys or indices
show_joint_types (bool) – Whether to show the joint types
plot_shapes (bool) – Whether to render the shapes connected to the rigid bodies
show_shape_types (bool) – Whether to show the shape geometry types
show_legend (bool) – Whether to show a legend
- collapse_fixed_joints(verbose=wp.config.verbose)¶
Removes fixed joints from the model and merges the bodies they connect. This is useful for simplifying the model for faster and more stable simulation.
- add_muscle(bodies, positions, f0, lm, lt, lmax, pen)¶
Adds a muscle-tendon activation unit.
- Parameters:
bodies (list[int]) – A list of body indices for each waypoint
positions (list[list[float] | tuple[float, float, float] | vec3f]) – A list of positions of each waypoint in the body’s local frame
f0 (float) – Force scaling
lm (float) – Muscle length
lt (float) – Tendon length
lmax (float) – Maximally efficient muscle length
pen (float)
- Returns:
The index of the muscle in the model
- Return type:
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, key=None)¶
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] | tuple[float, float, float, float] | vec4f) – The plane equation in form a*x + b*y + c*z + d = 0
pos (list[float] | tuple[float, float, float] | vec3f | None) – The position of the plane in world coordinates
rot (list[float] | tuple[float, float, float, float] | quatf | 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
key (str | None) – The key 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, key=None)¶
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] | tuple[float, float, float] | vec3f) – The location of the shape with respect to the parent frame
rot (list[float] | tuple[float, float, float, float] | quatf) – 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
key (str | None) – The key of the shape
- 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, key=None)¶
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] | tuple[float, float, float] | vec3f) – The location of the shape with respect to the parent frame
rot (list[float] | tuple[float, float, float, float] | quatf) – 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
key (str | None) – The key of the shape
- 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, key=None)¶
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] | tuple[float, float, float] | vec3f) – The location of the shape with respect to the parent frame
rot (list[float] | tuple[float, float, float, float] | quatf) – 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
key (str | None) – The key of the shape
- 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, key=None)¶
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] | tuple[float, float, float] | vec3f) – The location of the shape with respect to the parent frame
rot (list[float] | tuple[float, float, float, float] | quatf) – 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
key (str | None) – The key of the shape
- Returns:
The index of the added shape
- 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, key=None)¶
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] | tuple[float, float, float] | vec3f) – The location of the shape with respect to the parent frame
rot (list[float] | tuple[float, float, float, float] | quatf) – 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
key (str | None) – The key of the shape
- Returns:
The index of the added shape
- 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, 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 static shapes)
pos (list[float] | tuple[float, float, float] | vec3f | 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] | tuple[float, float, float, float] | quatf | 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] | tuple[float, float, float] | vec3f | 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
key (str | None) – The key of the shape
- 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, key=None)¶
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] | tuple[float, float, float] | vec3f) – The location of the shape with respect to the parent frame
rot (list[float] | tuple[float, float, float, float] | quatf) – The rotation of the shape with respect to the parent frame
sdf (SDF | None) – The sdf object
scale (list[float] | tuple[float, float, float] | vec3f) – 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
key (str | None) – The key of the shape
- Returns:
The index of the added shape
- add_particle(pos, vel, mass, radius=None, flags=PARTICLE_FLAG_ACTIVE)¶
Adds a single particle to the model
- Parameters:
pos (list[float] | tuple[float, float, float] | vec3f) – The initial position of the particle
vel (list[float] | tuple[float, float, float] | vec3f) – The initial velocity of the particle
mass (float) – The mass of the particle
radius (float | None) – The radius of the particle used in collision handling. If None, the radius is set to the default value (
default_particle_radius
).flags (uint32) – The flags that control the dynamical behavior of the particle, see PARTICLE_FLAG_* constants
- Return type:
Note
Set the mass equal to zero to create a ‘kinematic’ particle that does is not subject to dynamics.
- add_spring(i, j, ke, kd, control)¶
Adds a spring between two particles in the system
- Parameters:
Note
The spring is created with a rest-length based on the distance between the particles in their initial configuration.
- add_triangle(i, j, k, tri_ke=None, tri_ka=None, tri_kd=None, tri_drag=None, tri_lift=None)¶
Adds a triangular FEM element between three particles in the system.
Triangles are modeled as viscoelastic elements with elastic stiffness and damping parameters specified on the model. See model.tri_ke, model.tri_kd.
- Parameters:
- Returns:
The area of the triangle
- Return type:
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:
- Returns:
The areas of the triangles
- Return type:
Note
A triangle is created with a rest-length based on the distance between the particles in their initial configuration.
- add_tetrahedron(i, j, k, l, k_mu=1.0e3, k_lambda=1.0e3, k_damp=0.0)¶
Adds a tetrahedral FEM element between four particles in the system.
Tetrahedra are modeled as viscoelastic elements with a NeoHookean energy density based on [Smith et al. 2018].
- Parameters:
i (int) – The index of the first particle
j (int) – The index of the second particle
k (int) – The index of the third particle
l (int) – The index of the fourth particle
k_mu (float) – The first elastic Lame parameter
k_lambda (float) – The second elastic Lame parameter
k_damp (float) – The element’s damping stiffness
- Returns:
The volume of the tetrahedron
- Return type:
Note
The tetrahedron is created with a rest-pose based on the particle’s initial configuration
- add_edge(i, j, k, l, rest=None, edge_ke=None, edge_kd=None)¶
Adds a bending edge element between four particles in the system.
Bending elements are designed to be between two connected triangles. Then bending energy is based of [Bridson et al. 2002]. Bending stiffness is controlled by the model.tri_kb parameter.
- Parameters:
i (int) – The index of the first particle, i.e., opposite vertex 0
j (int) – The index of the second particle, i.e., opposite vertex 1
k (int) – The index of the third particle, i.e., vertex 0
l (int) – The index of the fourth particle, i.e., vertex 1
rest (float | None) – The rest angle across the edge in radians, if not specified it will be computed
edge_ke (float | None)
edge_kd (float | None)
- Return type:
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_edges(i, j, k, l, rest=None, edge_ke=None, edge_kd=None)¶
Adds bending edge elements between groups of four particles in the system.
Bending elements are designed to be between two connected triangles. Then bending energy is based of [Bridson et al. 2002]. Bending stiffness is controlled by the model.tri_kb parameter.
- Parameters:
i – The index of the first particle, i.e., opposite vertex 0
j – The index of the second particle, i.e., opposite vertex 1
k – The index of the third particle, i.e., vertex 0
l – The index of the fourth particle, i.e., vertex 1
rest (list[float] | None) – The rest angles across the edges in radians, if not specified they will be computed
- Return type:
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=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
tri_ke (float | None)
tri_ka (float | None)
tri_kd (float | None)
tri_drag (float | None)
tri_lift (float | None)
edge_ke (float | None)
edge_kd (float | None)
add_springs (bool)
spring_ke (float | None)
spring_kd (float | None)
particle_radius (float | None)
- 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.
scale (float)
tri_ke (float | None)
tri_ka (float | None)
tri_kd (float | None)
tri_drag (float | None)
tri_lift (float | None)
edge_ke (float | None)
edge_kd (float | None)
add_springs (bool)
spring_ke (float | None)
spring_kd (float | None)
- Return type:
None
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=None, radius_std=0.0)¶
- 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
tri_ke (float | None)
tri_ka (float | None)
tri_kd (float | None)
tri_drag (float | None)
tri_lift (float | None)
- 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:
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
vertices (list[list[float] | tuple[float, float, float] | vec3f]) – 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 | None)
tri_ka (float | None)
tri_kd (float | None)
tri_drag (float | None)
tri_lift (float | None)
- Return type:
None
- set_ground_plane(normal=None, offset=0.0, ke=None, kd=None, kf=None, mu=None, restitution=None)¶
Creates a ground plane for the world. If the normal is not specified, the up_vector of the ModelBuilder is used.
- set_coloring(particle_color_groups)¶
Sets coloring information with user-provided coloring.
- Parameters:
particle_color_groups – A list of list or np.array with dtype`=`int. The length of the list is the number of colors and each list or np.array contains the indices of vertices with this color.
- color(include_bending=False, balance_colors=True, target_max_min_color_ratio=1.1, coloring_algorithm=ColoringAlgorithm.MCS)¶
Runs coloring algorithm to generate coloring information.
- Parameters:
include_bending_energy – Whether to consider bending energy for trimeshes in the coloring process. If set to True, the generated graph will contain all the edges connecting o1 and o2; otherwise, the graph will be equivalent to the trimesh.
balance_colors – Whether to apply the color balancing algorithm to balance the size of each color
target_max_min_color_ratio – the color balancing algorithm will stop when the ratio between the largest color and the smallest color reaches this value
algorithm – Value should be an enum type of ColoringAlgorithm, otherwise it will raise an error. ColoringAlgorithm.mcs means using the MCS coloring algorithm, while ColoringAlgorithm.ordered_greedy means using the degree-ordered greedy algorithm. The MCS algorithm typically generates 30% to 50% fewer colors compared to the ordered greedy algorithm, while maintaining the same linear complexity. Although MCS has a constant overhead that makes it about twice as slow as the greedy algorithm, it produces significantly better coloring results. We recommend using MCS, especially if coloring is only part of the preprocessing.
Note
References to the coloring algorithm:
MCS: Pereira, F. M. Q., & Palsberg, J. (2005, November). Register allocation via coloring of chordal graphs. In Asian Symposium on Programming Languages and Systems (pp. 315-329). Berlin, Heidelberg: Springer Berlin Heidelberg.
Ordered Greedy: Ton-That, Q. M., Kry, P. G., & Andrews, S. (2023). Parallel block Neo-Hookean XPBD using graph clustering. Computers & Graphics, 110, 1-10.
- finalize(device=None, requires_grad=False)¶
Convert this builder object to a concrete model for simulation.
After building simulation elements this method should be called to transfer all data to device memory ready for simulation.
- Parameters:
device – 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:
- class newton.State¶
Time-varying state data for a
Model
.Time-varying state 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.- __init__()¶
- Return type:
None
- particle_q: array | None¶
Array of 3D particle positions with shape
(particle_count,)
and typevec3
.
- particle_qd: array | None¶
Array of 3D particle velocities with shape
(particle_count,)
and typevec3
.
- body_q: array | None¶
Array of body coordinates (7-dof transforms) in maximal coordinates with shape
(body_count,)
and typetransform
.
- body_qd: array | None¶
Array of body velocities in maximal coordinates (first three entries represent angular velocity, last three entries represent linear velocity) with shape
(body_count,)
and typespatial_vector
.
- body_f: array | None¶
Array of body forces in maximal coordinates (first three entries represent torque, last three entries represent linear force) with shape
(body_count,)
and typespatial_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 exceptFeatherstoneIntegrator
, which assumes the wrenches are measured w.r.t. world origin.
- joint_q: array | None¶
Array of generalized joint coordinates with shape
(joint_coord_count,)
and typefloat
.
- joint_qd: array | None¶
Array of generalized joint velocities with shape
(joint_dof_count,)
and typefloat
.
- clear_forces()¶
Clear all forces (for particles and bodies) in the state object.
- Return type:
None
- class newton.Control¶
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.- __init__()¶
- joint_act: array | None¶
Array of joint control inputs with shape
(joint_axis_count,)
and typefloat
.
- tri_activations: array | None¶
Array of triangle element activations with shape
(tri_count,)
and typefloat
.
- tet_activations: array | None¶
Array of tetrahedral element activations with shape with shape
(tet_count,) and type ``float
.
- muscle_activations: array | None¶
Array of muscle activations with shape
(muscle_count,)
and typefloat
.
- clear()¶
Reset the control inputs to zero.
- Return type:
None
- reset()¶
Reset the control inputs to zero.
- Return type:
None
Solvers¶
- class newton.solvers.SolverBase(model)¶
Generic base class for solvers. Provides methods to integrate rigid bodies and particles.
- Parameters:
model (Model)
- property device: Device¶
Get the device used by the solver.
- Returns:
The device used by the solver.
- Return type:
wp.Device
- integrate_bodies(model, state_in, state_out, dt, angular_damping=0.0)¶
Integrate the rigid bodies of the model.
- integrate_particles(model, state_in, state_out, dt)¶
Integrate the particles of the model.
- step(model, state_in, state_out, control, contacts, dt)¶
Simulate the model for a given time step using the given control input.
- Parameters:
model (Model) – The model to simulate.
state_in (State) – The input state.
state_out (State) – The output state.
control (Control) – The control input. Defaults to None which means the control values from the
Model
are used.contacts (Contact) – The contact information.
dt (float) – The time step (typically in seconds).
- class newton.solvers.XPBDSolver(model=None, 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)¶
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
, andControl
(optional) objects, this time-integrator may be used to advance the simulation state forward in time.Example
solver = newton.XPBDSolver(model) # simulation loop for i in range(100): solver.step(model, state_in, state_out, control, contacts, dt)
- Parameters:
model (Model)
- __init__(model=None, 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)¶
- Parameters:
model (Model)
- apply_particle_deltas(model, state_in, state_out, particle_deltas, dt)¶
- apply_body_deltas(model, state_in, state_out, body_deltas, dt, rigid_contact_inv_weight=None)¶
- step(model, state_in, state_out, control, contacts, dt)¶
Simulate the model for a given time step using the given control input.
- Parameters:
model (Model) – The model to simulate.
state_in (State) – The input state.
state_out (State) – The output state.
control (Control) – The control input. Defaults to None which means the control values from the
Model
are used.contacts (Contact) – The contact information.
dt (float) – The time step (typically in seconds).
- class newton.solvers.VBDSolver(model, iterations=10, handle_self_contact=False, penetration_free_conservative_bound_relaxation=0.42, friction_epsilon=1e-2, body_particle_contact_buffer_pre_alloc=4, vertex_collision_buffer_pre_alloc=32, edge_collision_buffer_pre_alloc=64, triangle_collision_buffer_pre_alloc=32, edge_edge_parallel_epsilon=1e-5)¶
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 VBDSolver’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 sameModel
object that you used that was used during construction. Currently, you must manually provide particle coloring and assign it to model.particle_color_groups to make VBD work.VBDSolver.simulate accepts three arguments: class:Model,
State
, andControl
(optional) objects, this time-integrator may be used to advance the simulation state forward in time.Example
model.particle_color_groups = # load or generate particle coloring solver = newton.VBDSolver(model) # simulation loop for i in range(100): solver.step(model, state_in, state_out, control, contacts, dt)
- Parameters:
model (Model)
- __init__(model, iterations=10, handle_self_contact=False, penetration_free_conservative_bound_relaxation=0.42, friction_epsilon=1e-2, body_particle_contact_buffer_pre_alloc=4, vertex_collision_buffer_pre_alloc=32, edge_collision_buffer_pre_alloc=64, triangle_collision_buffer_pre_alloc=32, edge_edge_parallel_epsilon=1e-5)¶
- Parameters:
model (Model)
- compute_force_element_adjacency(model)¶
- step(model, state_in, state_out, control, contacts, dt)¶
Simulate the model for a given time step using the given control input.
- Parameters:
model (Model) – The model to simulate.
state_in (State) – The input state.
state_out (State) – The output state.
control (Control) – The control input. Defaults to None which means the control values from the
Model
are used.contacts (Contact) – The contact information.
dt (float) – The time step (typically in seconds).
- simulate_one_step_no_self_contact(model, state_in, state_out, dt, control=None)¶
- simulate_one_step_with_collisions_penetration_free(model, state_in, state_out, dt, control=None)¶
- collision_detection_penetration_free(current_state, dt)¶
- rebuild_bvh(state)¶
This function will rebuild the BVHs used for detecting self-contacts using the input state.
When the simulated object deforms significantly, simply refitting the BVH can lead to deterioration of the BVH’s quality. In these cases, rebuilding the entire tree is necessary to achieve better querying efficiency.
- Parameters:
state (wp.sim.State) – The state whose particle positions (
State.particle_q
) will be used for rebuilding the BVHs.
- count_num_adjacent_edges = <warp.context.Kernel object>¶
- Parameters:
edges_array (array(ndim=2, dtype=int32))
num_vertex_adjacent_edges (array(ndim=1, dtype=int32))
- fill_adjacent_edges = <warp.context.Kernel object>¶
- Parameters:
edges_array (array(ndim=2, dtype=int32))
vertex_adjacent_edges_offsets (array(ndim=1, dtype=int32))
vertex_adjacent_edges_fill_count (array(ndim=1, dtype=int32))
vertex_adjacent_edges (array(ndim=1, dtype=int32))
- count_num_adjacent_faces = <warp.context.Kernel object>¶
- Parameters:
face_indices (array(ndim=2, dtype=int32))
num_vertex_adjacent_faces (array(ndim=1, dtype=int32))
- fill_adjacent_faces = <warp.context.Kernel object>¶
- Parameters:
face_indices (array(ndim=2, dtype=int32))
vertex_adjacent_faces_offsets (array(ndim=1, dtype=int32))
vertex_adjacent_faces_fill_count (array(ndim=1, dtype=int32))
vertex_adjacent_faces (array(ndim=1, dtype=int32))
- class newton.solvers.MuJoCoSolver(model, *, mjw_model=None, mjw_data=None, separate_envs_to_worlds=None, nefc_per_env=100, ncon_per_env=None, iterations=20, ls_iterations=10, solver='cg', integrator='euler', use_mujoco=False, disable_contacts=False, register_collision_groups=True, joint_damping=0.05, default_actuator_gear=None, actuator_gears=None, update_data_every=1, save_to_mjcf=None)¶
This solver provides an interface to simulate physics using the MuJoCo physics engine, optimized with GPU acceleration through mujoco_warp. It supports both MuJoCo and mujoco_warp backends, enabling efficient simulation of articulated systems with contacts and constraints.
Note
This solver requires mujoco_warp and its dependencies to be installed.
For installation instructions, see the mujoco_warp repository.
Example
solver = newton.MuJoCoSolver(model) # simulation loop for i in range(100): solver.step(model, state_in, state_out, control, contacts, dt)
- Parameters:
- __init__(model, *, mjw_model=None, mjw_data=None, separate_envs_to_worlds=None, nefc_per_env=100, ncon_per_env=None, iterations=20, ls_iterations=10, solver='cg', integrator='euler', use_mujoco=False, disable_contacts=False, register_collision_groups=True, joint_damping=0.05, default_actuator_gear=None, actuator_gears=None, update_data_every=1, save_to_mjcf=None)¶
- step(model, state_in, state_out, control, contacts, dt)¶
Simulate the model for a given time step using the given control input.
- Parameters:
- static apply_mjc_control(model, control, mj_data)¶
- static update_mjc_data(mj_data, model, state=None)¶
- static update_newton_state(model, state, mj_data, eval_fk=True)¶
- static convert_to_mjc(model, state=None, *, separate_envs_to_worlds=True, iterations=20, ls_iterations=10, nefc_per_env=100, ncon_per_env=None, solver='cg', integrator='euler', disableflags=0, impratio=1.0, tolerance=1e-8, ls_tolerance=0.01, timestep=0.01, cone=0, is_sparse=None, register_collision_groups=True, joint_limit_threshold=1e3, default_joint_damping=0.0, geom_solref=(0.02, 1.0), geom_solimp=(0.9, 0.95, 0.001, 0.5, 2.0), geom_friction=(1.0, 0.05, 0.05), geom_condim=3, target_filename=None, default_actuator_args=None, default_actuator_gear=None, actuator_gears=None, actuated_axes=None, skip_visual_only_geoms=True, add_axes=True)¶
Convert a Newton model and state to MuJoCo (Warp) model and data.
- Parameters:
Model (newton.Model) – The Newton model to convert.
State (newton.State) – The Newton state to convert.
model (Model)
state (State | None)
separate_envs_to_worlds (bool)
iterations (int)
ls_iterations (int)
nefc_per_env (int)
ncon_per_env (int | None)
disableflags (int)
impratio (float)
tolerance (float)
ls_tolerance (float)
timestep (float)
cone (int)
is_sparse (bool | None)
register_collision_groups (bool)
joint_limit_threshold (float)
default_joint_damping (float)
geom_condim (int)
target_filename (str | None)
default_actuator_args (dict | None)
default_actuator_gear (float | None)
add_axes (bool)
- Returns:
A tuple containing the model and data objects for
mujoco_warp
and MuJoCo.- Return type:
tuple[MjWarpModel, MjWarpData, MjModel, MjData]
Importers¶
Newton supports the loading of simulation models from URDF, MuJoCo (MJCF), and USD Physics files.
- newton.utils.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, hide_visuals=False, 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)¶
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.
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.
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.
- newton.utils.parse_mjcf(mjcf_filename, builder, xform=None, floating=False, base_joint=None, density=1000.0, stiffness=100.0, damping=10.0, armature=0.0, armature_scale=1.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, hide_visuals=False, parse_visuals_as_colliders=False, parse_meshes=True, up_axis='Z', ignore_names=(), ignore_classes=None, 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)¶
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.
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) – 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.
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.
joint_limit_lower (float) – The default lower joint limit if not specified in the MJCF.
joint_limit_upper (float) – The default upper joint limit if not specified in the MJCF.
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 (str) – The up axis of the mechanism. Can be either “X”, “Y” or “Z”. The default is “Z”.
ignore_names (List[str]) – A list of regular expressions. Bodies and joints with a name matching one of the regular expressions will be ignored.
ignore_classes (List[str]) – A list of regular expressions. Bodies and joints with a class matching one of the regular expressions will be ignored.
visual_classes (List[str]) – A list of regular expressions. Visual geometries with a class matching one of the regular expressions will be parsed.
collider_classes (List[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.
- newton.utils.parse_usd(source, builder, xform=None, default_density=1.0e3, only_load_enabled_rigid_bodies=False, only_load_enabled_joints=True, only_load_warp_scene=False, 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, joint_drive_gains_scaling=1.0, invert_rotations=False, verbose=wp.config.verbose, ignore_paths=None, cloned_env=None, collapse_fixed_joints=False, root_path='/')¶
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.xform (wp.transform) – The transform to apply to the entire scene.
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.
only_load_warp_scene (bool) – If True, only load bodies that belong to a PhysicsScene which is simulated by Warp as a simulation owner.
contact_ke (float) – The default contact stiffness to use, if not set on the primitive or the PhysicsScene with as “warp:contact_ke”. Only considered by the Euler integrators.
contact_kd (float) – The default contact damping to use, if not set on the primitive or the PhysicsScene with as “warp:contact_kd”. Only considered by the Euler integrators.
contact_kf (float) – The default friction stiffness to use, if not set on the primitive or the PhysicsScene with as “warp:contact_kf”. Only considered by the Euler integrators.
contact_ka (float) – The default adhesion distance to use, if not set on the primitive or the PhysicsScene with as “warp:contact_ka”. Only considered by the Euler integrators.
contact_mu (float) – The default friction coefficient to use if a shape has not friction coefficient defined in a PhysicsMaterial.
contact_restitution (float) – The default coefficient of restitution to use if a shape has not coefficient of restitution defined in a PhysicsMaterial.
contact_thickness (float) – The thickness to add to the shape geometry, if not set on the primitive or the PhysicsScene with as “warp:contact_thickness”.
joint_limit_ke (float) – The default stiffness to use for joint limits, if not set on the primitive or the PhysicsScene with as “warp:joint_limit_ke”. Only considered by the Euler integrators.
joint_limit_kd (float) – The default damping to use for joint limits, if not set on the primitive or the PhysicsScene with as “warp:joint_limit_kd”. Only considered by the Euler integrators.
armature (float) – The default armature to use for the bodies, if not set on the primitive or the PhysicsScene with as “warp:armature”.
joint_drive_gains_scaling (float) – The default scaling of the PD control gains (stiffness and damping), if not set in the PhysicsScene with as “warp: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.
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 newton.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 with as “warp:collapse_fixed_joints”.
root_path (str) – The USD path to import, defaults to “/”.
- 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)
”scene_attributes”
Dictionary of all attributes applied to the PhysicsScene prim
”collapse_results”
Dictionary returned by \(ModelBuilder.collapse_fixed_joints()\) if collapse_fixed_joints is True, otherwise None.
- Return type:
- newton.utils.import_usd.resolve_usd_from_url(url, target_folder_name=None, export_usda=False)¶
Download 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 | None) – Target folder name. If
None
, a time-stamped 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:
Collision Detection¶
Joint Types¶
- JOINT_PRISMATIC¶
Prismatic (slider) joint
- JOINT_REVOLUTE¶
Revolute (hinge) joint
- JOINT_BALL¶
Ball (spherical) joint with quaternion state representation
- JOINT_FIXED¶
Fixed (static) joint
- JOINT_FREE¶
Free (floating) joint
- JOINT_COMPOUND¶
Compound joint with 3 rotational degrees of freedom
- JOINT_UNIVERSAL¶
Universal joint with 2 rotational degrees of freedom
- JOINT_DISTANCE¶
Distance joint that keeps two bodies at a distance within its joint limits (only supported in
XPBDIntegrator
at the moment)
- 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:
- JOINT_MODE_FORCE¶
This is the default control mode where the control input is the torque \(\tau\) applied at the joint axis.
- 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
andModel.joint_target_kd
:\[\tau = k_e (\mathbf{q}_{\text{target}} - \mathbf{q}) - k_d \mathbf{\dot{q}}\]
- 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}})\]
Renderers¶
Based on the renderers from warp.render
, the newton.utils.SimRendererUsd
(which equals newton.utils.SimRenderer
) and
newton.utils.SimRendererOpenGL
classes from newton.utils.render
are derived to populate the renderers directly from
newton.ModelBuilder
scenes and update them from newton.State
objects.
- newton.utils.SimRendererUsd¶
alias of
SimRenderer
- newton.utils.SimRendererOpenGL¶
alias of
SimRenderer