Skip to content

API reference

Auto-generated from docstrings. The public surface is small by design — most users only touch Manipulator, Solution, and (when relevant) TolerancePolicy / Diagnostic.

Entry point: Manipulator

Public IK + FK handle for a robot arm.

Construct via the factory classmethods (e.g. :meth:from_urdf), then use :meth:fk and :meth:ik for the common path. The dispatched analytical solver auto-routes based on the arm's kinematic topology -- users do not need to import or name a specific solver.

.. note:: The constructor signature Manipulator(kinbody) is the escape hatch for callers who already have a :class:KinBody (e.g. from a custom loader). Most users should use :meth:from_urdf instead.

Source code in src/ssik/manipulator.py
class Manipulator:
    """Public IK + FK handle for a robot arm.

    Construct via the factory classmethods (e.g. :meth:`from_urdf`), then use
    :meth:`fk` and :meth:`ik` for the common path. The dispatched analytical
    solver auto-routes based on the arm's kinematic topology -- users do not
    need to import or name a specific solver.

    .. note::
        The constructor signature ``Manipulator(kinbody)`` is the escape hatch
        for callers who already have a :class:`KinBody` (e.g. from a custom
        loader). Most users should use :meth:`from_urdf` instead.
    """

    __slots__ = ("_kb", "_plan", "_solver_module")

    def __init__(
        self,
        kinbody: KinBody,
        *,
        policy: TolerancePolicy = DEFAULT_TOLERANCE_POLICY,
    ) -> None:
        """Wrap a pre-built :class:`KinBody`.

        :param kinbody: a POE-normalised :class:`KinBody`. If you have a URDF,
            use :meth:`from_urdf` instead -- it builds the KinBody for you.
        :param policy: tolerance policy used by the topology dispatcher.
            Defaults to :data:`~ssik.core.tolerances.DEFAULT_TOLERANCE_POLICY`.
        """
        self._kb: KinBody = kinbody
        self._plan: DispatchPlan = dispatch(kinbody, policy=policy)
        self._solver_module: ModuleType = importlib.import_module(
            _SOLVER_MODULE_PATHS[self._plan.solver_name]
        )

    # ------------------------------------------------------------------
    # Factories
    # ------------------------------------------------------------------

    @classmethod
    def from_urdf(
        cls,
        path: str | Path,
        *,
        base: str,
        ee: str,
        policy: TolerancePolicy = DEFAULT_TOLERANCE_POLICY,
    ) -> Manipulator:
        """Load a URDF and build a :class:`Manipulator` for the chain
        between ``base`` and ``ee``.

        The kinematic chain is POE-normalised internally so the dispatcher
        can match the arm's topology against the solver roster. Mesh loading
        is lazy (the URDF parser does not load STL files unless asked).

        :param path: path to the URDF file.
        :param base: name of the base link in the URDF.
        :param ee: name of the end-effector link in the URDF.
        :param policy: tolerance policy. Defaults to
            :data:`~ssik.core.tolerances.DEFAULT_TOLERANCE_POLICY`.

        :raises FileNotFoundError: if ``path`` doesn't exist.
        :raises ValueError: if ``base`` or ``ee`` are not link names in the URDF.
        :raises ImportError: if the optional dependency ``urchin`` is not
            installed (``pip install ssik[urdf]``).
        """
        # Imported lazily so the urchin dependency is only required when
        # from_urdf is actually called (it's an optional extra).
        from ssik._urdf import load_urdf_kinbody_normalized

        # urchin raises ValueError on missing files; rewrite to the more
        # idiomatic FileNotFoundError for the public API contract.
        path_obj = Path(path)
        if not path_obj.exists():
            raise FileNotFoundError(f"URDF file not found: {path_obj}")

        kb = load_urdf_kinbody_normalized(path, base, ee)
        return cls(kb, policy=policy)

    # ------------------------------------------------------------------
    # Introspection
    # ------------------------------------------------------------------

    @property
    def dof(self) -> int:
        """Number of joints in the chain."""
        return len(self._kb.joints)

    @property
    def joint_limits(self) -> list[tuple[float, float] | None]:
        """Per-joint ``(lower, upper)`` limits, or ``None`` for unconstrained.

        Units are radians for revolute joints, metres for prismatic. Joints
        without explicit limits in the source URDF are ``None`` (typically
        continuous revolute joints).
        """
        return [j.limits for j in self._kb.joints]

    @property
    def dispatch_plan(self) -> DispatchPlan:
        """Diagnostic info on which analytical solver was selected and why.

        Useful for understanding why a given arm dispatches to a particular
        solver (the ``reason`` field is a multi-line user-facing explanation).
        """
        return self._plan

    @property
    def kinbody(self) -> KinBody:
        """The underlying POE-normalised :class:`KinBody`.

        Power-user escape hatch for callers who need to invoke a specific
        solver, run codegen, or interact with the kinematics primitives
        directly. Most users should not need this.
        """
        return self._kb

    @property
    def solver_name(self) -> str:
        """Dotted name of the dispatched solver, e.g. ``"ikgeo.three_parallel"``."""
        return self._plan.solver_name

    def __repr__(self) -> str:
        return (
            f"<Manipulator: {self.dof}-DOF, dispatched to "
            f"{self._plan.solver_name} (tier {self._plan.tier})>"
        )

    # ------------------------------------------------------------------
    # Forward kinematics
    # ------------------------------------------------------------------

    def fk(self, q: ArrayLike) -> NDArray[np.float64]:
        """Forward kinematics: return the 4x4 SE(3) pose at config ``q``.

        :param q: joint vector of length :attr:`dof`. Float-castable
            (list, tuple, numpy array all work).

        :returns: 4x4 numpy array. Top-left 3x3 is the end-effector
            rotation matrix; column 3 (rows 0..2) is the position.

        :raises ValueError: if ``len(q) != dof``.
        """
        q_arr = np.asarray(q, dtype=np.float64)
        if q_arr.shape != (self.dof,):
            raise ValueError(f"fk expected q of shape ({self.dof},), got {q_arr.shape}")
        result: NDArray[np.float64] = poe_forward_kinematics(self._kb, q_arr)
        return result

    # ------------------------------------------------------------------
    # Inverse kinematics
    # ------------------------------------------------------------------

    @overload
    def solve(
        self,
        T_target: ArrayLike,
        *,
        explain: Literal[False] = False,
        max_solutions: int | None = None,
        q_seed: ArrayLike | None = None,
        respect_limits: bool = True,
        allow_refinement: bool = False,
        policy: TolerancePolicy = DEFAULT_TOLERANCE_POLICY,
        refinement_max_iters: int = 15,
        **solver_kwargs: Any,
    ) -> list[Solution]: ...

    @overload
    def solve(
        self,
        T_target: ArrayLike,
        *,
        explain: Literal[True],
        max_solutions: int | None = None,
        q_seed: ArrayLike | None = None,
        respect_limits: bool = True,
        allow_refinement: bool = False,
        policy: TolerancePolicy = DEFAULT_TOLERANCE_POLICY,
        refinement_max_iters: int = 15,
        **solver_kwargs: Any,
    ) -> tuple[list[Solution], Diagnostic]: ...

    def solve(
        self,
        T_target: ArrayLike,
        *,
        explain: bool = False,
        max_solutions: int | None = None,
        q_seed: ArrayLike | None = None,
        respect_limits: bool = True,
        allow_refinement: bool = False,
        policy: TolerancePolicy = DEFAULT_TOLERANCE_POLICY,
        refinement_max_iters: int = 15,
        **solver_kwargs: Any,
    ) -> list[Solution] | tuple[list[Solution], Diagnostic]:
        """Inverse kinematics: find every ``q`` such that ``fk(q) ≈ T_target``.

        :param T_target: 4x4 SE(3) target pose.
        :param explain: when ``True``, returns ``(sols, Diagnostic)``
            instead of just ``sols``. The diagnostic carries dispatch +
            filter attribution for triaging empty-list failures. Default
            ``False`` preserves the v1.0 return signature.
        :param max_solutions: optional cap on returned IKs (post-dedup,
            post-limits filter). ``None`` = full redundancy enumeration.
            ``1`` combined with ``q_seed`` is the trajectory-tracking idiom.
            On 7R jointlock arms the cap also short-circuits the lock-sweep
            internally for a 10-15x speedup.
        :param q_seed: optional length-:attr:`dof` seed. When provided,
            returned solutions are sorted by wrap-to-pi distance from
            ``q_seed`` (closest first). On jointlock-7R arms it also
            reorders the internal lock-sample sweep.
        :param respect_limits: when ``True`` (default), solutions outside
            URDF joint limits are dropped. Pass ``False`` for the raw
            geometric set (analysis / debugging).
        :param allow_refinement: opt into Newton polish for near-miss
            algebraic candidates. Default ``False`` -- the algebraic
            path is already at machine precision on tier-0 / SRS arms.
            Set ``True`` on tier-2 RR arms to recover edge-case
            candidates whose algebraic FK drifts above ``fk_atol``.
        :param policy: tolerance policy. Rarely customised. Defaults to
            :data:`~ssik.core.tolerances.DEFAULT_TOLERANCE_POLICY`.
        :param refinement_max_iters: cap on Newton iterations per candidate
            when ``allow_refinement=True``.
        :param solver_kwargs: forwarded verbatim to the dispatched solver
            for power users (``swivel_samples`` for SRS-class,
            ``linearity_joint`` for RR, etc.).

        :returns: list of :class:`Solution`, one per analytical IK branch.
            Empty list iff no candidate FK-closed within
            ``policy.subproblem_numerical`` (or all IKs were filtered by
            ``respect_limits=True``). Check ``if not sols:`` for
            "unreachable target". When ``explain=True``, returns
            ``(sols, Diagnostic)`` -- inspect ``Diagnostic.summary()``
            to attribute empty-list failures.

        :raises ValueError: if ``T_target.shape != (4, 4)`` or
            ``len(q_seed) != dof`` when ``q_seed`` is given.
        """
        from ssik.postprocess import nearest_to_seed as _ps_nearest_to_seed
        from ssik.postprocess import respect_limits as _ps_respect_limits
        from ssik.postprocess import wrap_to_limits as _ps_wrap_to_limits

        T = np.asarray(T_target, dtype=np.float64)
        if T.shape != (4, 4):
            raise ValueError(f"solve expected T_target of shape (4, 4), got {T.shape}")
        if q_seed is not None:
            q_seed_arr: NDArray[np.float64] | None = np.asarray(q_seed, dtype=np.float64)
            assert q_seed_arr is not None
            if q_seed_arr.shape != (self.dof,):
                raise ValueError(f"q_seed expected shape ({self.dof},), got {q_seed_arr.shape}")
        else:
            q_seed_arr = None

        # Filter kwargs by the dispatched solver's signature so callers can
        # pass q_seed (or any other not-universally-supported kwarg) without
        # tripping TypeError on solvers that don't accept it. The dispatch
        # is determined at __init__ time, so the signature lookup is per-IK
        # but cheap (~5 us).
        sig = inspect.signature(self._solver_module.solve)
        params = sig.parameters
        kwargs: dict[str, Any] = {"policy": policy}
        if "allow_refinement" in params:
            kwargs["allow_refinement"] = allow_refinement
        if "refinement_max_iters" in params:
            kwargs["refinement_max_iters"] = refinement_max_iters
        # When respect_limits=True, don't short-circuit the inner solver's
        # sweep on max_solutions: the closest-to-seed branch the solver
        # picks first may be out-of-limits and the postprocess pass would
        # drop it, leaving zero results. Force the full sweep, then
        # filter + trim. The user opts out via respect_limits=False.
        if "max_solutions" in params:
            kwargs["max_solutions"] = None if respect_limits else max_solutions
        if q_seed_arr is not None and "q_seed" in params:
            kwargs["q_seed"] = q_seed_arr
        # Power-user kwargs override our defaults.
        kwargs.update(solver_kwargs)

        # Internal solver functions still return (sols, is_ls); unwrap the
        # tuple at the public-API boundary. `is_ls` is redundant with
        # `len(sols) == 0` in every shipped solver -- ssik #238 item 1.
        sols, _is_ls = self._solver_module.solve(self._kb, T, **kwargs)
        raw_candidate_count = len(sols)

        # Cross-arm postprocess pass: solvers that didn't honour kwargs
        # natively get them applied here so the public API is uniform.
        # Order: wrap_to_limits first (try +/- 2pi shift to bring branches
        # into the URDF range), THEN respect_limits (drop anything still
        # outside). Without the shift, IKs returned in [-2pi, 0] would
        # erroneously be filtered on arms with limits in [0, 2pi]
        # (the JACO 2 case).
        if respect_limits:
            sols = _ps_wrap_to_limits(sols, self._kb)
            pre_limit_count = len(sols)
            sols = _ps_respect_limits(sols, self._kb)
            dropped_by_limits = pre_limit_count - len(sols)
        else:
            dropped_by_limits = 0
        if q_seed_arr is not None:
            sols = _ps_nearest_to_seed(sols, q_seed_arr)
        if max_solutions is not None and len(sols) > max_solutions:
            dropped_by_max_solutions = len(sols) - max_solutions
            sols = sols[:max_solutions]
        else:
            dropped_by_max_solutions = 0
        result: list[Solution] = sols
        if not explain:
            return result

        refinement_engaged = sum(1 for s in result if s.refinement_used == "lm")
        max_fk = max((s.fk_residual for s in result), default=float("nan"))
        diag = Diagnostic(
            solver_name=self._plan.solver_name,
            solver_tier=self._plan.tier,
            dispatch_reason=self._plan.reason,
            raw_candidates=raw_candidate_count,
            dropped_by_limits=dropped_by_limits,
            dropped_by_max_solutions=dropped_by_max_solutions,
            final_count=len(result),
            max_fk_residual=max_fk,
            refinement_engaged=refinement_engaged,
            fk_atol=policy.subproblem_numerical,
        )
        return result, diag

dof property

dof: int

Number of joints in the chain.

solver_name property

solver_name: str

Dotted name of the dispatched solver, e.g. "ikgeo.three_parallel".

kinbody property

kinbody: KinBody

The underlying POE-normalised :class:KinBody.

Power-user escape hatch for callers who need to invoke a specific solver, run codegen, or interact with the kinematics primitives directly. Most users should not need this.

from_urdf classmethod

from_urdf(
    path: str | Path,
    *,
    base: str,
    ee: str,
    policy: TolerancePolicy = DEFAULT_TOLERANCE_POLICY,
) -> Manipulator

Load a URDF and build a :class:Manipulator for the chain between base and ee.

The kinematic chain is POE-normalised internally so the dispatcher can match the arm's topology against the solver roster. Mesh loading is lazy (the URDF parser does not load STL files unless asked).

Parameters:

Name Type Description Default
path str | Path

path to the URDF file.

required
base str

name of the base link in the URDF.

required
ee str

name of the end-effector link in the URDF.

required
policy TolerancePolicy

tolerance policy. Defaults to :data:~ssik.core.tolerances.DEFAULT_TOLERANCE_POLICY.

DEFAULT_TOLERANCE_POLICY

Raises:

Type Description
FileNotFoundError

if path doesn't exist.

ValueError

if base or ee are not link names in the URDF.

ImportError

if the optional dependency urchin is not installed (pip install ssik[urdf]).

Source code in src/ssik/manipulator.py
@classmethod
def from_urdf(
    cls,
    path: str | Path,
    *,
    base: str,
    ee: str,
    policy: TolerancePolicy = DEFAULT_TOLERANCE_POLICY,
) -> Manipulator:
    """Load a URDF and build a :class:`Manipulator` for the chain
    between ``base`` and ``ee``.

    The kinematic chain is POE-normalised internally so the dispatcher
    can match the arm's topology against the solver roster. Mesh loading
    is lazy (the URDF parser does not load STL files unless asked).

    :param path: path to the URDF file.
    :param base: name of the base link in the URDF.
    :param ee: name of the end-effector link in the URDF.
    :param policy: tolerance policy. Defaults to
        :data:`~ssik.core.tolerances.DEFAULT_TOLERANCE_POLICY`.

    :raises FileNotFoundError: if ``path`` doesn't exist.
    :raises ValueError: if ``base`` or ``ee`` are not link names in the URDF.
    :raises ImportError: if the optional dependency ``urchin`` is not
        installed (``pip install ssik[urdf]``).
    """
    # Imported lazily so the urchin dependency is only required when
    # from_urdf is actually called (it's an optional extra).
    from ssik._urdf import load_urdf_kinbody_normalized

    # urchin raises ValueError on missing files; rewrite to the more
    # idiomatic FileNotFoundError for the public API contract.
    path_obj = Path(path)
    if not path_obj.exists():
        raise FileNotFoundError(f"URDF file not found: {path_obj}")

    kb = load_urdf_kinbody_normalized(path, base, ee)
    return cls(kb, policy=policy)

solve

solve(
    T_target: ArrayLike,
    *,
    explain: Literal[False] = False,
    max_solutions: int | None = None,
    q_seed: ArrayLike | None = None,
    respect_limits: bool = True,
    allow_refinement: bool = False,
    policy: TolerancePolicy = DEFAULT_TOLERANCE_POLICY,
    refinement_max_iters: int = 15,
    **solver_kwargs: Any,
) -> list[Solution]
solve(
    T_target: ArrayLike,
    *,
    explain: Literal[True],
    max_solutions: int | None = None,
    q_seed: ArrayLike | None = None,
    respect_limits: bool = True,
    allow_refinement: bool = False,
    policy: TolerancePolicy = DEFAULT_TOLERANCE_POLICY,
    refinement_max_iters: int = 15,
    **solver_kwargs: Any,
) -> tuple[list[Solution], Diagnostic]
solve(
    T_target: ArrayLike,
    *,
    explain: bool = False,
    max_solutions: int | None = None,
    q_seed: ArrayLike | None = None,
    respect_limits: bool = True,
    allow_refinement: bool = False,
    policy: TolerancePolicy = DEFAULT_TOLERANCE_POLICY,
    refinement_max_iters: int = 15,
    **solver_kwargs: Any,
) -> list[Solution] | tuple[list[Solution], Diagnostic]

Inverse kinematics: find every q such that fk(q) ≈ T_target.

Parameters:

Name Type Description Default
T_target ArrayLike

4x4 SE(3) target pose.

required
explain bool

when True, returns (sols, Diagnostic) instead of just sols. The diagnostic carries dispatch + filter attribution for triaging empty-list failures. Default False preserves the v1.0 return signature.

False
max_solutions int | None

optional cap on returned IKs (post-dedup, post-limits filter). None = full redundancy enumeration. 1 combined with q_seed is the trajectory-tracking idiom. On 7R jointlock arms the cap also short-circuits the lock-sweep internally for a 10-15x speedup.

None
q_seed ArrayLike | None

optional length-:attr:dof seed. When provided, returned solutions are sorted by wrap-to-pi distance from q_seed (closest first). On jointlock-7R arms it also reorders the internal lock-sample sweep.

None
respect_limits bool

when True (default), solutions outside URDF joint limits are dropped. Pass False for the raw geometric set (analysis / debugging).

True
allow_refinement bool

opt into Newton polish for near-miss algebraic candidates. Default False -- the algebraic path is already at machine precision on tier-0 / SRS arms. Set True on tier-2 RR arms to recover edge-case candidates whose algebraic FK drifts above fk_atol.

False
policy TolerancePolicy

tolerance policy. Rarely customised. Defaults to :data:~ssik.core.tolerances.DEFAULT_TOLERANCE_POLICY.

DEFAULT_TOLERANCE_POLICY
refinement_max_iters int

cap on Newton iterations per candidate when allow_refinement=True.

15
solver_kwargs Any

forwarded verbatim to the dispatched solver for power users (swivel_samples for SRS-class, linearity_joint for RR, etc.).

{}

Returns:

Type Description
list[Solution] | tuple[list[Solution], Diagnostic]

list of :class:Solution, one per analytical IK branch. Empty list iff no candidate FK-closed within policy.subproblem_numerical (or all IKs were filtered by respect_limits=True). Check if not sols: for "unreachable target". When explain=True, returns (sols, Diagnostic) -- inspect Diagnostic.summary() to attribute empty-list failures.

Raises:

Type Description
ValueError

if T_target.shape != (4, 4) or len(q_seed) != dof when q_seed is given.

Source code in src/ssik/manipulator.py
def solve(
    self,
    T_target: ArrayLike,
    *,
    explain: bool = False,
    max_solutions: int | None = None,
    q_seed: ArrayLike | None = None,
    respect_limits: bool = True,
    allow_refinement: bool = False,
    policy: TolerancePolicy = DEFAULT_TOLERANCE_POLICY,
    refinement_max_iters: int = 15,
    **solver_kwargs: Any,
) -> list[Solution] | tuple[list[Solution], Diagnostic]:
    """Inverse kinematics: find every ``q`` such that ``fk(q) ≈ T_target``.

    :param T_target: 4x4 SE(3) target pose.
    :param explain: when ``True``, returns ``(sols, Diagnostic)``
        instead of just ``sols``. The diagnostic carries dispatch +
        filter attribution for triaging empty-list failures. Default
        ``False`` preserves the v1.0 return signature.
    :param max_solutions: optional cap on returned IKs (post-dedup,
        post-limits filter). ``None`` = full redundancy enumeration.
        ``1`` combined with ``q_seed`` is the trajectory-tracking idiom.
        On 7R jointlock arms the cap also short-circuits the lock-sweep
        internally for a 10-15x speedup.
    :param q_seed: optional length-:attr:`dof` seed. When provided,
        returned solutions are sorted by wrap-to-pi distance from
        ``q_seed`` (closest first). On jointlock-7R arms it also
        reorders the internal lock-sample sweep.
    :param respect_limits: when ``True`` (default), solutions outside
        URDF joint limits are dropped. Pass ``False`` for the raw
        geometric set (analysis / debugging).
    :param allow_refinement: opt into Newton polish for near-miss
        algebraic candidates. Default ``False`` -- the algebraic
        path is already at machine precision on tier-0 / SRS arms.
        Set ``True`` on tier-2 RR arms to recover edge-case
        candidates whose algebraic FK drifts above ``fk_atol``.
    :param policy: tolerance policy. Rarely customised. Defaults to
        :data:`~ssik.core.tolerances.DEFAULT_TOLERANCE_POLICY`.
    :param refinement_max_iters: cap on Newton iterations per candidate
        when ``allow_refinement=True``.
    :param solver_kwargs: forwarded verbatim to the dispatched solver
        for power users (``swivel_samples`` for SRS-class,
        ``linearity_joint`` for RR, etc.).

    :returns: list of :class:`Solution`, one per analytical IK branch.
        Empty list iff no candidate FK-closed within
        ``policy.subproblem_numerical`` (or all IKs were filtered by
        ``respect_limits=True``). Check ``if not sols:`` for
        "unreachable target". When ``explain=True``, returns
        ``(sols, Diagnostic)`` -- inspect ``Diagnostic.summary()``
        to attribute empty-list failures.

    :raises ValueError: if ``T_target.shape != (4, 4)`` or
        ``len(q_seed) != dof`` when ``q_seed`` is given.
    """
    from ssik.postprocess import nearest_to_seed as _ps_nearest_to_seed
    from ssik.postprocess import respect_limits as _ps_respect_limits
    from ssik.postprocess import wrap_to_limits as _ps_wrap_to_limits

    T = np.asarray(T_target, dtype=np.float64)
    if T.shape != (4, 4):
        raise ValueError(f"solve expected T_target of shape (4, 4), got {T.shape}")
    if q_seed is not None:
        q_seed_arr: NDArray[np.float64] | None = np.asarray(q_seed, dtype=np.float64)
        assert q_seed_arr is not None
        if q_seed_arr.shape != (self.dof,):
            raise ValueError(f"q_seed expected shape ({self.dof},), got {q_seed_arr.shape}")
    else:
        q_seed_arr = None

    # Filter kwargs by the dispatched solver's signature so callers can
    # pass q_seed (or any other not-universally-supported kwarg) without
    # tripping TypeError on solvers that don't accept it. The dispatch
    # is determined at __init__ time, so the signature lookup is per-IK
    # but cheap (~5 us).
    sig = inspect.signature(self._solver_module.solve)
    params = sig.parameters
    kwargs: dict[str, Any] = {"policy": policy}
    if "allow_refinement" in params:
        kwargs["allow_refinement"] = allow_refinement
    if "refinement_max_iters" in params:
        kwargs["refinement_max_iters"] = refinement_max_iters
    # When respect_limits=True, don't short-circuit the inner solver's
    # sweep on max_solutions: the closest-to-seed branch the solver
    # picks first may be out-of-limits and the postprocess pass would
    # drop it, leaving zero results. Force the full sweep, then
    # filter + trim. The user opts out via respect_limits=False.
    if "max_solutions" in params:
        kwargs["max_solutions"] = None if respect_limits else max_solutions
    if q_seed_arr is not None and "q_seed" in params:
        kwargs["q_seed"] = q_seed_arr
    # Power-user kwargs override our defaults.
    kwargs.update(solver_kwargs)

    # Internal solver functions still return (sols, is_ls); unwrap the
    # tuple at the public-API boundary. `is_ls` is redundant with
    # `len(sols) == 0` in every shipped solver -- ssik #238 item 1.
    sols, _is_ls = self._solver_module.solve(self._kb, T, **kwargs)
    raw_candidate_count = len(sols)

    # Cross-arm postprocess pass: solvers that didn't honour kwargs
    # natively get them applied here so the public API is uniform.
    # Order: wrap_to_limits first (try +/- 2pi shift to bring branches
    # into the URDF range), THEN respect_limits (drop anything still
    # outside). Without the shift, IKs returned in [-2pi, 0] would
    # erroneously be filtered on arms with limits in [0, 2pi]
    # (the JACO 2 case).
    if respect_limits:
        sols = _ps_wrap_to_limits(sols, self._kb)
        pre_limit_count = len(sols)
        sols = _ps_respect_limits(sols, self._kb)
        dropped_by_limits = pre_limit_count - len(sols)
    else:
        dropped_by_limits = 0
    if q_seed_arr is not None:
        sols = _ps_nearest_to_seed(sols, q_seed_arr)
    if max_solutions is not None and len(sols) > max_solutions:
        dropped_by_max_solutions = len(sols) - max_solutions
        sols = sols[:max_solutions]
    else:
        dropped_by_max_solutions = 0
    result: list[Solution] = sols
    if not explain:
        return result

    refinement_engaged = sum(1 for s in result if s.refinement_used == "lm")
    max_fk = max((s.fk_residual for s in result), default=float("nan"))
    diag = Diagnostic(
        solver_name=self._plan.solver_name,
        solver_tier=self._plan.tier,
        dispatch_reason=self._plan.reason,
        raw_candidates=raw_candidate_count,
        dropped_by_limits=dropped_by_limits,
        dropped_by_max_solutions=dropped_by_max_solutions,
        final_count=len(result),
        max_fk_residual=max_fk,
        refinement_engaged=refinement_engaged,
        fk_atol=policy.subproblem_numerical,
    )
    return result, diag

fk

fk(q: ArrayLike) -> NDArray[np.float64]

Forward kinematics: return the 4x4 SE(3) pose at config q.

Parameters:

Name Type Description Default
q ArrayLike

joint vector of length :attr:dof. Float-castable (list, tuple, numpy array all work).

required

Returns:

Type Description
NDArray[float64]

4x4 numpy array. Top-left 3x3 is the end-effector rotation matrix; column 3 (rows 0..2) is the position.

Raises:

Type Description
ValueError

if len(q) != dof.

Source code in src/ssik/manipulator.py
def fk(self, q: ArrayLike) -> NDArray[np.float64]:
    """Forward kinematics: return the 4x4 SE(3) pose at config ``q``.

    :param q: joint vector of length :attr:`dof`. Float-castable
        (list, tuple, numpy array all work).

    :returns: 4x4 numpy array. Top-left 3x3 is the end-effector
        rotation matrix; column 3 (rows 0..2) is the position.

    :raises ValueError: if ``len(q) != dof``.
    """
    q_arr = np.asarray(q, dtype=np.float64)
    if q_arr.shape != (self.dof,):
        raise ValueError(f"fk expected q of shape ({self.dof},), got {q_arr.shape}")
    result: NDArray[np.float64] = poe_forward_kinematics(self._kb, q_arr)
    return result

Per-call return: Solution

A single analytical IK solution.

Parameters:

Name Type Description Default
q NDArray[float64]

joint-angle vector. Length matches the chain's DOF.

required
fk_residual float

||FK(q) - T_target||_F at the moment the solver returned the candidate. The caller can compare against any target tolerance; the solver's own fk_atol was a filter, not a contract on the value reported here.

required
refinement_used RefinementMode

"none" if the solution came directly from the algebraic / closed-form path; "lm" if Levenberg-Marquardt refinement polished it (when allow_refinement=True).

'none'
Source code in src/ssik/core/solution.py
@dataclass(frozen=True)
class Solution:
    """A single analytical IK solution.

    :param q: joint-angle vector. Length matches the chain's DOF.
    :param fk_residual: ``||FK(q) - T_target||_F`` at the moment the solver
        returned the candidate. The caller can compare against any target
        tolerance; the solver's own ``fk_atol`` was a *filter*, not a
        contract on the value reported here.
    :param refinement_used: ``"none"`` if the solution came directly from
        the algebraic / closed-form path; ``"lm"`` if Levenberg-Marquardt
        refinement polished it (when ``allow_refinement=True``).
    """

    q: NDArray[np.float64]
    fk_residual: float
    refinement_used: RefinementMode = "none"

Diagnostic record: Diagnostic

Returned alongside the solution list when solve(T, explain=True).

Per-call diagnostic record from solve(T, explain=True).

All counts are post-filter aggregates -- the solver's own enumeration cost (number of raw algebraic candidates before any filtering) is in raw_candidates; each subsequent filter is a delta. final_count == len(returned_solutions).

The fields are deliberately data-only (no methods that re-run the solve, no live references to the kinbody). A diagnostic is a snapshot, safe to log / serialise.

Source code in src/ssik/core/diagnostic.py
@dataclass(frozen=True)
class Diagnostic:
    """Per-call diagnostic record from ``solve(T, explain=True)``.

    All counts are post-filter aggregates -- the solver's own
    enumeration cost (number of raw algebraic candidates before any
    filtering) is in ``raw_candidates``; each subsequent filter is a
    delta. ``final_count == len(returned_solutions)``.

    The fields are deliberately data-only (no methods that re-run the
    solve, no live references to the kinbody). A diagnostic is a
    snapshot, safe to log / serialise.
    """

    solver_name: str
    """Dispatched solver, e.g. ``"ikgeo.three_parallel"``."""

    solver_tier: int
    """0 = closed-form, 1 = univariate search, 2 = bivariate search."""

    dispatch_reason: str
    """Human-readable explanation of why the dispatcher picked this solver.
    Often the most useful field for 'why did ssik refuse my arm?' triage."""

    raw_candidates: int
    """Raw analytical candidate count returned by the inner solver, before
    any post-processing. ``0`` means the solver itself returned nothing --
    pose is outside the analytical reach or the solver's preconditions
    aren't met. ``>0`` with ``final_count == 0`` means every candidate was
    filtered (limits, etc.)."""

    dropped_by_limits: int
    """Candidates that fell outside URDF joint limits (after the ``q ± 2π``
    rescue pass). ``0`` when ``respect_limits=False`` was passed."""

    dropped_by_max_solutions: int
    """Surviving candidates truncated by the ``max_solutions`` cap."""

    final_count: int
    """Number of solutions in the returned list."""

    max_fk_residual: float
    """Worst ``fk_residual`` among returned solutions. ``nan`` when
    ``final_count == 0``."""

    refinement_engaged: int
    """How many candidates ran through Levenberg-Marquardt polish (when
    ``allow_refinement=True`` was passed). ``0`` when refinement was off."""

    fk_atol: float
    """The FK-closure threshold the solver used. Useful when the user
    customised the tolerance policy and wants the live value back."""

    warnings: tuple[str, ...] = field(default_factory=tuple)
    """Optional conditioning / robustness flags raised during the solve.
    Empty tuple in the common-path. Today: forward-compatible reservation;
    populated by the HP / RR solvers once they wire up conditioning checks
    (#178)."""

    def summary(self) -> str:
        """One-paragraph human-readable summary for logging / triage.

        Distinguishes the four common cases:
        - reachable (returned >=1 IK)
        - unreachable (0 raw candidates)
        - all-filtered (raw candidates > 0, final 0 -- joint limits etc.)
        - capped (max_solutions truncation)
        """
        lines = [
            f"solver: {self.solver_name} (tier {self.solver_tier})",
            f"dispatch: {self.dispatch_reason}",
        ]
        if self.final_count > 0:
            lines.append(
                f"  -> {self.raw_candidates} candidates "
                f"-> {self.final_count} returned (max FK {self.max_fk_residual:.1e}, "
                f"threshold {self.fk_atol:.0e})"
            )
            if self.dropped_by_limits:
                lines.append(f"  filtered by joint limits: {self.dropped_by_limits}")
            if self.dropped_by_max_solutions:
                lines.append(f"  capped by max_solutions: {self.dropped_by_max_solutions}")
        elif self.raw_candidates == 0:
            lines.append(
                "  -> 0 raw candidates: pose appears unreachable "
                "(or outside this solver's analytical envelope)"
            )
        else:
            lines.append(f"  -> {self.raw_candidates} raw candidates, all filtered:")
            if self.dropped_by_limits:
                lines.append(
                    f"     dropped by joint limits: {self.dropped_by_limits} "
                    f"(pass respect_limits=False for the raw geometric set)"
                )
        if self.refinement_engaged:
            lines.append(f"  LM polish engaged on {self.refinement_engaged} candidates")
        for w in self.warnings:
            lines.append(f"  warning: {w}")
        return "\n".join(lines)

solver_name instance-attribute

solver_name: str

Dispatched solver, e.g. "ikgeo.three_parallel".

solver_tier instance-attribute

solver_tier: int

0 = closed-form, 1 = univariate search, 2 = bivariate search.

dispatch_reason instance-attribute

dispatch_reason: str

Human-readable explanation of why the dispatcher picked this solver. Often the most useful field for 'why did ssik refuse my arm?' triage.

raw_candidates instance-attribute

raw_candidates: int

Raw analytical candidate count returned by the inner solver, before any post-processing. 0 means the solver itself returned nothing -- pose is outside the analytical reach or the solver's preconditions aren't met. >0 with final_count == 0 means every candidate was filtered (limits, etc.).

dropped_by_limits instance-attribute

dropped_by_limits: int

Candidates that fell outside URDF joint limits (after the q ± 2π rescue pass). 0 when respect_limits=False was passed.

dropped_by_max_solutions instance-attribute

dropped_by_max_solutions: int

Surviving candidates truncated by the max_solutions cap.

final_count instance-attribute

final_count: int

Number of solutions in the returned list.

max_fk_residual instance-attribute

max_fk_residual: float

Worst fk_residual among returned solutions. nan when final_count == 0.

refinement_engaged instance-attribute

refinement_engaged: int

How many candidates ran through Levenberg-Marquardt polish (when allow_refinement=True was passed). 0 when refinement was off.

fk_atol instance-attribute

fk_atol: float

The FK-closure threshold the solver used. Useful when the user customised the tolerance policy and wants the live value back.

warnings class-attribute instance-attribute

warnings: tuple[str, ...] = field(default_factory=tuple)

Optional conditioning / robustness flags raised during the solve. Empty tuple in the common-path. Today: forward-compatible reservation; populated by the HP / RR solvers once they wire up conditioning checks (#178).

summary

summary() -> str

One-paragraph human-readable summary for logging / triage.

Distinguishes the four common cases: - reachable (returned >=1 IK) - unreachable (0 raw candidates) - all-filtered (raw candidates > 0, final 0 -- joint limits etc.) - capped (max_solutions truncation)

Source code in src/ssik/core/diagnostic.py
def summary(self) -> str:
    """One-paragraph human-readable summary for logging / triage.

    Distinguishes the four common cases:
    - reachable (returned >=1 IK)
    - unreachable (0 raw candidates)
    - all-filtered (raw candidates > 0, final 0 -- joint limits etc.)
    - capped (max_solutions truncation)
    """
    lines = [
        f"solver: {self.solver_name} (tier {self.solver_tier})",
        f"dispatch: {self.dispatch_reason}",
    ]
    if self.final_count > 0:
        lines.append(
            f"  -> {self.raw_candidates} candidates "
            f"-> {self.final_count} returned (max FK {self.max_fk_residual:.1e}, "
            f"threshold {self.fk_atol:.0e})"
        )
        if self.dropped_by_limits:
            lines.append(f"  filtered by joint limits: {self.dropped_by_limits}")
        if self.dropped_by_max_solutions:
            lines.append(f"  capped by max_solutions: {self.dropped_by_max_solutions}")
    elif self.raw_candidates == 0:
        lines.append(
            "  -> 0 raw candidates: pose appears unreachable "
            "(or outside this solver's analytical envelope)"
        )
    else:
        lines.append(f"  -> {self.raw_candidates} raw candidates, all filtered:")
        if self.dropped_by_limits:
            lines.append(
                f"     dropped by joint limits: {self.dropped_by_limits} "
                f"(pass respect_limits=False for the raw geometric set)"
            )
    if self.refinement_engaged:
        lines.append(f"  LM polish engaged on {self.refinement_engaged} candidates")
    for w in self.warnings:
        lines.append(f"  warning: {w}")
    return "\n".join(lines)

Tuning: TolerancePolicy

Numeric tolerances for kinematic predicates and subproblem solvers.

Structural-predicate fields are consumed by :mod:ssik.kinematics.predicates and :func:ssik.core.topology.describe_topology.

Subproblem-solver fields are consumed by SP1-SP6 under :mod:ssik.subproblems. Their names capture the reason each tolerance exists so diagnostic messages can say e.g. "SP6 sign branch rejected: closure distance 1.2e-4 > subproblem_numerical 1e-5" rather than citing raw numbers.

Attributes: axis_parallel: cross-product magnitude below which two unit-vector axes are considered parallel (or anti-parallel). For unit vectors ||a x b|| = sin(theta) so the default 1e-8 accepts axes differing by up to ~1 microradian. axis_intersect: perpendicular distance below which two lines in 3D are considered to intersect. Default matches the axis_parallel tolerance in spirit -- metric-scale chains. subproblem_feasibility: threshold on residuals that decide whether a subproblem input admits an exact solution or only a least-squares approximation (is_ls=True). Used by SP1's |p_perp| vs |q_perp| check, SP4's |rhs| - R boundary, SP2's sphere mismatch, etc. subproblem_numerical: threshold for filtering spurious candidates produced by quartic / ellipse root-finding inside SP5 and SP6. Unit-circle closure is checked to this tolerance; returned solutions that fail are dropped. subproblem_degeneracy: rank / collinearity threshold. A QR leading coefficient or sin-of-angle-between-axes below this value marks the input as degenerate and SP6/aux return ([], is_ls=True) rather than produce nonsense. subproblem_dedup: angle-space tolerance for deduplicating SP5/SP6 solutions. Two solutions within this radian distance (on every joint, mod 2pi) collapse to one. Larger than subproblem_numerical because the quartic-root backsolve amplifies residual-level error into coarser angle-level error; default 1e-3 (~0.06 degrees) is the physical indistinguishability threshold for robot kinematics.

Source code in src/ssik/core/tolerances.py
@dataclass(frozen=True)
class TolerancePolicy:
    """Numeric tolerances for kinematic predicates and subproblem solvers.

    Structural-predicate fields are consumed by
    :mod:`ssik.kinematics.predicates` and
    :func:`ssik.core.topology.describe_topology`.

    Subproblem-solver fields are consumed by SP1-SP6 under
    :mod:`ssik.subproblems`. Their names capture the *reason* each tolerance
    exists so diagnostic messages can say e.g. ``"SP6 sign branch rejected:
    closure distance 1.2e-4 > subproblem_numerical 1e-5"`` rather than citing
    raw numbers.

    Attributes:
        axis_parallel: cross-product magnitude below which two unit-vector
            axes are considered parallel (or anti-parallel). For unit
            vectors ``||a x b|| = sin(theta)`` so the default ``1e-8``
            accepts axes differing by up to ~1 microradian.
        axis_intersect: perpendicular distance below which two lines in
            3D are considered to intersect. Default matches the
            ``axis_parallel`` tolerance in spirit -- metric-scale chains.
        subproblem_feasibility: threshold on residuals that decide whether
            a subproblem input admits an *exact* solution or only a
            least-squares approximation (``is_ls=True``). Used by SP1's
            ``|p_perp| vs |q_perp|`` check, SP4's ``|rhs| - R`` boundary,
            SP2's sphere mismatch, etc.
        subproblem_numerical: threshold for filtering spurious candidates
            produced by quartic / ellipse root-finding inside SP5 and SP6.
            Unit-circle closure is checked to this tolerance; returned
            solutions that fail are dropped.
        subproblem_degeneracy: rank / collinearity threshold. A QR leading
            coefficient or sin-of-angle-between-axes below this value
            marks the input as degenerate and SP6/aux return
            ``([], is_ls=True)`` rather than produce nonsense.
        subproblem_dedup: angle-space tolerance for deduplicating SP5/SP6
            solutions. Two solutions within this radian distance (on every
            joint, mod 2pi) collapse to one. Larger than
            ``subproblem_numerical`` because the quartic-root backsolve
            amplifies residual-level error into coarser angle-level error;
            default ``1e-3`` (~0.06 degrees) is the physical
            indistinguishability threshold for robot kinematics.
    """

    axis_parallel: float = 1e-8
    axis_intersect: float = 1e-8
    subproblem_feasibility: float = 1e-9
    subproblem_numerical: float = 1e-5
    subproblem_degeneracy: float = 1e-12
    subproblem_dedup: float = 1e-3

Postprocess helpers

The solve() pipeline already applies these by default (when respect_limits=True); they're exposed for callers who want a different order, an extra filter step, or to compose with collision/dexterity scoring.

Drop solutions where any joint's q value is outside its reachable range.

Joints with limits=None are unconstrained (continuous joints, or fixtures that don't supply limits) and never reject a solution. Joints with limits=(lo, hi) reject any solution where q[i] < lo or q[i] > hi strictly; values exactly on the boundary are accepted.

Parameters:

Name Type Description Default
sols list[Solution]

candidate solutions (e.g. output of an ssik solver's solve()).

required
kb KinBody

the same :class:KinBody used for the IK call. Joint limits come from kb.joints[i].limits.

required

Returns:

Type Description
list[Solution]

filtered solutions; preserves input order.

Source code in src/ssik/postprocess.py
def respect_limits(sols: list[Solution], kb: KinBody) -> list[Solution]:
    """Drop solutions where any joint's q value is outside its reachable range.

    Joints with ``limits=None`` are unconstrained (continuous joints, or
    fixtures that don't supply limits) and never reject a solution. Joints
    with ``limits=(lo, hi)`` reject any solution where ``q[i] < lo`` or
    ``q[i] > hi`` strictly; values exactly on the boundary are accepted.

    :param sols: candidate solutions (e.g. output of an ssik solver's
        ``solve()``).
    :param kb: the same :class:`KinBody` used for the IK call. Joint limits
        come from ``kb.joints[i].limits``.
    :returns: filtered solutions; preserves input order.
    """
    n_joints = len(kb.joints)
    kept: list[Solution] = []
    for sol in sols:
        if len(sol.q) != n_joints:
            raise ValueError(f"solution q-length {len(sol.q)} doesn't match kb DOF {n_joints}")
        within = True
        for i, joint in enumerate(kb.joints):
            if joint.limits is None:
                continue
            lo, hi = joint.limits
            if sol.q[i] < lo or sol.q[i] > hi:
                within = False
                break
        if within:
            kept.append(sol)
    return kept

Try wrapping each joint's q value by ±2*pi integer multiples to bring it into the joint's reachable range.

A revolute joint at q = 3.0 with limits [-pi, pi] is FK-equivalent to q - 2*pi ≈ -3.28, which is also outside the range, so neither wrap fits and the solution stays at q = 3.0 (and would be dropped by :func:respect_limits if called next). A joint at q = 4.0 with limits [-pi, pi] wraps to q - 2*pi ≈ -2.28 which is in range: we keep the wrapped value.

Joints with limits=None are left unchanged (no constraint to wrap into). Prismatic joints are left unchanged (no rotational periodicity).

Search is over k ∈ {-2, -1, 0, +1, +2} integer multiples of 2*pi; that covers any joint whose limits span up to ±5*pi (more than enough for any commercial arm). The smallest-|k| wrap that lands in range wins, biasing toward the original value.

Parameters:

Name Type Description Default
sols list[Solution]

candidate solutions.

required
kb KinBody

the same :class:KinBody used for the IK call.

required

Returns:

Type Description
list[Solution]

solutions with each q-vector adjusted joint-wise; preserves input order; returns Solution instances with the wrapped q and other fields unchanged.

Source code in src/ssik/postprocess.py
def wrap_to_limits(sols: list[Solution], kb: KinBody) -> list[Solution]:
    """Try wrapping each joint's q value by ``±2*pi`` integer multiples to
    bring it into the joint's reachable range.

    A revolute joint at ``q = 3.0`` with limits ``[-pi, pi]`` is FK-equivalent
    to ``q - 2*pi ≈ -3.28``, which is *also* outside the range, so neither
    wrap fits and the solution stays at ``q = 3.0`` (and would be dropped by
    :func:`respect_limits` if called next). A joint at ``q = 4.0`` with
    limits ``[-pi, pi]`` wraps to ``q - 2*pi ≈ -2.28`` which is in range:
    we keep the wrapped value.

    Joints with ``limits=None`` are left unchanged (no constraint to wrap
    into). Prismatic joints are left unchanged (no rotational periodicity).

    Search is over ``k ∈ {-2, -1, 0, +1, +2}`` integer multiples of ``2*pi``;
    that covers any joint whose limits span up to ±5*pi (more than enough for
    any commercial arm). The smallest-|k| wrap that lands in range wins,
    biasing toward the original value.

    :param sols: candidate solutions.
    :param kb: the same :class:`KinBody` used for the IK call.
    :returns: solutions with each q-vector adjusted joint-wise; preserves
        input order; returns ``Solution`` instances with the wrapped q
        and other fields unchanged.
    """
    n_joints = len(kb.joints)
    out: list[Solution] = []
    for sol in sols:
        if len(sol.q) != n_joints:
            raise ValueError(f"solution q-length {len(sol.q)} doesn't match kb DOF {n_joints}")
        q_new = np.asarray(sol.q, dtype=np.float64).copy()
        for i, joint in enumerate(kb.joints):
            if joint.limits is None or joint.joint_type != "revolute":
                continue
            lo, hi = joint.limits
            q_i = float(q_new[i])
            if lo <= q_i <= hi:
                continue
            # Try wraps with smallest |k| first.
            best = q_i
            best_in_range = False
            for k in (1, -1, 2, -2):
                candidate = q_i + 2.0 * np.pi * k
                if lo <= candidate <= hi:
                    best = candidate
                    best_in_range = True
                    break
            if best_in_range:
                q_new[i] = best
        out.append(replace(sol, q=q_new))
    return out

Sort solutions by joint-space distance to a reference configuration.

The "wrap-to-pi" distance treats angle differences modulo 2*pi, so e.g. q=3.0 and q_seed=-3.0 are at distance |wrap(3.0 - (-3.0))| = |wrap(6.0)| = |6.0 - 2*pi| ≈ 0.28, not 6.0. This is the right metric for revolute-joint similarity.

Parameters:

Name Type Description Default
sols list[Solution]

candidate solutions.

required
q_seed NDArray[float64]

reference joint configuration (length matches the chain's DOF).

required
metric str

one of "wrap_l2" (default; sum-of-squares of wrap-to-pi differences) or "wrap_linf" (max wrap-to-pi difference). wrap_l2 is smooth and prefers configurations that are uniformly close; wrap_linf is hard-cap and prefers configurations whose worst-joint deviation is small.

'wrap_l2'

Returns:

Type Description
list[Solution]

solutions sorted by ascending distance to q_seed. Stable sort: ties preserve input order.

Source code in src/ssik/postprocess.py
def nearest_to_seed(
    sols: list[Solution],
    q_seed: NDArray[np.float64],
    *,
    metric: str = "wrap_l2",
) -> list[Solution]:
    """Sort solutions by joint-space distance to a reference configuration.

    The "wrap-to-pi" distance treats angle differences modulo ``2*pi``, so
    e.g. ``q=3.0`` and ``q_seed=-3.0`` are at distance
    ``|wrap(3.0 - (-3.0))| = |wrap(6.0)| = |6.0 - 2*pi| ≈ 0.28``, not 6.0.
    This is the right metric for revolute-joint similarity.

    :param sols: candidate solutions.
    :param q_seed: reference joint configuration (length matches the chain's
        DOF).
    :param metric: one of ``"wrap_l2"`` (default; sum-of-squares of
        wrap-to-pi differences) or ``"wrap_linf"`` (max wrap-to-pi
        difference). ``wrap_l2`` is smooth and prefers configurations that
        are uniformly close; ``wrap_linf`` is hard-cap and prefers
        configurations whose worst-joint deviation is small.
    :returns: solutions sorted by ascending distance to ``q_seed``. Stable
        sort: ties preserve input order.
    """
    if metric not in ("wrap_l2", "wrap_linf"):
        raise ValueError(f"unknown metric {metric!r}; expected 'wrap_l2' or 'wrap_linf'")
    seed = np.asarray(q_seed, dtype=np.float64)

    def distance(sol: Solution) -> float:
        diffs = [_wrap_to_pi(float(sol.q[i] - seed[i])) for i in range(len(seed))]
        if metric == "wrap_l2":
            return float(np.sqrt(sum(d * d for d in diffs)))
        # wrap_linf
        return float(max(abs(d) for d in diffs))

    # Python's sort is stable, so ties preserve input order.
    return sorted(sols, key=distance)

Truncate to the first k solutions.

Use after :func:nearest_to_seed (or any other ranking) to keep only the top-k matches. k <= 0 returns an empty list.

Renamed from max_solutions in v1.0 to avoid name collision with the max_solutions kwarg on Manipulator.solve / artifact solve() -- they have different shapes (kwarg is an int passed in; this function takes (sols, k)).

Parameters:

Name Type Description Default
sols list[Solution]

candidate solutions, typically already sorted.

required
k int

maximum number of solutions to keep.

required

Returns:

Type Description
list[Solution]

sols[:max(k, 0)].

Source code in src/ssik/postprocess.py
def take_first(sols: list[Solution], k: int) -> list[Solution]:
    """Truncate to the first ``k`` solutions.

    Use after :func:`nearest_to_seed` (or any other ranking) to keep only
    the top-``k`` matches. ``k <= 0`` returns an empty list.

    Renamed from ``max_solutions`` in v1.0 to avoid name collision with
    the ``max_solutions`` kwarg on ``Manipulator.solve`` / artifact
    ``solve()`` -- they have different shapes (kwarg is an int passed in;
    this function takes ``(sols, k)``).

    :param sols: candidate solutions, typically already sorted.
    :param k: maximum number of solutions to keep.
    :returns: ``sols[:max(k, 0)]``.
    """
    return list(sols[: max(k, 0)])

CLI: ssik build

ssik build <urdf> --base <link> --ee <link> [--out <path>]
ssik classify <urdf> --base <link> --ee <link>
ssik add-arm <urdf> --base <link> --ee <link> --name <arm>

Full help: ssik <command> --help. See Setting up your robot for the full URDF-to-artifact workflow.