Damped Least Squares (Levenberg-Marquardt) inverse kinematics solver.
DLS is a Jacobian-based iterative solver that computes joint angles to position an end-effector at a target pose. The damping factor prevents instability near kinematic singularities.
Features
- Works with
BB.Robot.Stateor plain position maps - Position and orientation solving (quaternion or axis constraints)
- Numerical Jacobian computation (works with any kinematic chain)
- Adaptive damping for improved convergence
- Respects joint limits by clamping solved values
- Uses Nx tensors for efficient computation
- Returns best-effort positions even on failure
Usage
robot = MyRobot.robot()
{:ok, state} = BB.Robot.State.new(robot)
# Solve for end-effector to reach target position
target = Vec3.new(0.4, 0.2, 0.1)
case BB.IK.DLS.solve(robot, state, :end_effector, target) do
{:ok, positions, meta} ->
BB.Robot.State.set_positions(state, positions)
IO.puts("Solved in #{meta.iterations} iterations")
{:error, %BB.Error.Kinematics.NoSolution{residual: residual}} ->
IO.puts("Failed to converge, residual: #{residual}m")
endTarget Formats
Vec3.t()- Position-only targetTransform.t()- Position + full orientation from transform{Vec3.t(), {:quaternion, Quaternion.t()}}- Position + explicit quaternion{Vec3.t(), {:axis, Vec3.t()}}- Position + tool axis direction constraint
Options
:max_iterations- Maximum solver iterations (default: 100):tolerance- Position convergence tolerance in metres (default: 1.0e-4):orientation_tolerance- Orientation convergence in radians (default: 0.01):lambda- Damping factor (default: 0.5):adaptive_damping- Adjust lambda based on error reduction (default: true):step_size- Maximum joint update per iteration in radians (default: 0.1):respect_limits- Whether to clamp to joint limits (default: true):exclude_joints- List of joint names to exclude from IK solving (default: []). Useful for excluding end-effectors like grippers that shouldn't affect positioning.:check_collisions- Whether to verify the solution doesn't cause self-collision (default: false):collision_margin- Safety margin for collision checking in metres (default: 0.0)
Algorithm
DLS uses the damped pseudoinverse to compute joint updates:
Δθ = J^T (J J^T + λ²I)^(-1) ewhere J is the Jacobian, e is the pose error, and λ is the damping factor. The damping prevents instability when J J^T is near-singular.
Comparison with FABRIK
- DLS: Better orientation control, handles 6-DOF arms well, slower per iteration
- FABRIK: Faster for position-only, struggles with orientation, simpler algorithm
Summary
Functions
Solve IK and update the state in-place.
Functions
@spec solve_and_update( BB.Robot.t(), BB.Robot.State.t(), atom(), BB.IK.Solver.target(), keyword() ) :: BB.IK.Solver.solve_result()
Solve IK and update the state in-place.
Convenience function that calls solve/5 and applies the result
to the given BB.Robot.State.
Returns
Same as solve/5, but on success the state's ETS table is updated.