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:
objectArticulationView provides a flexible interface for selecting and manipulating subsets of articulations and their joints, links, and shapes within a Model. It supports pattern-based selection, inclusion/exclusion filters, and convenient attribute access and modification for simulation and control.
- Parameters:
model (Model) – The model containing the articulations.
pattern (str) – Pattern to match articulation keys.
include_joints (list[str | int] | None) – List of joint names, patterns, or indices to include.
exclude_joints (list[str | int] | None) – List of joint names, patterns, or indices to exclude.
include_links (list[str | int] | None) – List of link names, patterns, or indices to include.
exclude_links (list[str | int] | None) – List of link names, patterns, or indices to exclude.
include_joint_types (list[int] | None) – List of joint types to include.
exclude_joint_types (list[int] | None) – List of joint types to exclude.
verbose (bool | None) – If True, prints selection summary.
- __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.
- eval_jacobian(state, J=None, joint_S_s=None, mask=None)#
Evaluate spatial Jacobian for articulations in this view.
Computes the spatial Jacobian J that maps joint velocities to spatial velocities of each link in world frame.
- Parameters:
state (State) – The state containing body transforms (body_q).
J – Optional output array for the Jacobian, shape (articulation_count, max_links*6, max_dofs). If None, allocates internally.
joint_S_s – Optional pre-allocated temp array for motion subspaces.
mask – Optional mask of articulations in this ArticulationView (all by default).
- Returns:
The Jacobian array J, or None if the model has no articulations.
- eval_mass_matrix(state, H=None, J=None, body_I_s=None, joint_S_s=None, mask=None)#
Evaluate generalized mass matrix for articulations in this view.
Computes the generalized mass matrix H = J^T * M * J, where J is the spatial Jacobian and M is the block-diagonal spatial mass matrix.
- Parameters:
state (State) – The state containing body transforms (body_q).
H – Optional output array for mass matrix, shape (articulation_count, max_dofs, max_dofs). If None, allocates internally.
J – Optional pre-computed Jacobian. If None, computes internally.
body_I_s – Optional pre-allocated temp array for spatial inertias.
joint_S_s – Optional pre-allocated temp array for motion subspaces.
mask – Optional mask of articulations in this ArticulationView (all by default).
- Returns:
The mass matrix array H, or None if the model has no articulations.
- get_attribute(name, source)#
Get an attribute from the source (Model, State, or Control).
- get_dof_forces(source)#
Get the joint forces (DoF forces) for the selected articulations.
- Parameters:
source (Control) – The source from which to retrieve the DoF forces.
- Returns:
The joint forces (dtype=float).
- Return type:
array
- get_dof_positions(source)#
Get the joint coordinate positions (DoF positions) for the selected articulations.
- get_dof_velocities(source)#
Get the joint coordinate velocities (DoF velocities) for the selected articulations.
- get_link_transforms(source)#
Get the world-space transforms of all links in the selected articulations.
- get_link_velocities(source)#
Get the world-space spatial velocities of all links in the selected articulations.
- 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.
- get_root_velocities(source)#
Get the root velocities of the articulations.
- set_attribute(name, target, values, mask=None)#
Set an attribute in the target (Model, State, or Control).
- Parameters:
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_dof_forces(target, values, mask=None)#
Set the joint forces (DoF forces) for the selected articulations.
- Parameters:
target (Control) – The target where to set the DoF forces.
values (array) – The values to set (dtype=float).
mask (array, optional) – Mask of articulations in this ArticulationView (all by default).
- set_dof_positions(target, values, mask=None)#
Set the joint coordinate positions (DoF positions) for the selected articulations.
- set_dof_velocities(target, values, mask=None)#
Set the joint coordinate velocities (DoF velocities) for the selected articulations.
- set_root_transforms(target, values, mask=None)#
Set the root transforms of the articulations. Call
eval_fk()to apply changes to all articulation links.
- set_root_velocities(target, values, mask=None)#
Set the root velocities of the articulations.
- property body_names#
Alias for link_names.
- property body_shapes#
Alias for link_shapes.