kins − kinematics definitions for LinuxCNC
loadrt trivkins
loadrt rotatekins
loadrt tripodkins
loadrt genhexkins
loadrt maxkins
loadrt genserkins
loadrt pumakins
loadrt scarakins
Rather than exporting HAL pins and functions, these components provide the forward and inverse kinematics definitions for LinuxCNC.
trivkins
− Trivial Kinematics
There is a 1:1 correspondence between joints and axes. Most
standard milling machines and lathes use the trivial
kinematics module.
rotatekins
− Rotated Kinematics
The X and Y axes are rotated 45 degrees compared to the
joints 0 and 1.
tripodkins
− Tripod Kinematics
The joints represent the distance of the controlled point
from three predefined locations (the motors), giving three
degrees of freedom in position (XYZ)
tripodkins.Bx
tripodkins.Cx
tripodkins.Cy
The location of the three motors is (0,0), (Bx,0), and (Cx,Cy)
genhexkins
− Hexapod Kinematics
Gives six degrees of freedom in position and orientation
(XYZABC). The location of base and platform joints is
defined by hal parameters. The forward kinematics iteration
is controlled by hal pins.
genhexkins.base.N.x
genhexkins.base.N.y
genhexkins.base.N.z
genhexkins.platform.N.x
genhexkins.platform.N.y
genhexkins.platform.N.z
Parameters describing the Nth joint’s coordinates.
genhexkins.convergence−criterion
Minimum error value that ends iterations with converged solution.
genhexkins.limit−iterations
Limit of iterations, if exceeded iterations stop with no convergence.
genhexkins.max−error
Maximum error value, if exceeded iterations stop with no convergence.
genhexkins.last−iterations
Number of iterations spent for the last forward kinematics solution.
genhexkins.max−iterations
Maximum number of iterations spent for a converged solution during current session.
maxkins
− 5-axis kinematics example
Kinematics for Chris Radek’s tabletop 5 axis mill
named ’max’ with tilting head (B axis) and
horizintal rotary mounted to the table (C axis). Provides
UVW motion in the rotated coordinate system. The source
file, maxkins.c, may be a useful starting point for other
5-axis systems.
genserkins
− generalized serial kinematics
Kinematics that can model a general serial-link manipulator
with up to 6 angular joints.
The kinematics
use Denavit-Hartenberg definition for the joint and links.
The DH definitions are the ones used by John J Craig in
"Introduction to Robotics: Mechanics and Control"
The parameters for the manipulator are defined by hal pins.
genserkins.A−N
genserkins.ALPHA−N
genserkins.D−N
Parameters describing the Nth joint’s geometry.
pumakins
− kinematics for puma typed robots
Kinematics for a puma-style robot with 6 joints
pumakins.A2
pumakins.A3
pumakins.D3
pumakins.D4
Describe the geometry of the robot
scarakins
− kinematics for SCARA-type robots
scarakins.D1
Vertical distance from the ground plane to the center of the inner arm.
scarakins.D2
Horizontal distance between joint[0] axis and joint[1] axis, ie. the length of the inner arm.
scarakins.D3
Vertical distance from the center of the inner arm to the center of the outer arm. May be positive or negative depending on the structure of the robot.
scarakins.D4
Horizontal distance between joint[1] axis and joint[2] axis, ie. the length of the outer arm.
scarakins.D5
Vertical distance from the end effector to the tooltip. Positive means the tooltip is lower than the end effector, and is the normal case.
scarakins.D6
Horizontal distance from the centerline of the end effector (and the joints 2 and 3 axis) and the tooltip. Zero means the tooltip is on the centerline. Non-zero values should be positive, if negative they introduce a 180 degree offset on the value of joint[3].
Kinematics section in the LinuxCNC documentation