newton.Model#
- class newton.Model(device=None)[source]#
Bases:
object
Represents the static (non-time-varying) definition of a simulation model in Newton.
The Model class encapsulates all geometry, constraints, and parameters that describe a physical system for simulation. It is designed to be constructed via the ModelBuilder, which handles the correct initialization and population of all fields.
- Key Features:
Stores all static data for simulation: particles, rigid bodies, joints, shapes, soft/rigid elements, etc.
Supports grouping of entities by environment using group indices (e.g., particle_group, body_group, etc.). - Group index -1: global entities shared across all environments. - Group indices 0, 1, 2, …: environment-specific entities.
Grouping enables: - Collision detection optimization (e.g., separating environments) - Visualization (e.g., spatially separating environments) - Parallel processing of independent environments
Note
It is strongly recommended to use the
ModelBuilder
to construct a Model. Direct instantiation and manual population of Model fields is possible but discouraged.- __init__(device=None)#
Initialize a Model object.
- Parameters:
device (wp.Device, optional) – Device on which the Model’s data will be allocated.
- add_attribute(name, attrib, frequency)#
Add a custom attribute to the model.
- Parameters:
- Raises:
AttributeError – If the attribute already exists, is not a wp.array, or is on the wrong device.
- collide(state, collision_pipeline=None, rigid_contact_max_per_pair=None, rigid_contact_margin=0.01, soft_contact_max=None, soft_contact_margin=0.01, edge_sdf_iter=10, iterate_mesh_vertices=True, requires_grad=None)#
Generate contact points for the particles and rigid bodies in the model.
This method produces a
Contacts
object containing collision/contact information for use in contact-dynamics kernels.- Parameters:
state (State) – The current state of the model.
collision_pipeline (CollisionPipeline, optional) – Collision pipeline to use for contact generation. If not provided, a new one will be created if it hasn’t been constructed before for this model.
rigid_contact_max_per_pair (int, optional) – Maximum number of rigid contacts per shape pair. If None, a kernel is launched to count the number of possible contacts.
rigid_contact_margin (float, optional) – Margin for rigid contact generation. Default is 0.01.
soft_contact_max (int, optional) – Maximum number of soft contacts. If None, a kernel is launched to count the number of possible contacts.
soft_contact_margin (float, optional) – Margin for soft contact generation. Default is 0.01.
edge_sdf_iter (int, optional) – Number of search iterations for finding closest contact points between edges and SDF. Default is 10.
iterate_mesh_vertices (bool, optional) – Whether to iterate over all vertices of a mesh for contact generation (used for capsule/box <> mesh collision). Default is True.
requires_grad (bool, optional) – Whether to duplicate contact arrays for gradient computation. If None, uses
Model.requires_grad
.
- Returns:
The contact object containing collision information.
- Return type:
- control(requires_grad=None, clone_variables=True)#
Create and return a new
Control
object for this model.The returned control object is initialized with the control inputs from the model description.
- Parameters:
requires_grad (bool, optional) – Whether the control variables should have requires_grad enabled. If None, uses the model’s
requires_grad
setting.clone_variables (bool) – If True, clone the control input arrays; if False, use references.
- Returns:
The initialized control object.
- Return type:
- get_attribute_frequency(name)#
Get the frequency of an attribute.
- Possible frequencies are:
“body”: per body
“joint”: per joint
“joint_coord”: per joint coordinate
“joint_dof”: per joint degree of freedom
“shape”: per shape
- Parameters:
name (str) – Name of the attribute.
- Returns:
The frequency of the attribute.
- Return type:
- Raises:
AttributeError – If the attribute frequency is not known.
- set_gravity(gravity)#
Set gravity for runtime modification.
- Parameters:
gravity (tuple[float, float, float] | list[float] | vec3f) – Gravity vector as a tuple, list, or wp.vec3. Common values: (0, 0, -9.81) for Z-up, (0, -9.81, 0) for Y-up.
Note
After calling this method, you should notify solvers via solver.notify_model_changed(SolverNotifyFlags.MODEL_PROPERTIES).
- state(requires_grad=None)#
Create and return a new
State
object for this model.The returned state is initialized with the initial configuration from the model description.
- Parameters:
requires_grad (bool, optional) – Whether the state variables should have requires_grad enabled. If None, uses the model’s
requires_grad
setting.- Returns:
The state object
- Return type:
- articulation_count#
Total number of articulations in the system.
- articulation_group#
Environment group index for each articulation, shape [articulation_count], int. -1 for global.
- articulation_key#
Articulation keys, shape [articulation_count], str.
- articulation_start#
Articulation start index, shape [articulation_count], int.
- attribute_frequency#
Classifies each attribute as per body, per joint, per DOF, etc.
- body_com#
Rigid body center of mass (in local frame), shape [body_count, 3], float.
- body_count#
Total number of bodies in the system.
- body_group#
Environment group index for each body, shape [body_count], int. Global entities have group index -1.
- body_inertia#
Rigid body inertia tensor (relative to COM), shape [body_count, 3, 3], float.
- body_inv_inertia#
Rigid body inverse inertia tensor (relative to COM), shape [body_count, 3, 3], float.
- body_inv_mass#
Rigid body inverse mass, shape [body_count], float.
- body_key#
Rigid body keys, shape [body_count], str.
- body_mass#
Rigid body mass, shape [body_count], float.
- body_q#
Rigid body poses for state initialization, shape [body_count, 7], float.
- body_qd#
Rigid body velocities for state initialization, shape [body_count, 6], float.
- body_shapes#
Mapping from body index to list of attached shape indices.
- device#
Device on which the Model was allocated.
- edge_bending_properties#
Bending edge stiffness and damping, shape [edge_count, 2], float.
- edge_constraint_lambdas#
Lagrange multipliers for edge constraints (internal use).
- edge_count#
Total number of edges in the system.
- edge_indices#
Bending edge indices, shape [edge_count*4], int, each row is [o0, o1, v1, v2], where v1, v2 are on the edge.
- edge_rest_angle#
Bending edge rest angle, shape [edge_count], float.
- edge_rest_length#
Bending edge rest length, shape [edge_count], float.
- equality_constraint_anchor#
Anchor point on first body, shape [equality_constraint_count, 3], float.
- equality_constraint_body1#
First body index, shape [equality_constraint_count], int.
- equality_constraint_body2#
Second body index, shape [equality_constraint_count], int.
- equality_constraint_count#
Total number of equality constraints in the system.
- equality_constraint_enabled#
Whether constraint is active, shape [equality_constraint_count], bool.
- equality_constraint_joint1#
First joint index, shape [equality_constraint_count], int.
- equality_constraint_joint2#
Second joint index, shape [equality_constraint_count], int.
- equality_constraint_key#
Constraint name/key, shape [equality_constraint_count], str.
- equality_constraint_polycoef#
Polynomial coefficients, shape [equality_constraint_count, 2], float.
- equality_constraint_relpose#
Relative pose, shape [equality_constraint_count, 7], float.
- equality_constraint_torquescale#
Torque scale, shape [equality_constraint_count], float.
- equality_constraint_type#
Type of equality constraint, shape [equality_constraint_count], int.
- gravity#
Gravity vector, shape [1], dtype vec3.
- joint_X_c#
Joint mass frame in child frame, shape [joint_count, 7], float.
- joint_X_p#
Joint transform in parent frame, shape [joint_count, 7], float.
- 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.
- joint_armature#
Armature for each joint axis (used by
SolverMuJoCo
andSolverFeatherstone
), shape [joint_dof_count], float.
- joint_axis#
Joint axis in child frame, shape [joint_dof_count, 3], float.
- joint_child#
Joint child body indices, shape [joint_count], int.
- joint_coord_count#
Total number of position degrees of freedom of all joints.
- joint_count#
Total number of joints in the system.
- joint_dof_count#
Total number of velocity degrees of freedom of all joints. Equals the number of joint axes.
- joint_dof_dim#
Number of linear and angular dofs per joint, shape [joint_count, 2], int.
- joint_dof_mode#
Control mode for each joint dof, shape [joint_dof_count], int.
- joint_effort_limit#
Joint effort (force/torque) limits, shape [joint_dof_count], float.
- joint_enabled#
Controls which joint is simulated (bodies become disconnected if False), shape [joint_count], int.
- joint_f#
Generalized joint forces for state initialization, shape [joint_dof_count], float.
- joint_friction#
Joint friction coefficient, shape [joint_dof_count], float.
- joint_group#
Environment group index for each joint, shape [joint_count], int. -1 for global.
- joint_key#
Joint keys, shape [joint_count], str.
- joint_limit_kd#
Joint position limit damping (used by
SolverSemiImplicit
andSolverFeatherstone
), shape [joint_dof_count], float.
- joint_limit_ke#
Joint position limit stiffness (used by
SolverSemiImplicit
andSolverFeatherstone
), shape [joint_dof_count], float.
- joint_limit_lower#
Joint lower position limits, shape [joint_dof_count], float.
- joint_limit_upper#
Joint upper position limits, shape [joint_dof_count], float.
- joint_parent#
Joint parent body indices, shape [joint_count], int.
- joint_q#
Generalized joint positions for state initialization, shape [joint_coord_count], float.
- joint_q_start#
Start index of the first position coordinate per joint (last value is a sentinel for dimension queries), shape [joint_count + 1], int.
- joint_qd#
Generalized joint velocities for state initialization, shape [joint_dof_count], float.
- joint_qd_start#
Start index of the first velocity coordinate per joint (last value is a sentinel for dimension queries), shape [joint_count + 1], int.
- joint_target#
Generalized joint target inputs, shape [joint_dof_count], float.
- joint_target_kd#
Joint damping, shape [joint_dof_count], float.
- joint_target_ke#
Joint stiffness, shape [joint_dof_count], float.
- joint_twist_lower#
Joint lower twist limit, shape [joint_count], float.
- joint_twist_upper#
Joint upper twist limit, shape [joint_count], float.
- joint_type#
Joint type, shape [joint_count], int.
- joint_velocity_limit#
Joint velocity limits, shape [joint_dof_count], float.
- max_joints_per_articulation#
Maximum number of joints in any articulation (used for IK kernel dimensioning).
- muscle_activations#
Muscle activations, shape [muscle_count], float.
- muscle_bodies#
Body indices of the muscle waypoints, int.
- muscle_count#
Total number of muscles in the system.
- muscle_params#
Muscle parameters, shape [muscle_count, 5], float.
- muscle_points#
Local body offset of the muscle waypoints, float.
- muscle_start#
Start index of the first muscle point per muscle, shape [muscle_count], int.
- num_envs#
Number of articulation environments added to the ModelBuilder via add_builder.
- particle_adhesion#
Particle adhesion strength.
- particle_cohesion#
Particle cohesion strength.
- particle_color_groups#
Coloring of all particles for Gauss-Seidel iteration (see
SolverVBD
). Each array contains indices of particles sharing the same color.
- particle_colors#
Color assignment for every particle.
- particle_count#
Total number of particles in the system.
- particle_flags#
Particle enabled state, shape [particle_count], int.
- particle_grid#
HashGrid instance for accelerated simulation of particle interactions.
- particle_group#
Environment group index for each particle, shape [particle_count], int. -1 for global.
- particle_inv_mass#
Particle inverse mass, shape [particle_count], float.
- particle_kd#
Particle normal contact damping (used by
SolverSemiImplicit
).
- particle_ke#
Particle normal contact stiffness (used by
SolverSemiImplicit
).
- particle_kf#
Particle friction force stiffness (used by
SolverSemiImplicit
).
- particle_mass#
Particle mass, shape [particle_count], float.
- particle_max_radius#
Maximum particle radius (useful for HashGrid construction).
- particle_max_velocity#
Maximum particle velocity (to prevent instability).
- particle_mu#
Particle friction coefficient.
- particle_q#
Particle positions, shape [particle_count, 3], float.
- particle_qd#
Particle velocities, shape [particle_count, 3], float.
- particle_radius#
Particle radius, shape [particle_count], float.
- requires_grad#
Whether the model was finalized (see
ModelBuilder.finalize()
) with gradient computation enabled.
- rigid_contact_max#
Number of potential contact points between rigid bodies.
- rigid_contact_rolling_friction#
Rolling friction coefficient for rigid body contacts (used by
SolverXPBD
).
- rigid_contact_torsional_friction#
Torsional friction coefficient for rigid body contacts (used by
SolverXPBD
).
- shape_body#
Rigid shape body index, shape [shape_count], int.
- shape_collision_filter_pairs#
Pairs of shape indices that should not collide.
- shape_collision_group#
Collision group of each shape, shape [shape_count], int.
- shape_collision_radius#
Collision radius for bounding sphere broadphase, shape [shape_count], float.
- shape_contact_pair_count#
Number of shape contact pairs.
- shape_contact_pairs#
Pairs of shape indices that may collide, shape [contact_pair_count, 2], int.
- shape_count#
Total number of shapes in the system.
- shape_filter#
Shape filter group, shape [shape_count], int.
- shape_flags#
Rigid shape flags, shape [shape_count], int.
- shape_group#
Environment group index for each shape, shape [shape_count], int. -1 for global.
- shape_is_solid#
Whether shape is solid or hollow, shape [shape_count], bool.
- shape_key#
List of keys for each shape.
- shape_material_ka#
Shape contact adhesion distance, shape [shape_count], float.
- shape_material_kd#
Shape contact damping stiffness, shape [shape_count], float.
- shape_material_ke#
Shape contact elastic stiffness, shape [shape_count], float.
- shape_material_kf#
Shape contact friction stiffness, shape [shape_count], float.
- shape_material_mu#
Shape coefficient of friction, shape [shape_count], float.
- shape_material_restitution#
Shape coefficient of restitution, shape [shape_count], float.
- shape_scale#
Shape 3D scale, shape [shape_count, 3], float.
- shape_source#
List of source geometry objects (e.g.,
Mesh
,SDF
) used for rendering and broadphase, shape [shape_count].
- shape_source_ptr#
Geometry source pointer to be used inside the Warp kernels which can be generated by finalizing the geometry objects, see for example
newton.Mesh.finalize()
, shape [shape_count], uint64.
- shape_thickness#
Shape thickness, shape [shape_count], float.
- shape_transform#
Rigid shape transforms, shape [shape_count, 7], float.
- shape_type#
Shape geometry type, shape [shape_count], int32.
- soft_contact_kd#
Damping of soft contacts (used by
SolverSemiImplicit
andSolverFeatherstone
).
- soft_contact_ke#
Stiffness of soft contacts (used by
SolverSemiImplicit
andSolverFeatherstone
).
- soft_contact_kf#
Stiffness of friction force in soft contacts (used by
SolverSemiImplicit
andSolverFeatherstone
).
- soft_contact_mu#
Friction coefficient of soft contacts.
- soft_contact_restitution#
Restitution coefficient of soft contacts (used by
SolverXPBD
).
- spring_constraint_lambdas#
Lagrange multipliers for spring constraints (internal use).
- spring_control#
Particle spring activation, shape [spring_count], float.
- spring_count#
Total number of springs in the system.
- spring_damping#
Particle spring damping, shape [spring_count], float.
- spring_indices#
Particle spring indices, shape [spring_count*2], int.
- spring_rest_length#
Particle spring rest length, shape [spring_count], float.
- spring_stiffness#
Particle spring stiffness, shape [spring_count], float.
- tet_activations#
Tetrahedral volumetric activations, shape [tet_count], float.
- tet_count#
Total number of tetrahedra in the system.
- tet_indices#
Tetrahedral element indices, shape [tet_count*4], int.
- tet_materials#
Tetrahedral elastic parameters in form \(k_{mu}, k_{lambda}, k_{damp}\), shape [tet_count, 3].
- tet_poses#
Tetrahedral rest poses, shape [tet_count, 3, 3], float.
- tri_activations#
Triangle element activations, shape [tri_count], float.
- tri_areas#
Triangle element rest areas, shape [tri_count], float.
- tri_count#
Total number of triangles in the system.
- tri_indices#
Triangle element indices, shape [tri_count*3], int.
- tri_materials#
Triangle element materials, shape [tri_count, 5], float.
- tri_poses#
Triangle element rest pose, shape [tri_count, 2, 2], float.
- up_axis#
0 for x, 1 for y, 2 for z.
- Type:
Up axis
- up_vector#
Up vector of the world, shape [3], float.