Convenience functions for DLS-based motion.
This module wraps BB.Motion with the DLS solver pre-configured,
providing a simpler API for common inverse kinematics motion tasks.
Single Target
# Move end-effector to target position
case BB.IK.DLS.Motion.move_to(MyRobot, :gripper, {0.3, 0.2, 0.1}) do
{:ok, meta} -> IO.puts("Reached in #{meta.iterations} iterations")
{:error, reason, _meta} -> IO.puts("Failed: #{reason}")
end
# Just solve without moving (for validation)
case BB.IK.DLS.Motion.solve(MyRobot, :gripper, {0.3, 0.2, 0.1}) do
{:ok, positions, meta} -> IO.inspect(positions)
{:error, reason, _meta} -> IO.puts("Unreachable: #{reason}")
endMultiple Targets (for gait, coordinated motion)
targets = %{left_foot: {0.1, 0.0, 0.0}, right_foot: {-0.1, 0.0, 0.0}}
case BB.IK.DLS.Motion.move_to_multi(MyRobot, targets) do
{:ok, results} -> IO.puts("All targets reached")
{:error, failed, reason, _} -> IO.puts("Failed: #{failed}: #{reason}")
endIn Custom Commands
use BB.Command
@impl BB.Command
def handle_command(%{target: target}, context, state) do
case BB.IK.DLS.Motion.move_to(context, :gripper, target) do
{:ok, meta} ->
{:stop, :normal, %{state | result: %{residual: meta.residual}}}
{:error, reason, _meta} ->
{:stop, :normal, %{state | result: {:error, reason}}}
end
end
@impl BB.Command
def result(%{result: {:error, _} = error}), do: error
def result(%{result: result}), do: {:ok, result}
Summary
Functions
Move an end-effector to a target position using DLS.
Move multiple end-effectors to target positions simultaneously using DLS.
Solve DLS without moving the robot.
Solve DLS for multiple targets without moving the robot.
Types
@type meta() :: BB.IK.Solver.meta()
@type multi_motion_result() :: BB.Motion.multi_motion_result()
@type multi_solve_result() :: BB.Motion.multi_solve_result()
@type positions() :: BB.IK.Solver.positions()
@type robot_or_context() :: module() | BB.Command.Context.t()
@type target() :: BB.IK.Solver.target()
Functions
@spec move_to(robot_or_context(), atom(), target(), keyword()) :: motion_result()
Move an end-effector to a target position using DLS.
This is a convenience wrapper around BB.Motion.move_to/4 with the
DLS solver pre-configured.
Options
DLS-specific:
:max_iterations- Maximum DLS iterations (default: 100):tolerance- Convergence tolerance in metres (default: 1.0e-4):orientation_tolerance- Orientation tolerance in radians (default: 0.01):lambda- Damping factor (default: 0.5):adaptive_damping- Adapt lambda based on error (default: true):step_size- Max joint update per iteration (default: 0.1):respect_limits- Whether to clamp to joint limits (default: true)
Motion:
:delivery- How to send actuator commands::pubsub(default),:direct, or:sync
Returns
{:ok, meta}- Successfully moved; meta contains solver info{:error, reason, meta}- Failed to reach target
Examples
BB.IK.DLS.Motion.move_to(MyRobot, :gripper, {0.3, 0.2, 0.1})
BB.IK.DLS.Motion.move_to(context, :gripper, target,
delivery: :direct,
max_iterations: 200,
tolerance: 0.001
)
@spec move_to_multi(robot_or_context(), targets(), keyword()) :: multi_motion_result()
Move multiple end-effectors to target positions simultaneously using DLS.
Useful for coordinated motion like walking gaits. Each target is solved independently using DLS and all actuator commands are sent together.
Options
Same as move_to/4.
Returns
{:ok, results}- All targets solved; results is a map of link →{:ok, positions, meta}{:error, failed_link, reason, results}- A target failed
Examples
targets = %{
left_foot: {0.1, 0.0, 0.0},
right_foot: {-0.1, 0.0, 0.0}
}
case BB.IK.DLS.Motion.move_to_multi(MyRobot, targets) do
{:ok, results} ->
IO.puts("All limbs positioned")
{:error, failed_link, reason, _results} ->
IO.puts("Failed to reach #{failed_link}: #{reason}")
end
@spec solve(robot_or_context(), atom(), target(), keyword()) :: solve_result()
Solve DLS without moving the robot.
Useful for validating targets are reachable before committing to motion, or for planning multi-step movements.
Options
:max_iterations- Maximum DLS iterations (default: 100):tolerance- Convergence tolerance in metres (default: 1.0e-4):orientation_tolerance- Orientation tolerance in radians (default: 0.01):lambda- Damping factor (default: 0.5):adaptive_damping- Adapt lambda based on error (default: true):step_size- Max joint update per iteration (default: 0.1):respect_limits- Whether to clamp to joint limits (default: true)
Returns
{:ok, positions, meta}- Successfully solved{:error, reason, meta}- Failed to solve
Examples
case BB.IK.DLS.Motion.solve(MyRobot, :gripper, target) do
{:ok, positions, %{reached: true}} ->
IO.puts("Target reachable")
IO.inspect(positions)
{:ok, _positions, %{reached: false, residual: residual}} ->
IO.puts("Close but not exact, residual: #{residual}m")
{:error, :no_solution, _meta} ->
IO.puts("Failed to converge")
end
@spec solve_multi(robot_or_context(), targets(), keyword()) :: multi_solve_result()
Solve DLS for multiple targets without moving the robot.
Useful for validating that all targets in a coordinated motion are reachable.
Options
Same as solve/4.
Returns
{:ok, results}- All targets solved{:error, failed_link, reason, results}- A target failed
Examples
targets = %{left_foot: {0.1, 0.0, 0.0}, right_foot: {-0.1, 0.0, 0.0}}
case BB.IK.DLS.Motion.solve_multi(MyRobot, targets) do
{:ok, results} ->
Enum.each(results, fn {link, {:ok, _pos, meta}} ->
IO.puts("#{link}: #{meta.residual}m residual")
end)
{:error, failed_link, reason, _results} ->
IO.puts("#{failed_link} unreachable: #{reason}")
end