newton.State#
- 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 solver as derived data, e.g.: forces.
The exact attributes depend on the contents of the model. State objects should generally be created using the
newton.Model.state()
function.Methods
__init__
()Clear all forces (for particles and bodies) in the state object.
Attributes
The number of bodies represented in the state.
The number of generalized joint position coordinates represented in the state.
The number of generalized joint velocity coordinates represented in the state.
The number of particles represented in the state.
Indicates whether the state arrays have gradient computation enabled.
Array of 3D particle positions with shape
(particle_count,)
and typevec3
.Array of 3D particle velocities with shape
(particle_count,)
and typevec3
.Array of 3D particle forces with shape
(particle_count,)
and typevec3
.Array of body coordinates (7-dof transforms) in maximal coordinates with shape
(body_count,)
and typetransform
.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
.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
.Array of generalized joint coordinates with shape
(joint_coord_count,)
and typefloat
.Array of generalized joint velocities with shape
(joint_dof_count,)
and typefloat
.- __init__()#
- 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 solvers exceptFeatherstoneSolver
, 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.