newton.sim.ik#

Classes

IKSolver(model, joint_q, objectives, *a, **kw)

Modular inverse-kinematics solver.

JointLimitObjective(joint_limit_lower, ...)

Joint limit constraint objective.

PositionObjective(link_index, link_offset, ...)

End-effector positional target for one link.

RotationObjective(link_index, ...[, weight])

End-effector rotational target for one link.

class newton.sim.ik.IKSolver(model, joint_q, objectives, *a, **kw)[source]#

Modular inverse-kinematics solver.

The solver uses an adaptive Levenberg-Marquardt loop and supports three Jacobian back-ends:

  • AUTODIFF — Warp’s reverse-mode autodiff for every objective

  • ANALYTIC — objective-specific analytic Jacobians only

  • MIXED — analytic where available, autodiff fallback elsewhere

Parameters:
  • model (newton.Model) – Singleton articulation shared by _all_ problems.

  • joint_q (What varies from problem to problem are (1) the corresponding row in) – Initial joint coordinates, one row per problem. Modified in place.

  • objectives ((2) any per-problem data stored internally by the) – Ordered list of objectives shared by _all_ problems. Each IKObjective instance can carry arrays of per-problem parameters (e.g. an array of target positions of length n_problems).

  • jacobian_mode (JacobianMode, default JacobianMode.AUTODIFF) – Backend used in compute_jacobian.

  • lambda_initial (float, default 0.1) – Initial LM damping per problem.

  • lambda_factor (float, default 2.0) – Multiplicative update factor for λ.

  • lambda_min (float, default 1e-5) – Lower clamp for λ.

  • lambda_max (float, default 1e10) – Upper clamp for λ.

  • rho_min (float, default 1e-3) – Acceptance threshold on predicted vs. actual reduction.

  • structure (Batch)

  • ------

  • same (The solver handles a batch of independent IK problems that all reference the)

  • objects. (articulation (model) and the same list of objective)

  • joint_q

  • and

  • objectives

  • e.g.

  • array (an)

  • duplicated. (of target positions. Nothing else is)

  • problems (- Shared across)

  • data (- Per-problem)

Supported joint types#

ANALYTIC and MIXED modes currently only support models with revolute, prismatic, and fixed joints. For more complex joint types (e.g., free, ball, D6), use AUTODIFF mode. Velocity-space optimization is planned for broader analytic support in future updates.

__init__(model, joint_q, objectives, lambda_initial=0.1, jacobian_mode=JacobianMode.AUTODIFF, lambda_factor=2.0, lambda_min=1e-5, lambda_max=1e10, rho_min=1e-3)#

Construct a batch IK solver.

See class doc-string for parameter semantics.

solve(iterations=10, step_size=1.0)#

Run the Levenberg-Marquardt loop.

Parameters:
  • iterations (int, default 10) – Maximum number of outer iterations.

  • step_size (float, default 1.0) – Multiplicative scale on deltaq before applying the proposal.

  • Side-effects

  • ------------

  • coordinates. (Updates self.joint_q in-place with the converged)

class newton.sim.ik.PositionObjective(link_index, link_offset, target_positions, n_problems, total_residuals, residual_offset, weight=1.0)[source]#

End-effector positional target for one link.

Parameters:
  • link_index (int) – Body index whose frame defines the end-effector.

  • link_offset (wp.vec3) – Offset from the body frame (local coordinates).

  • target_positions (wp.array(dtype=wp.vec3)) – One target position per problem.

  • n_problems (int) – Number of parallel IK problems.

  • total_residuals (int) – Global residual vector length (for autodiff bookkeeping).

  • residual_offset (int) – Starting index of this objective inside the residual vector.

  • weight (float, default 1.0) – Scalar weight multiplying both residual and Jacobian rows.

__init__(link_index, link_offset, target_positions, n_problems, total_residuals, residual_offset, weight=1.0)#
init_buffers(model, jacobian_mode)#

Precompute lookup tables for analytic jacobian computation.

supports_analytic()#
residual_dim()#
compute_residuals(body_q, joint_q, model, residuals, start_idx)#
compute_jacobian_autodiff(tape, model, jacobian, start_idx, joint_q)#
compute_jacobian_analytic(body_q, joint_q, model, jacobian, joint_S_s, start_idx)#
class newton.sim.ik.JointLimitObjective(joint_limit_lower, joint_limit_upper, n_problems, total_residuals, residual_offset, weight=0.1)[source]#

Joint limit constraint objective.

Parameters:
  • joint_limit_lower (wp.array(dtype=float)) – Lower bounds for each joint coordinate.

  • joint_limit_upper (wp.array(dtype=float)) – Upper bounds for each joint coordinate.

  • n_problems (int, optional) – Number of parallel IK problems.

  • total_residuals (int, optional) – Global residual vector length (for autodiff bookkeeping).

  • residual_offset (int, optional) – Starting index of this objective inside the residual vector.

  • weight (float, default 0.1) – Scalar weight for limit violation penalty.

__init__(joint_limit_lower, joint_limit_upper, n_problems, total_residuals, residual_offset, weight=0.1)#
init_buffers(model, jacobian_mode)#
supports_analytic()#
residual_dim()#
compute_residuals(body_q, joint_q, model, residuals, start_idx)#
compute_jacobian_autodiff(tape, model, jacobian, start_idx, joint_q)#
compute_jacobian_analytic(body_q, joint_q, model, jacobian, joint_S_s, start_idx)#
class newton.sim.ik.RotationObjective(link_index, link_offset_rotation, target_rotations, n_problems, total_residuals, residual_offset, weight=1.0)[source]#

End-effector rotational target for one link.

Parameters:
  • link_index (int) – Body index whose frame defines the end-effector.

  • link_offset_rotation (wp.quat) – Rotation offset from the body frame (local coordinates).

  • target_rotations (wp.array(dtype=wp.vec4)) – One target quaternion per problem (stored as vec4).

  • n_problems (int) – Number of parallel IK problems.

  • total_residuals (int) – Global residual vector length (for autodiff bookkeeping).

  • residual_offset (int) – Starting index of this objective inside the residual vector.

  • weight (float, default 1.0) – Scalar weight multiplying both residual and Jacobian rows.

__init__(link_index, link_offset_rotation, target_rotations, n_problems, total_residuals, residual_offset, weight=1.0)#
init_buffers(model, jacobian_mode)#

Precompute lookup tables for analytic jacobian computation.

supports_analytic()#
residual_dim()#
compute_residuals(body_q, joint_q, model, residuals, start_idx)#
compute_jacobian_autodiff(tape, model, jacobian, start_idx, joint_q)#
compute_jacobian_analytic(body_q, joint_q, model, jacobian, joint_S_s, start_idx)#