Kinematic computations for robot manipulators.
This module provides forward kinematics and related computations for robots defined with the BB DSL.
Forward Kinematics
Forward kinematics computes the position and orientation of any link given the current joint positions:
# Get the transform from base to end-effector
transform = BB.Robot.Kinematics.forward_kinematics(
robot,
state,
:end_effector
)
# Extract position
pos = BB.Math.Transform.get_translation(transform)
{BB.Math.Vec3.x(pos), BB.Math.Vec3.y(pos), BB.Math.Vec3.z(pos)}Conventions
- All positions are in meters
- All angles are in radians
- Transforms are 4x4 homogeneous matrices (Nx tensors)
- The base link is at the identity transform
Summary
Functions
Compute transforms for all links in the robot.
Compute the transform for a single joint given its current position.
Compute the forward kinematics transform from base to a target link.
Get the position of a link in the base frame.
Functions
@spec all_link_transforms( BB.Robot.t(), BB.Robot.State.t() | %{required(atom()) => float()} ) :: %{ required(atom()) => BB.Math.Transform.t() }
Compute transforms for all links in the robot.
Returns a map from link name to its transform in the base frame.
Examples
transforms = BB.Robot.Kinematics.all_link_transforms(robot, state)
end_effector_transform = transforms[:end_effector]
@spec compute_joint_transform(BB.Robot.t(), %{required(atom()) => float()}, atom()) :: BB.Math.Transform.t()
Compute the transform for a single joint given its current position.
This combines the joint's fixed origin transform with the variable transform due to joint motion.
@spec forward_kinematics( BB.Robot.t(), BB.Robot.State.t() | %{required(atom()) => float()}, atom() ) :: BB.Math.Transform.t()
Compute the forward kinematics transform from base to a target link.
Returns a 4x4 homogeneous transformation matrix representing the position and orientation of the target link in the base frame.
Parameters
robot: The Robot structstate: The current robot state (or a map of joint positions)target_link: The name of the link to compute the transform for
Examples
robot = MyRobot.robot()
{:ok, state} = BB.Robot.State.new(robot)
BB.Robot.State.set_joint_position(state, :shoulder, :math.pi() / 4)
transform = BB.Robot.Kinematics.forward_kinematics(robot, state, :forearm)
pos = BB.Math.Transform.get_translation(transform)
@spec link_position( BB.Robot.t(), BB.Robot.State.t() | %{required(atom()) => float()}, atom() ) :: {float(), float(), float()}
Get the position of a link in the base frame.
This is a convenience function that extracts just the translation from the forward kinematics transform.
Examples
{x, y, z} = BB.Robot.Kinematics.link_position(robot, state, :end_effector)