# `BB.Motion`
[🔗](https://github.com/beam-bots/bb/blob/main/lib/bb/motion.ex#L5)

High-level motion primitives that bridge IK solving and actuator commands.

This module provides functions for moving robot end-effectors to target
positions using pluggable IK solvers. It handles the full workflow:
solving IK, updating robot state, and sending commands to actuators.

## Usage

Single-target functions:
- `move_to/4` - Solve IK for one target, update state, send actuator commands
- `solve_only/4` - Solve IK without sending commands (for planning/validation)

Multi-target functions (for coordinated motion like gait):
- `move_to_multi/3` - Solve IK for multiple targets simultaneously
- `solve_only_multi/3` - Solve multiple targets without sending commands

Utility:
- `send_positions/3` - Send pre-computed positions to actuators (bypasses IK)

## Context Sources

Functions accept either:
- A robot module (uses Runtime to get robot and state)
- A `BB.Command.Context` struct (uses context fields directly)

The second form is useful when implementing custom commands that need
to perform IK-based motion.

## Examples

    # Single target
    case BB.Motion.move_to(MyRobot, :gripper, {0.3, 0.2, 0.1}, solver: BB.IK.FABRIK) do
      {:ok, meta} -> IO.puts("Reached target in #{meta.iterations} iterations")
      {:error, %{class: :kinematics} = error} -> IO.puts("Failed: #{BB.Error.message(error)}")
    end

    # Multiple targets (for gait, coordinated motion)
    targets = %{left_foot: {0.1, 0.0, 0.0}, right_foot: {-0.1, 0.0, 0.0}}
    case BB.Motion.move_to_multi(MyRobot, targets, solver: BB.IK.FABRIK) do
      {:ok, results} -> IO.puts("All targets reached")
      {:error, failed_link, error, _results} -> IO.puts("Failed: #{failed_link}")
    end

    # In a custom command handler
    def handle_command(%{target: target}, context) do
      case BB.Motion.move_to(context, :gripper, target, solver: BB.IK.FABRIK) do
        {:ok, meta} -> {:ok, %{residual: meta.residual}}
        {:error, error} -> {:error, error}
      end
    end

    # Just solve without moving (for validation)
    case BB.Motion.solve_only(MyRobot, :gripper, {0.3, 0.2, 0.1}, solver: BB.IK.FABRIK) do
      {:ok, positions, meta} -> IO.inspect(positions, label: "Would set")
      {:error, %BB.Error.Kinematics.Unreachable{}} -> IO.puts("Cannot reach target")
    end

    # Send pre-computed positions
    positions = %{shoulder: 0.5, elbow: 1.2}
    :ok = BB.Motion.send_positions(MyRobot, positions, delivery: :direct)

# `delivery`

```elixir
@type delivery() :: :pubsub | :direct | :sync
```

# `kinematics_error`

```elixir
@type kinematics_error() :: BB.IK.Solver.kinematics_error()
```

# `meta`

```elixir
@type meta() :: BB.IK.Solver.meta()
```

# `motion_result`

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

# `multi_motion_result`

```elixir
@type multi_motion_result() ::
  {:ok, multi_results()} | {:error, atom(), kinematics_error(), multi_results()}
```

# `multi_results`

```elixir
@type multi_results() :: %{
  required(atom()) =&gt; {:ok, positions(), meta()} | {:error, kinematics_error()}
}
```

# `multi_solve_result`

```elixir
@type multi_solve_result() ::
  {:ok, multi_results()} | {:error, atom(), kinematics_error(), multi_results()}
```

# `positions`

```elixir
@type positions() :: BB.IK.Solver.positions()
```

# `robot_or_context`

```elixir
@type robot_or_context() :: module() | BB.Command.Context.t()
```

# `solve_result`

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

# `target`

```elixir
@type target() :: BB.IK.Solver.target()
```

# `targets`

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

# `move_to`

```elixir
@spec move_to(robot_or_context(), atom(), target(), keyword()) :: motion_result()
```

Move an end-effector to a target position.

Solves inverse kinematics for the given target, updates the robot state,
and sends position commands to all actuators controlling the affected joints.

## Options

Required:
- `:solver` - Module implementing `BB.IK.Solver` behaviour

Optional:
- `:delivery` - How to send actuator commands: `:pubsub` (default), `:direct`, or `:sync`
- `:max_iterations` - Maximum solver iterations (passed to solver)
- `:tolerance` - Convergence tolerance in metres (passed to solver)
- `:respect_limits` - Whether to clamp to joint limits (passed to solver)

## Returns

- `{:ok, meta}` - Successfully moved; meta contains solver info (iterations, residual, etc.)
- `{:error, error}` - Failed; error is a struct from `BB.Error.Kinematics`

## Examples

    BB.Motion.move_to(MyRobot, :gripper, {0.3, 0.2, 0.1}, solver: BB.IK.FABRIK)

    BB.Motion.move_to(context, :gripper, target,
      solver: BB.IK.FABRIK,
      delivery: :direct,
      max_iterations: 100
    )

# `move_to_multi`

```elixir
@spec move_to_multi(robot_or_context(), targets(), keyword()) :: multi_motion_result()
```

Move multiple end-effectors to target positions simultaneously.

Useful for coordinated motion like walking gaits where multiple limbs
must move together. Each target is solved independently and all actuator
commands are sent together.

If any target fails to solve, the operation stops and returns an error
with information about which target failed. Targets solved before the
failure are included in the results.

## Options

Required:
- `:solver` - Module implementing `BB.IK.Solver` behaviour

Optional:
- `:delivery` - How to send actuator commands: `:pubsub` (default), `:direct`, or `:sync`
- `:max_iterations` - Maximum solver iterations (passed to solver)
- `:tolerance` - Convergence tolerance in metres (passed to solver)
- `:respect_limits` - Whether to clamp to joint limits (passed to solver)

## Returns

- `{:ok, results}` - All targets solved; results is a map of link → `{:ok, positions, meta}`
- `{:error, failed_link, error, results}` - A target failed; error is from `BB.Error.Kinematics`

## Examples

    targets = %{
      left_foot: {0.1, 0.0, 0.0},
      right_foot: {-0.1, 0.0, 0.0}
    }

    case BB.Motion.move_to_multi(MyRobot, targets, solver: BB.IK.FABRIK) do
      {:ok, results} ->
        IO.puts("All targets reached")

      {:error, failed_link, error, _results} ->
        IO.puts("Failed to reach #{failed_link}: #{BB.Error.message(error)}")
    end

# `send_positions`

```elixir
@spec send_positions(robot_or_context(), positions(), keyword()) :: :ok
```

Send pre-computed joint positions to actuators.

Bypasses IK solving entirely - useful when you've already computed
positions through other means (e.g., trajectory planning, manual input).

Updates the robot state and sends commands to all actuators controlling
the specified joints.

## Options

- `:delivery` - How to send actuator commands: `:pubsub` (default), `:direct`, or `:sync`
- `:velocity` - Velocity hint for actuators (rad/s or m/s)
- `:duration` - Duration hint for actuators (milliseconds)

## Examples

    positions = %{shoulder: 0.5, elbow: 1.2, wrist: 0.3}
    :ok = BB.Motion.send_positions(MyRobot, positions)

    # With direct delivery for lower latency
    :ok = BB.Motion.send_positions(MyRobot, positions, delivery: :direct)

# `solve_only`

```elixir
@spec solve_only(robot_or_context(), atom(), target(), keyword()) :: solve_result()
```

Solve IK without moving the robot.

Useful for:
- Validating that a target is reachable before committing
- Planning multi-step motions
- Visualising solutions before execution

## Options

Same as `move_to/4` except `:delivery` is not used.

## Returns

- `{:ok, positions, meta}` - Successfully solved; positions is a joint name → value map
- `{:error, error}` - Failed to solve; error is a struct from `BB.Error.Kinematics`

## Examples

    # Check if target is reachable
    case BB.Motion.solve_only(MyRobot, :gripper, target, solver: BB.IK.FABRIK) do
      {:ok, _positions, %{reached: true}} -> :reachable
      {:error, _} -> :unreachable
    end

# `solve_only_multi`

```elixir
@spec solve_only_multi(robot_or_context(), targets(), keyword()) ::
  multi_solve_result()
```

Solve IK for multiple targets without moving the robot.

Useful for validating that a set of coordinated targets are all reachable
before committing to motion.

## Options

Same as `move_to_multi/3` except `:delivery` is not used.

## Returns

- `{:ok, results}` - All targets solved; results is a map of link → `{:ok, positions, meta}`
- `{:error, failed_link, error, results}` - A target failed; error is from `BB.Error.Kinematics`

## Examples

    targets = %{left_foot: {0.1, 0.0, 0.0}, right_foot: {-0.1, 0.0, 0.0}}

    case BB.Motion.solve_only_multi(MyRobot, targets, solver: BB.IK.FABRIK) do
      {:ok, results} ->
        Enum.each(results, fn {link, {:ok, _positions, meta}} ->
          IO.puts("#{link}: residual=#{meta.residual}")
        end)

      {:error, failed_link, error, _results} ->
        IO.puts("#{failed_link} is unreachable: #{BB.Error.message(error)}")
    end

---

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