newton.eval_ik#

newton.eval_ik(model, state, joint_q, joint_qd, mask=None, indices=None, body_flag_filter=BodyFlags.ALL)[source]#

Evaluates the model’s inverse kinematics given the state’s body information (State.body_q and State.body_qd) and updates the generalized joint coordinates joint_q and joint_qd.

The input State.body_qd is interpreted using Newton’s public body-twist convention (v_com_world, omega_world). For FREE and DISTANCE joints, the recovered joint_qd linear entries are referenced at the child COM and expressed in the joint parent frame.

Parameters:
  • model (Model) – The model to evaluate.

  • state (State | Model | object) – The state-like object with the body’s maximal coordinates (positions State.body_q and velocities State.body_qd) to use.

  • joint_q (wp.array[float]) – Generalized joint position coordinates, shape [joint_coord_count], float

  • joint_qd (wp.array[float]) – Generalized joint velocity coordinates, shape [joint_dof_count], float

  • mask (wp.array[bool] | None) – Boolean mask indicating which articulations to update. If None, updates all (or those specified by indices).

  • indices (wp.array[int] | None) – Integer indices of articulations to update. If None, updates all articulations.

  • body_flag_filter (int) – Body flag filter controlling which joints are written based on each joint’s child body flag. Default updates joints for both dynamic and kinematic child bodies. Entries that do not match the filter retain their existing values in joint_q and joint_qd.

Note

The mask and indices parameters are mutually exclusive. If both are provided, a ValueError is raised.