# `BB.IK.Solver`
[🔗](https://github.com/beam-bots/bb/blob/main/lib/bb/ik/solver.ex#L5)

Behaviour for inverse kinematics solvers in the BB ecosystem.

This behaviour defines a common interface for IK solvers, allowing
different algorithms (FABRIK, Jacobian, analytical, etc.) to be
used interchangeably.

## Implementing a Solver

    defmodule MyApp.IK.CustomSolver do
      @behaviour BB.IK.Solver

      @impl true
      def solve(robot, state_or_positions, target_link, target, opts) do
        # Your implementation here
        {:ok, positions, meta}
      end
    end

## Target Types

Solvers accept targets as:
- `Vec3.t()` - Position only
- `{Vec3.t(), orientation}` - Position with orientation constraint
- `Transform.t()` - 4x4 homogeneous transform (extracts position and quaternion)

Orientation can be specified as:
- `:none` - Position only (default)
- `{:axis, Vec3.t()}` - Tool pointing direction (end-effector Z-axis alignment)
- `{:quaternion, Quaternion.t()}` - Full 6-DOF orientation

## Options

Common options that solvers should support:
- `:max_iterations` - Maximum solver iterations (default: 50)
- `:tolerance` - Position convergence tolerance in metres (default: 1.0e-4)
- `:orientation_tolerance` - Angular convergence tolerance in radians (default: 0.01)
- `:strict_orientation` - If true, error when orientation unsatisfiable; if false, best-effort (default: false)
- `:respect_limits` - Whether to clamp to joint limits (default: true)
- `:initial_positions` - Starting joint positions (default: from state)

## Error Types

Solvers return structured errors from `BB.Error.Kinematics`:

- `%BB.Error.Kinematics.UnknownLink{}` - Target link not found in robot topology
- `%BB.Error.Kinematics.NoDofs{}` - Chain has no movable joints
- `%BB.Error.Kinematics.Unreachable{}` - Target outside workspace
- `%BB.Error.Kinematics.NoSolution{}` - Solver failed to converge

# `kinematics_error`

```elixir
@type kinematics_error() ::
  BB.Error.Kinematics.UnknownLink.t()
  | BB.Error.Kinematics.NoDofs.t()
  | BB.Error.Kinematics.Unreachable.t()
  | BB.Error.Kinematics.NoSolution.t()
```

# `meta`

```elixir
@type meta() :: %{
  iterations: non_neg_integer(),
  residual: float(),
  orientation_residual: float() | nil,
  reached: boolean()
}
```

# `opts`

```elixir
@type opts() :: [
  max_iterations: pos_integer(),
  tolerance: float(),
  orientation_tolerance: float(),
  strict_orientation: boolean(),
  respect_limits: boolean(),
  initial_positions: positions() | nil
]
```

# `orientation_target`

```elixir
@type orientation_target() ::
  :none | {:axis, BB.Math.Vec3.t()} | {:quaternion, BB.Math.Quaternion.t()}
```

Orientation target for IK solving.

- `:none` - Position only (default)
- `{:axis, Vec3.t()}` - Tool pointing direction (end-effector Z-axis)
- `{:quaternion, Quaternion.t()}` - Full 6-DOF orientation

# `positions`

```elixir
@type positions() :: %{required(atom()) =&gt; float()}
```

# `solve_result`

```elixir
@type solve_result() :: {:ok, positions(), meta()} | {:error, kinematics_error()}
```

# `target`

```elixir
@type target() ::
  BB.Math.Vec3.t()
  | {BB.Math.Vec3.t(), orientation_target()}
  | BB.Math.Transform.t()
```

Target for IK solving.

- `Vec3.t()` - Position only
- `{Vec3.t(), orientation_target()}` - Position with orientation constraint
- `Transform.t()` - 4x4 homogeneous transform (extracts position and quaternion)

# `solve`

```elixir
@callback solve(
  robot :: BB.Robot.t(),
  state_or_positions :: BB.Robot.State.t() | positions(),
  target_link :: atom(),
  target :: target(),
  opts :: opts()
) :: solve_result()
```

Solve inverse kinematics for a target link to reach a target position/pose.

## Parameters

- `robot` - The BB.Robot struct containing topology and joint information
- `state_or_positions` - Either a BB.Robot.State or a map of joint positions
- `target_link` - The name of the link to position (end-effector)
- `target` - Target position `{x, y, z}` or 4x4 pose transform
- `opts` - Solver options

## Returns

- `{:ok, positions, meta}` - Successfully solved; positions map and metadata
- `{:error, error}` - Failed to solve; error struct contains all metadata

Error structs include `:positions` with best-effort joint values when applicable.

---

*Consult [api-reference.md](api-reference.md) for complete listing*
