newton.State#

class newton.State[source]#

Bases: object

Represents the time-varying state of a Model in a simulation.

The State object holds all dynamic quantities that change over time during simulation, such as particle and rigid body positions, velocities, and forces, as well as joint coordinates.

State objects are typically created via newton.Model.state() and are used to store and update the simulation’s current configuration and derived data.

classmethod validate_extended_attributes(attributes)#

Validate names passed to request_state_attributes().

Only extended state attributes listed in EXTENDED_ATTRIBUTES are accepted.

Parameters:

attributes (tuple[str, ...]) – Tuple of attribute names to validate.

Raises:

ValueError – If any attribute name is not in EXTENDED_ATTRIBUTES.

__init__()#

Initialize an empty State object. To ensure that the attributes are properly allocated create the State object via newton.Model.state() instead.

assign(other)#

Copies the array attributes of another State object into this one.

This can be useful for swapping states in a simulation when using CUDA graphs. If the number of substeps is odd, the last state needs to be explicitly copied for the graph to be captured correctly:

# Assume we are capturing the following simulation loop in a CUDA graph
for i in range(sim_substeps):
    state_0.clear_forces()

    solver.step(state_0, state_1, control, contacts, sim_dt)

    # Swap states - handle CUDA graph case specially
    if sim_substeps % 2 == 1 and i == sim_substeps - 1:
        # Swap states by copying the state arrays for graph capture
        state_0.assign(state_1)
    else:
        # We can just swap the state references
        state_0, state_1 = state_1, state_0
Parameters:

other (State) – The source State object to copy from.

Raises:

ValueError – If the states have mismatched attributes (one has an array allocated where the other is None).

clear_forces()#

Clear all force arrays (for particles and bodies) in the state object.

Sets all entries of particle_f and body_f to zero, if present.

EXTENDED_ATTRIBUTES: frozenset[str] = frozenset({'body_parent_f', 'body_qdd'})#

Names of optional extended state attributes that are not allocated by default.

These can be requested via newton.ModelBuilder.request_state_attributes() or newton.Model.request_state_attributes() before calling newton.Model.state().

See Extended State Attributes for details and usage.

property body_count: int#

The number of bodies represented in the state.

body_f: array | None#

Rigid body forces (spatial), shape (body_count,), dtype spatial_vector. First three entries: linear force in world frame applied at the body’s center of mass (COM). Last three: torque (moment) in world frame.

Note

body_f represents an external wrench in world frame with the body’s center of mass (COM) as reference point.

body_parent_f: array | None#

Parent interaction forces, shape (body_count,), dtype spatial_vector. First three entries: linear force; last three: torque.

This is an extended state attribute; see Extended State Attributes for more information.

Note

body_parent_f represents incoming joint wrenches in world frame, referenced to the body’s center of mass (COM).

body_q: array | None#

Rigid body transforms (7-DOF), shape (body_count,), dtype transform.

body_q_prev: array | None#

Previous rigid body transforms for finite-difference velocity computation.

body_qd: array | None#

Rigid body velocities (spatial), shape (body_count,), dtype spatial_vector. First three entries: linear velocity relative to the body’s center of mass in world frame; last three: angular velocity in world frame. See Twist conventions in Newton for more information.

body_qdd: array | None#

Rigid body accelerations (spatial), shape (body_count,), dtype spatial_vector. First three entries: linear acceleration relative to the body’s center of mass in world frame; last three: angular acceleration in world frame.

This is an extended state attribute; see Extended State Attributes for more information.

property joint_coord_count: int#

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

property joint_dof_count: int#

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

joint_q: array | None#

Generalized joint position coordinates, shape (joint_coord_count,), dtype float.

joint_qd: array | None#

Generalized joint velocity coordinates, shape (joint_dof_count,), dtype float.

property particle_count: int#

The number of particles represented in the state.

particle_f: array | None#

3D forces on particles, shape (particle_count,), dtype vec3.

particle_q: array | None#

3D positions of particles, shape (particle_count,), dtype vec3.

particle_qd: array | None#

3D velocities of particles, shape (particle_count,), dtype vec3.

property requires_grad: bool#

Indicates whether the state arrays have gradient computation enabled.