newton.ik.IKObjective#
- class newton.ik.IKObjective[source]#
Bases:
objectAbstract base class for inverse kinematics objectives.
- Subclasses must implement the following methods:
residual_dim(): Returns the number of residuals (constraints) this objective contributes.
compute_residuals(body_q, joint_q, model, residuals, start_idx): Computes the residuals for this objective.
compute_jacobian_autodiff(tape, model, jacobian, start_idx, dq_dof): Computes the Jacobian using autodiff.
- Optional methods for analytic Jacobian support:
supports_analytic(): Returns True if analytic Jacobian is supported, otherwise False.
compute_jacobian_analytic(body_q, joint_q, model, jacobian, joint_S_s, start_idx): Computes the analytic Jacobian if supported.
- Device and buffer management:
bind_device(device): Binds the objective to a specific device.
init_buffers(model, jacobian_mode): Initializes any buffers required for Jacobian computation.
Notes
The interface is designed for batch processing of multiple IK problems in parallel.
Each subclass may store per-problem data (e.g., targets) as device arrays.
- __init__()#
- bind_device(device)#
Binds the objective to a specific device (e.g., CUDA or CPU).
- Parameters:
device (wp.Device) – The device to bind to.
- compute_jacobian_analytic(body_q, joint_q, model, jacobian, joint_S_s, start_idx)#
Computes the analytic Jacobian for this objective, if supported.
- Parameters:
body_q (wp.array2d(dtype=wp.transform)) – Array of body transforms for each problem.
joint_q (wp.array2d(dtype=wp.float)) – Array of joint coordinates for each problem.
model (newton.Model) – The kinematic model.
jacobian (wp.array3d(dtype=wp.float)) – Output array for the Jacobian.
joint_S_s (wp.array2d(dtype=wp.spatial_vector)) – Motion subspace matrices.
start_idx (int) – Starting index in the Jacobian for this objective.
- compute_jacobian_autodiff(tape, model, jacobian, start_idx, dq_dof)#
Computes the Jacobian for this objective using automatic differentiation.
- Parameters:
tape (wp.Tape) – Autodiff tape.
model (newton.Model) – The kinematic model.
jacobian (wp.array3d(dtype=wp.float)) – Output array for the Jacobian.
start_idx (int) – Starting index in the Jacobian for this objective.
dq_dof (wp.array2d(dtype=wp.float)) – Derivative of q with respect to DoF.
- compute_residuals(body_q, joint_q, model, residuals, start_idx, problem_idx)#
Computes the residuals for this objective and writes them into the residuals array.
- Parameters:
body_q (wp.array2d(dtype=wp.transform)) – Array of body transforms for each problem.
joint_q (wp.array2d(dtype=wp.float)) – Array of joint coordinates for each problem.
model (newton.Model) – The kinematic model.
residuals (wp.array2d(dtype=wp.float)) – Output array for residuals.
start_idx (int) – Starting index in the residuals array for this objective.
problem_idx (wp.array1d(dtype=int32) | None) – Maps each batched row to the originating problem index when rows have been duplicated (for example, when evaluating multiple candidates per problem). Typical usage inside a kernel looks like row_idx = wp.tid(); base = problem_idx[row_idx]; target = self.target_positions[base]. Defaults to None, which indicates rows already align with the solver batch.
- init_buffers(model, jacobian_mode)#
Initializes any buffers required for Jacobian computation.
- Parameters:
model (newton.Model) – The kinematic model.
jacobian_mode (IKJacobianType) – The Jacobian computation mode (analytic or autodiff).
- residual_dim()#
Returns the number of residuals (constraints) this objective contributes. Must be implemented by subclasses.
- set_batch_layout(total_residuals, residual_offset, n_batch)#
Register the residual layout for this objective within the optimizer’s global system.
- Parameters:
total_residuals (int) – Total number of residual rows across all objectives (global height of J and r).
residual_offset (int) – Starting row index (into the global residual/Jacobian) reserved for this objective.
n_batch (int) – Number of rows that will be evaluated together by the optimizer (e.g., n_problems * n_seeds, or further expanded for candidates).
Notes
n_batch is the size of the evaluation batch, not the number of base problems.
Per-problem buffers (e.g., targets) should be sized by the number of base problems and accessed via the problem_idx mapping provided at evaluation time, rather than assuming one target per batch row.
This method is called by the optimizer before any residual/Jacobian computations.
- supports_analytic()#
Returns True if this objective supports analytic Jacobian computation. Subclasses should override if analytic Jacobian is available.