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
66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 | |
solver_name
property
¶
Dotted name of the dispatched solver, e.g. "ikgeo.three_parallel".
kinbody
property
¶
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: |
DEFAULT_TOLERANCE_POLICY
|
Raises:
| Type | Description |
|---|---|
FileNotFoundError
|
if |
ValueError
|
if |
ImportError
|
if the optional dependency |
Source code in src/ssik/manipulator.py
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 |
False
|
max_solutions
|
int | None
|
optional cap on returned IKs (post-dedup,
post-limits filter). |
None
|
q_seed
|
ArrayLike | None
|
optional length-:attr: |
None
|
respect_limits
|
bool
|
when |
True
|
allow_refinement
|
bool
|
opt into Newton polish for near-miss
algebraic candidates. Default |
False
|
policy
|
TolerancePolicy
|
tolerance policy. Rarely customised. Defaults to
:data: |
DEFAULT_TOLERANCE_POLICY
|
refinement_max_iters
|
int
|
cap on Newton iterations per candidate
when |
15
|
solver_kwargs
|
Any
|
forwarded verbatim to the dispatched solver
for power users ( |
{}
|
Returns:
| Type | Description |
|---|---|
list[Solution] | tuple[list[Solution], Diagnostic]
|
list of :class: |
Raises:
| Type | Description |
|---|---|
ValueError
|
if |
Source code in src/ssik/manipulator.py
249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 | |
fk ¶
Forward kinematics: return the 4x4 SE(3) pose at config q.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
q
|
ArrayLike
|
joint vector of length :attr: |
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 |
Source code in src/ssik/manipulator.py
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
|
|
required |
refinement_used
|
RefinementMode
|
|
'none'
|
Source code in src/ssik/core/solution.py
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
29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 | |
solver_tier
instance-attribute
¶
0 = closed-form, 1 = univariate search, 2 = bivariate search.
dispatch_reason
instance-attribute
¶
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 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
¶
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
¶
Surviving candidates truncated by the max_solutions cap.
max_fk_residual
instance-attribute
¶
Worst fk_residual among returned solutions. nan when
final_count == 0.
refinement_engaged
instance-attribute
¶
How many candidates ran through Levenberg-Marquardt polish (when
allow_refinement=True was passed). 0 when refinement was off.
fk_atol
instance-attribute
¶
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
¶
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 ¶
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
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
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
|
required |
kb
|
KinBody
|
the same :class: |
required |
Returns:
| Type | Description |
|---|---|
list[Solution]
|
filtered solutions; preserves input order. |
Source code in src/ssik/postprocess.py
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: |
required |
Returns:
| Type | Description |
|---|---|
list[Solution]
|
solutions with each q-vector adjusted joint-wise; preserves
input order; returns |
Source code in src/ssik/postprocess.py
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'
|
Returns:
| Type | Description |
|---|---|
list[Solution]
|
solutions sorted by ascending distance to |
Source code in src/ssik/postprocess.py
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]
|
|
Source code in src/ssik/postprocess.py
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.