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

Behaviour and API for actuators in the BB framework.

This module serves two purposes:

1. **Behaviour** - Defines callbacks for actuator implementations
2. **API** - Provides functions for sending commands to actuators

## Behaviour

Actuators receive position/velocity/effort commands and drive hardware.
They must implement the `init/1` and `disarm/1` callbacks.

## Usage

The `use BB.Actuator` macro sets up your module as an actuator callback module.
Your module is NOT a GenServer - the framework provides a wrapper GenServer
(`BB.Actuator.Server`) that delegates to your callbacks.

### Required Callbacks

- `init/1` - Initialise actuator state from resolved options
- `disarm/1` - Make hardware safe (called without GenServer state)

### Optional Callbacks

- `handle_options/2` - React to parameter changes at runtime
- `handle_call/3`, `handle_cast/2`, `handle_info/2` - Standard GenServer-style callbacks
- `handle_continue/2`, `terminate/2` - Lifecycle callbacks
- `options_schema/0` - Define accepted configuration options

### Options Schema

If your actuator accepts configuration options, pass them via `:options_schema`:

    defmodule MyServoActuator do
      use BB.Actuator,
        options_schema: [
          channel: [type: {:in, 0..15}, required: true, doc: "PWM channel"],
          controller: [type: :atom, required: true, doc: "Controller name"]
        ]

      @impl BB.Actuator
      def init(opts) do
        channel = Keyword.fetch!(opts, :channel)
        bb = Keyword.fetch!(opts, :bb)
        {:ok, %{channel: channel, bb: bb}}
      end

      @impl BB.Actuator
      def disarm(opts) do
        MyHardware.disable(opts[:controller], opts[:channel])
        :ok
      end

      @impl BB.Actuator
      def handle_cast({:command, msg}, state) do
        # Handle actuator commands
        {:noreply, state}
      end
    end

For actuators that don't need configuration, omit `:options_schema`:

    defmodule SimpleActuator do
      use BB.Actuator

      @impl BB.Actuator
      def init(opts) do
        {:ok, %{bb: opts[:bb]}}
      end

      @impl BB.Actuator
      def disarm(_opts), do: :ok
    end

### Parameter References

Options can reference parameters for runtime-adjustable configuration:

    actuator :motor, {MyMotor, max_effort: param([:motion, :max_effort])}

When the parameter changes, `handle_options/2` is called with the new resolved
options. Override it to update your state accordingly.

### Auto-injected Options

The `:bb` option is automatically provided and should NOT be included in your
`options_schema`. It contains `%{robot: module, path: [atom]}`.

### Safety Registration

Safety registration is automatic - the framework registers your module with
`BB.Safety` using the resolved options. You don't need to call `BB.Safety.register`
manually.

## API

Supports both pubsub delivery (for orchestration, logging, replay) and
direct GenServer delivery (for time-critical control paths).

### Delivery Methods

- **Pubsub** (`set_position/4`, etc.) - Commands published to `[:actuator | path]`.
  Enables logging, replay, and multi-subscriber patterns. Actuators receive
  commands via `handle_info/2`.

- **Direct** (`set_position!/4`, etc.) - Commands sent directly via `BB.Process.cast`.
  Lower latency for time-critical control. Actuators receive via `handle_cast/2`.

- **Synchronous** (`set_position_sync/5`, etc.) - Commands sent via `BB.Process.call`.
  Returns acknowledgement or error. Actuators respond via `handle_call/3`.

### Examples

    # Pubsub delivery (for kinematics/orchestration)
    BB.Actuator.set_position(MyRobot, [:base_link, :shoulder, :servo], 1.57)

    # Direct delivery (for time-critical control)
    BB.Actuator.set_position!(MyRobot, :shoulder_servo, 1.57)

    # Synchronous with acknowledgement
    {:ok, :accepted} = BB.Actuator.set_position_sync(MyRobot, :shoulder_servo, 1.57)

# `disarm`

```elixir
@callback disarm(opts :: keyword()) :: :ok | {:error, term()}
```

Make the hardware safe.

Called with the opts provided at registration. Must work without GenServer state.
This callback is required for actuators since they control physical hardware.

# `handle_call`
*optional* 

```elixir
@callback handle_call(request :: term(), from :: GenServer.from(), state :: term()) ::
  {:reply, reply :: term(), new_state :: term()}
  | {:reply, reply :: term(), new_state :: term(),
     timeout() | :hibernate | {:continue, term()}}
  | {:noreply, new_state :: term()}
  | {:noreply, new_state :: term(),
     timeout() | :hibernate | {:continue, term()}}
  | {:stop, reason :: term(), new_state :: term()}
  | {:stop, reason :: term(), reply :: term(), new_state :: term()}
```

Handle synchronous calls.

Same semantics as `c:GenServer.handle_call/3`.

# `handle_cast`
*optional* 

```elixir
@callback handle_cast(request :: term(), state :: term()) ::
  {:noreply, new_state :: term()}
  | {:noreply, new_state :: term(),
     timeout() | :hibernate | {:continue, term()}}
  | {:stop, reason :: term(), new_state :: term()}
```

Handle asynchronous casts.

Same semantics as `c:GenServer.handle_cast/2`.

# `handle_continue`
*optional* 

```elixir
@callback handle_continue(continue_arg :: term(), state :: term()) ::
  {:noreply, new_state :: term()}
  | {:noreply, new_state :: term(),
     timeout() | :hibernate | {:continue, term()}}
  | {:stop, reason :: term(), new_state :: term()}
```

Handle continue instructions.

Same semantics as `c:GenServer.handle_continue/2`.

# `handle_info`
*optional* 

```elixir
@callback handle_info(msg :: term(), state :: term()) ::
  {:noreply, new_state :: term()}
  | {:noreply, new_state :: term(),
     timeout() | :hibernate | {:continue, term()}}
  | {:stop, reason :: term(), new_state :: term()}
```

Handle all other messages.

Same semantics as `c:GenServer.handle_info/2`.

# `handle_options`
*optional* 

```elixir
@callback handle_options(new_opts :: keyword(), state :: term()) ::
  {:ok, new_state :: term()} | {:stop, reason :: term()}
```

Handle parameter changes at runtime.

Called when a referenced parameter changes. The `new_opts` contain all options
with the updated parameter value(s) resolved.

Return `{:ok, new_state}` to update state, or `{:stop, reason}` to shut down.

# `init`

```elixir
@callback init(opts :: keyword()) ::
  {:ok, state :: term()}
  | {:ok, state :: term(), timeout() | :hibernate | {:continue, term()}}
  | {:stop, reason :: term()}
  | :ignore
```

Initialise actuator state from resolved options.

Called with options after parameter references have been resolved.
The `:bb` key contains `%{robot: module, path: [atom]}`.

Return `{:ok, state}` or `{:ok, state, timeout_or_continue}` on success,
`{:stop, reason}` to abort startup, or `:ignore` to skip this actuator.

# `options_schema`
*optional* 

```elixir
@callback options_schema() :: Spark.Options.t()
```

Returns the options schema for this actuator.

The schema should NOT include the `:bb` option - it is auto-injected.
If this callback is not implemented, the module cannot accept options
in the DSL (must be used as a bare module).

# `terminate`
*optional* 

```elixir
@callback terminate(reason :: term(), state :: term()) :: term()
```

Clean up before termination.

Same semantics as `c:GenServer.terminate/2`.

# `follow_trajectory`

```elixir
@spec follow_trajectory(module(), [atom()], [keyword() | map()], keyword()) :: :ok
```

Send a trajectory command via pubsub.

## Waypoint Structure

Each waypoint should be a keyword list or map with:
- `position` - Position (radians or metres)
- `velocity` - Velocity (rad/s or m/s)
- `acceleration` - Acceleration (rad/s² or m/s²)
- `time_from_start` - Time from trajectory start (milliseconds)

## Options

- `:repeat` - Number of repetitions: positive integer or `:forever` (default 1)
- `:command_id` - Correlation ID for feedback tracking

# `follow_trajectory!`

```elixir
@spec follow_trajectory!(module(), atom(), [keyword() | map()], keyword()) :: :ok
```

Send a trajectory command directly to an actuator (bypasses pubsub).

# `follow_trajectory_sync`

```elixir
@spec follow_trajectory_sync(
  module(),
  atom(),
  [keyword() | map()],
  keyword(),
  timeout()
) ::
  {:ok, :accepted | {:accepted, map()}} | {:error, term()}
```

Send a trajectory command and wait for acknowledgement.

# `hold`

```elixir
@spec hold(module(), [atom()], keyword()) :: :ok
```

Send a hold command via pubsub.

Instructs the actuator to actively maintain its current position.

## Options

- `:command_id` - Correlation ID for feedback tracking

# `hold!`

```elixir
@spec hold!(module(), atom(), keyword()) :: :ok
```

Send a hold command directly to an actuator (bypasses pubsub).

# `hold_sync`

```elixir
@spec hold_sync(module(), atom(), keyword(), timeout()) ::
  {:ok, :accepted | {:accepted, map()}} | {:error, term()}
```

Send a hold command and wait for acknowledgement.

# `set_effort`

```elixir
@spec set_effort(module(), [atom()], number(), keyword()) :: :ok
```

Send an effort (torque/force) command via pubsub.

## Options

- `:duration` - Duration (milliseconds), nil = until stopped
- `:command_id` - Correlation ID for feedback tracking

# `set_effort!`

```elixir
@spec set_effort!(module(), atom(), number(), keyword()) :: :ok
```

Send an effort command directly to an actuator (bypasses pubsub).

# `set_effort_sync`

```elixir
@spec set_effort_sync(module(), atom(), number(), keyword(), timeout()) ::
  {:ok, :accepted | {:accepted, map()}} | {:error, term()}
```

Send an effort command and wait for acknowledgement.

# `set_position`

```elixir
@spec set_position(module(), [atom()], number(), keyword()) :: :ok
```

Send a position command via pubsub.

The command is published to `[:actuator | path]` where subscribers can
receive it via `handle_info({:bb, path, message}, state)`.

## Options

- `:velocity` - Velocity hint (rad/s or m/s)
- `:duration` - Duration hint (milliseconds)
- `:command_id` - Correlation ID for feedback tracking

## Examples

    BB.Actuator.set_position(MyRobot, [:base_link, :shoulder, :servo], 1.57)
    BB.Actuator.set_position(MyRobot, [:shoulder, :servo], 1.57, velocity: 0.5)

# `set_position!`

```elixir
@spec set_position!(module(), atom(), number(), keyword()) :: :ok
```

Send a position command directly to an actuator (bypasses pubsub).

Uses `BB.Process.cast` for fire-and-forget delivery. The actuator receives
the command via `handle_cast({:command, message}, state)`.

## Options

Same as `set_position/4`.

# `set_position_sync`

```elixir
@spec set_position_sync(module(), atom(), number(), keyword(), timeout()) ::
  {:ok, :accepted | {:accepted, map()}} | {:error, term()}
```

Send a position command and wait for acknowledgement.

Uses `BB.Process.call` for synchronous delivery. Returns the actuator's
response or raises on timeout.

## Options

Same as `set_position/4`, plus:
- Fifth argument is timeout in milliseconds (default 5000)

## Returns

- `{:ok, :accepted}` - Command accepted
- `{:ok, :accepted, map()}` - Command accepted with additional info
- `{:error, reason}` - Command rejected

# `set_velocity`

```elixir
@spec set_velocity(module(), [atom()], number(), keyword()) :: :ok
```

Send a velocity command via pubsub.

## Options

- `:duration` - Duration (milliseconds), nil = until stopped
- `:command_id` - Correlation ID for feedback tracking

# `set_velocity!`

```elixir
@spec set_velocity!(module(), atom(), number(), keyword()) :: :ok
```

Send a velocity command directly to an actuator (bypasses pubsub).

# `set_velocity_sync`

```elixir
@spec set_velocity_sync(module(), atom(), number(), keyword(), timeout()) ::
  {:ok, :accepted | {:accepted, map()}} | {:error, term()}
```

Send a velocity command and wait for acknowledgement.

# `stop`

```elixir
@spec stop(module(), [atom()], keyword()) :: :ok
```

Send a stop command via pubsub.

## Options

- `:mode` - `:immediate` (default) or `:decelerate`
- `:command_id` - Correlation ID for feedback tracking

# `stop!`

```elixir
@spec stop!(module(), atom(), keyword()) :: :ok
```

Send a stop command directly to an actuator (bypasses pubsub).

# `stop_sync`

```elixir
@spec stop_sync(module(), atom(), keyword(), timeout()) ::
  {:ok, :accepted | {:accepted, map()}} | {:error, term()}
```

Send a stop command and wait for acknowledgement.

---

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