BB.IK.DLS.Jacobian (bb_ik_dls v0.3.2)

Copy Markdown View Source

Numerical Jacobian computation for inverse kinematics.

The Jacobian matrix relates joint velocities to end-effector velocities:

 = J(θ) θ̇

where ẋ is the end-effector velocity (6D for position + orientation), θ̇ is the joint velocity vector, and J is the Jacobian matrix.

This module computes the Jacobian numerically using finite differences, which works with any kinematic chain without requiring analytical derivation.

Summary

Functions

Compute the position-only Jacobian (3xN matrix).

Compute the full Jacobian including orientation (6xN matrix).

Functions

compute(robot, positions, target_link, joint_names)

@spec compute(BB.Robot.t(), map(), atom(), [atom()]) :: Nx.Tensor.t()

Compute the position-only Jacobian (3xN matrix).

Returns a 3xN Nx tensor where N is the number of joints. Each column j represents the change in end-effector position per unit change in joint j.

Parameters

  • robot - The BB.Robot struct
  • positions - Current joint positions map %{atom() => float()}
  • target_link - The end-effector link name
  • joint_names - Ordered list of joint names in the kinematic chain

Returns

An Nx tensor of shape {3, n} where n is the length of joint_names.

compute_with_orientation(robot, positions, target_link, joint_names)

@spec compute_with_orientation(BB.Robot.t(), map(), atom(), [atom()]) :: Nx.Tensor.t()

Compute the full Jacobian including orientation (6xN matrix).

Returns a 6xN Nx tensor where N is the number of joints. Rows 0-2 represent position change, rows 3-5 represent orientation change (as angular velocity / axis-angle rate).

Parameters

Same as compute/4.

Returns

An Nx tensor of shape {6, n} where n is the length of joint_names.