newton.sim.Model#

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

Bases: object

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.

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

Initializes the Model object.

Parameters:

device (wp.Device) – Device on which the Model’s data will be allocated.

add_attribute(name, attrib, frequency)#

Add a custom attribute to the model

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

Generates contact points for the particles and rigid bodies in the model 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:

Contacts

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:

Control

get_attribute_frequency(name)#

Get the frequency of an attribute, e.g., “body”, “joint”, etc.

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:

State

articulation_count#

Total number of articulations in the system.

articulation_key#

Articulation keys, shape [articulation_count], str.

articulation_start#

Articulation start index, shape [articulation_count], int.

attribute_frequency#

Classify 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_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#

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

body_qd#

Velocities of rigid bodies used 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 parameters, 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.

gravity#

Gravity vector, shape [3], float.

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 MuJoCoSolver and FeatherstoneSolver), 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 in the system.

joint_count#

Total number of joints in the system.

joint_dof_count#

Total number of velocity degrees of freedom of all joints in the system. 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 used for state initialization, shape [joint_dof_count], float.

joint_friction#

Joint friction coefficient, shape [joint_dof_count], float.

joint_key#

Joint keys, shape [joint_count], str.

joint_limit_kd#

Joint position limit damping (used by SemiImplicitSolver and FeatherstoneSolver), shape [joint_dof_count], float.

joint_limit_ke#

Joint position limit stiffness (used by SemiImplicitSolver and FeatherstoneSolver), 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 used for state initialization, shape [joint_coord_count], float.

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.

joint_qd#

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

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.

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.

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 that were added to the ModelBuilder via add_builder.

particle_adhesion#

Particle adhesion strength. Default is 0.0.

particle_cohesion#

Particle cohesion strength. Default is 0.0.

particle_color_groups#

The coloring of all the particles, used by VBDSolver for Gauss-Seidel iteration. Each array contains indices of particles sharing the same color.

particle_colors#

Contains the color assignment for every particle.

particle_count#

Total number of particles in the system.

particle_flags#

Particle enabled state, shape [particle_count], bool.

particle_grid#

HashGrid instance used for accelerated simulation of particle interactions.

particle_inv_mass#

Particle inverse mass, shape [particle_count], float.

particle_kd#

Particle normal contact damping (used by SemiImplicitSolver). Default is 1.0e2.

particle_ke#

Particle normal contact stiffness (used by SemiImplicitSolver). Default is 1.0e3.

particle_kf#

Particle friction force stiffness (used by SemiImplicitSolver). Default is 1.0e2.

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). Default is 1e5.

particle_mu#

Particle friction coefficient. Default is 0.5.

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#

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

rigid_contact_torsional_friction#

Torsional friction coefficient for rigid body contacts (used by XPBDSolver).

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_group_map#

Mapping from collision group to list of shape indices.

shape_collision_radius#

Collision radius of each shape used for bounding sphere broadphase collision checking, 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_flags#

Rigid shape flags, shape [shape_count], uint32.

shape_geo#

Shape geometry properties (geo type, scale, thickness, etc.).

shape_geo_src#

List of source geometry objects (e.g., wp.Mesh, SDF) used for rendering and broadphase.

shape_key#

List of keys for each shape.

shape_materials#

Rigid shape contact materials.

shape_transform#

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

soft_contact_kd#

Damping of soft contacts (used by SemiImplicitSolver and FeatherstoneSolver). Default is 10.0.

soft_contact_ke#

Stiffness of soft contacts (used by SemiImplicitSolver and FeatherstoneSolver). Default is 1.0e3.

soft_contact_kf#

Stiffness of friction force in soft contacts (used by SemiImplicitSolver and FeatherstoneSolver). Default is 1.0e3.

soft_contact_mu#

Friction coefficient of soft contacts. Default is 0.5.

soft_contact_restitution#

Restitution coefficient of soft contacts (used by XPBDSolver). Default is 0.0.

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#

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

up_vector#

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