newton.selection.ArticulationView#

class newton.selection.ArticulationView(model, pattern, include_joints=None, exclude_joints=None, include_links=None, exclude_links=None, include_joint_types=None, exclude_joint_types=None, verbose=None)[source]#

Bases: object

__init__(model, pattern, include_joints=None, exclude_joints=None, include_links=None, exclude_links=None, include_joint_types=None, exclude_joint_types=None, verbose=None)#
eval_fk(target, mask=None)#

Evaluates forward kinematics given the joint coordinates and updates the body information.

Parameters:
  • target (Model | State) – The target where to evaluate forward kinematics (Model or State).

  • mask (array) – Mask of articulations in this ArticulationView (all by default).

get_attribute(name, source)#

Get an attribute from the source (Model, State, or Control).

Parameters:
  • name (str) – The name of the attribute to get.

  • source (Model | State | Control) – The source from which to get the attribute.

Returns:

The attribute values (dtype matches the attribute).

Return type:

array

get_model_articulation_mask(mask=None)#

Get Model articulation mask from a mask in this ArticulationView.

Parameters:

mask (array) – Mask of articulations in this ArticulationView (all by default).

get_root_transforms(source)#

Get the root transforms of the articulations.

Parameters:

source (Model | State) – Where to get the root transforms (Model or State).

Returns:

The root transforms (dtype=wp.transform).

Return type:

array

get_root_velocities(source)#

Get the root velocities of the articulations.

Parameters:

source (Model | State) – Where to get the root velocities (Model or State).

Returns:

The root velocities (dtype=wp.spatial_vector).

Return type:

array

set_attribute(name, target, values, mask=None)#

Set an attribute in the target (Model, State, or Control).

Parameters:
  • name (str) – The name of the attribute to set.

  • target (Model | State | Control) – The target where to set the attribute.

  • values (array) – The values to set for the attribute.

  • mask (array) – Mask of articulations in this ArticulationView (all by default).

Note

When setting attributes on the Model, it may be necessary to inform the solver about such changes by calling newton.solvers.SolverBase.notify_model_changed() after finished setting Model attributes.

set_root_transforms(target, values, mask=None)#

Set the root transforms of the articulations. Call eval_fk() to apply changes to all articulation links.

Parameters:
  • target (Model | State) – Where to set the root transforms (Model or State).

  • values (array) – The root transforms to set (dtype=wp.transform).

  • mask (array) – Mask of articulations in this ArticulationView (all by default).

set_root_velocities(target, values, mask=None)#

Set the root velocities of the articulations.

Parameters:
  • target (Model | State) – Where to set the root velocities (Model or State).

  • values (array) – The root velocities to set (dtype=wp.spatial_vector).

  • mask (array) – Mask of articulations in this ArticulationView (all by default).