newton.ik.IKObjectivePosition#

class newton.ik.IKObjectivePosition(link_index, link_offset, target_positions, weight=1.0)[source]#

Bases: IKObjective

Match the world-space position of a point on a link.

Parameters:
  • link_index (int) – Body index whose frame defines the constrained link.

  • link_offset (wp.vec3) – Point in the link’s local frame [m].

  • target_positions (wp.array(dtype=wp.vec3)) – Target positions [m], shape [problem_count].

  • weight (float) – Scalar multiplier applied to the residual and Jacobian rows.

__init__(link_index, link_offset, target_positions, weight=1.0)#
compute_jacobian_analytic(body_q, joint_q, model, jacobian, joint_S_s, start_idx)#

Fill the position Jacobian block from the analytic motion subspace.

Parameters:
  • body_q (array(ndim=2, dtype=transformf)) – Batched body transforms for the evaluation rows, shape [n_batch, body_count].

  • joint_q (array(ndim=2, dtype=float32)) – Batched joint coordinates, shape [n_batch, joint_coord_count]. Present for interface compatibility and not used directly by this objective.

  • model (Model) – Shared articulation model.

  • jacobian (array(ndim=3, dtype=float32)) – Global Jacobian buffer to update, shape [n_batch, total_residual_count, joint_dof_count].

  • joint_S_s (array(ndim=2, dtype=vector(length=6, dtype=float32))) – Batched motion-subspace columns, shape [n_batch, joint_dof_count].

  • start_idx (int) – First residual row reserved for this objective.

compute_jacobian_autodiff(tape, model, jacobian, start_idx, dq_dof)#

Fill the position Jacobian block using Warp autodiff.

Parameters:
  • tape (Tape) – Recorded Warp tape whose output is the global residual buffer.

  • model (Model) – Shared articulation model.

  • jacobian (array(ndim=3, dtype=float32)) – Global Jacobian buffer to update, shape [n_batch, total_residual_count, joint_dof_count].

  • start_idx (int) – First residual row reserved for this objective.

  • dq_dof (array(ndim=2, dtype=float32)) – Differentiable joint update variable for the current batch, shape [n_batch, joint_dof_count].

compute_residuals(body_q, joint_q, model, residuals, start_idx, problem_idx)#

Write weighted position errors into the global residual buffer.

Parameters:
  • body_q (array(ndim=2, dtype=transformf)) – Batched body transforms for the evaluation rows, shape [n_batch, body_count].

  • joint_q (array(ndim=2, dtype=float32)) – Batched joint coordinates, shape [n_batch, joint_coord_count]. Present for interface compatibility and not used directly by this objective.

  • model (Model) – Shared articulation model. Present for interface compatibility.

  • residuals (array(ndim=2, dtype=float32)) – Global residual buffer to update, shape [n_batch, total_residual_count].

  • start_idx (int) – First residual row reserved for this objective.

  • problem_idx (array(ndim=1, dtype=int32)) – Mapping from evaluation rows to base problem indices, shape [n_batch], used to fetch target_positions.

init_buffers(model, jacobian_mode)#

Initialize caches used by analytic or autodiff Jacobian evaluation.

Parameters:
  • model (Model) – Shared articulation model.

  • jacobian_mode (IKJacobianType) – Jacobian backend selected for this objective.

residual_dim()#

Return the three translational residual rows for this objective.

set_target_position(problem_idx, new_position)#

Update the target position for a single base IK problem.

Parameters:
  • problem_idx (int) – Base problem index to update.

  • new_position (vec3f) – Replacement target position [m] in world coordinates.

set_target_positions(new_positions)#

Replace the target positions for all base IK problems.

Parameters:

new_positions (array(ndim=1, dtype=vec3f)) – Target positions [m], shape [problem_count].

supports_analytic()#

Return True because this objective has an analytic Jacobian.