linuxcnc/docs/man/man9/kins.9
2023-01-06 09:27:14 -07:00

505 lines
13 KiB
Groff

.TH KINS "9" "2014-12-22" "LinuxCNC Documentation" "Kinematics Modules"
.SH NAME
kins \- kinematics definitions for LinuxCNC
For additional information, see the Documents 'Advanced Topics':
\fBKinematics\fR
\fB5-Axis Kinematics\fR
\fBSwitchable Kinematics\fR
.SH SYNOPSIS
.B loadrt trivkins (use for most cartesian machines)
.PP
.B loadrt corexykins
.PP
.B loadrt genhexkins
.PP
.B loadrt genserkins
.PP
.B loadrt lineardeltakins (see separate manpage)
.PP
.B loadrt maxkins
.PP
.B loadrt pentakins
.PP
.B loadrt pumakins
.PP
.B loadrt rosekins
.PP
.B loadrt rotarydeltakins
.PP
.B loadrt rotatekins
.PP
.B loadrt scarakins
.PP
.B loadrt tripodkins
.PP
.B loadrt xyzab_tdr_kins
.PP
.B loadrt xyzac\-trt\-kins
.PP
.B loadrt xyzbc\-trt\-kins
.PP
.B loadrt 5axiskins
.PP
.SH DESCRIPTION
Rather than exporting HAL pins and functions, these components provide the
forward and inverse kinematics definitions for LinuxCNC.
.SS trivkins \- generalized trivial kinematics
Joint numbers are assigned sequentially according to the axis letters specified
with the \fBcoordinates=\fR parameter.
If the coordinates= parameter is omitted, joint numbers are assigned
\fBsequentially\fR to every known axis letter ("xyzabcuvw").
.TP
Example: loadrt \fBtrivkins\fR
.TP
Assigns all axis letters to joint numbers in sequence:
.PP
x==joint0, y==joint1, z==joint2
a==joint3, b==joint4, c==joint5
u==joint6, v==joint7, w==joint8
.br
.ns
.TP
Example: loadrt \fBtrivkins coordinates=xyz\fR
.br
.ns
.TP
Assigns: x==joint0, y==joint1, z==joint2
.br
.ns
.TP
Example: loadrt \fBtrivkins coordinates=xz\fR
.br
.ns
.TP
Assigns: x==joint0, z==joint1
.br
.ns
.TP
Example: loadrt \fBtrivkins coordinates=xyzy\fR
.br
.ns
.TP
Assigns: x==joint0, y0==joint1, z==joint2, y1==joint3
.PP
The default kinematics type is \fBKINEMATICS_IDENTITY\fR. GUIs may provide
special features for configurations using this default kinematics type. For
instance, the AXIS GUI automatically handles joint and world mode operations so
that the distinctions between joints and axes are not visible to the operator.
This is feasible since there is an exact correspondence between a joint number
and its matching axis letter.
.br
.ns
.TP
The kinematics type can be set with the \fBkinstype=\fR parameter:
.br
.ns
.TP
kinstype=\fB1\fR for KINEMATICS_IDENTITY (default if kinstype= omitted)
.br
.ns
.TP
kinstype=[\fBb\fR|\fBB\fR] for KINEMATICS_BOTH
.br
.ns
.TP
kinstype=[\fBf\fR|\fBF\fR] for KINEMATICS_FORWARD_ONLY
.br
.ns
.TP
kinstype=[\fBi\fR|\fBI\fR] for KINEMATICS_INVERSE_ONLY
.TP
Example: loadrt \fBtrivkins coordinates=xyz kinstype=b\fR
.PP
Use kinstype=\fBB\fR (KINEMATICS_BOTH) for configurations that need to move joints
independently (joint mode) or as coordinated (teleop) movements in world coordinates.
When using the axis gui with KINEMATICS_BOTH, the '\fB$\fR' key is
used to toggle between joint and teleop (world) modes.
.PP
An axis letter may be used more than once (\fBduplicated\fR) to assign
multiple joints to a single axis coordinate letter.
.br
.ns
.TP
Example: coordinates=\fBxyyzw\fR kinstype=\fBB\fR
.br
.ns
.TP
Assigns: x==joint0, y==joint1 \fBAND\fR joint2, z==joint3, w==joint4
.PP
The above example illustrates a gantry configuration that uses
\fBduplicated\fR coordinate letters to indicate that
two joints (joint1 and joint2) move a single axis (y). Using
kinstype=\fBB\fR allows the configuration to be toggled between joint
and world modes of operation. Homing configuration options are
available to synchronize the final homing move for selected joints --
see the documentation for \fBHoming Configuration\fR.
\fBNOTES\fR for \fBduplicated\fR coordinates:
When \fBduplicated\fR coordinate letters are used, specifying
KINEMATICS_BOTH (kinstype=\fBB\fR) allows a gui to support
jogging of each individual joint in \fBjoint mode\fR.
\fBCaution\fR is required for machines where the movement
of a single joint (in a set specified by a \fBduplicated\fR coordinate letter)
can lead to gantry racking or other unwanted outcomes.
When the kinstype= parameter is omitted, operation defaults to
KINEMATICS_IDENTITY (kinstype=\fB1\fR) and a gui may allow jogging
based upon a selected axis coordinate letter
(or by a keyboard key) before homing is completed and the
machine is still in \fBjoint mode\fR. The joint selected will depend upon
the gui implementation but typically only one of the multiple
joints in the set will jog. Consequently, specifying KINEMATICS_BOTH
is recommended as it enables support for unambiguous, independent
jogging of each individual joint.
Machines that implement homing for all joints (including the provisions
for synchronizing the final homing move for multiple joints) may be homed
at machine startup and automatically switch to \fBworld\fR mode where
per-coordinate jogging is available.
.SS corexykins \- CoreXY Kinematics
.TP
X = 0.5*(JOINT_0 + JOINT_1)
.br
.ns
.TP
Y = 0.5*(JOINT_0 \- JOINT_1)
.br
.ns
.TP
Z = JOINT_2
.TP
[KINS]JOINTS= must specify 3 or more joints (maximum 9)
.TP
If enabled by the number of [KINS]JOINTS= specified, JOINT_3,4,5,6,7,8 correspond to coordinates A,B,C,U,V,W respectively.
.SS 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.
(See switchkins documentation for more info)
.TP
.B genhexkins.base.\fIN\fB.x
.br
.ns
.TP
.B genhexkins.base.\fIN\fB.y
.br
.ns
.TP
.B genhexkins.base.\fIN\fB.z
.br
.ns
.TP
.B genhexkins.platform.\fIN\fB.x
.br
.ns
.TP
.B genhexkins.platform.\fIN\fB.y
.br
.ns
.TP
.B genhexkins.platform.\fIN\fB.z
Parameters describing the \fIN\fRth joint's coordinates.
.br
.ns
.TP
.B genhexkins.spindle\-offset
Added to all joints Z coordinates to change the machine origin.
Facilitates adjusting spindle position.
.br
.ns
.TP
.B genhexkins.base\-n.\fIN\fB.x
.br
.ns
.TP
.B genhexkins.base\-n.\fIN\fB.y
.br
.ns
.TP
.B genhexkins.base\-n.\fIN\fB.z
.br
.ns
.TP
.B genhexkins.platform\-n.\fIN\fB.x
.br
.ns
.TP
.B genhexkins.platform\-n.\fIN\fB.y
.br
.ns
.TP
.B genhexkins.platform\-n.\fIN\fB.z
Parameters describing unit vectors of \fIN\fRth joint's axis. Used to
calculate strut length correction for cardanic joints and non-captive
actuators.
.br
.ns
.TP
.B genhexkins.screw\-lead
Lead of strut actuator screw, positive for the right-handed thread.
Default is 0 (strut length correction disabled).
.br
.ns
.TP
.B genhexkins.correction.\fIN\fB
Current values of strut length correction for non-captive actuators with
cardanic joints.
.B genhexkins.convergence\-criterion
Minimum error value that ends iterations with converged solution.
.br
.ns
.TP
.B genhexkins.limit\-iterations
Limit of iterations, if exceeded iterations stop with no convergence.
.br
.ns
.TP
.B genhexkins.max\-error
Maximum error value, if exceeded iterations stop with no convergence.
.br
.ns
.TP
.B genhexkins.last\-iterations
Number of iterations spent for the last forward kinematics solution.
.br
.ns
.TP
.B genhexkins.max\-iterations
Maximum number of iterations spent for a converged solution during current
session.
.br
.ns
.TP
.B genhexkins.tool\-offset
TCP offset from platform origin along Z to implement RTCP function. To
avoid joints jump change tool offset only when the platform is not tilted.
.SS genserkins \- generalized serial kinematics
Kinematics that can model a general serial-link manipulator with up to 6
angular joints.
(See switchkins documentation for more info)
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.
Note that this uses a convention sometimes known as "Modified DH Parameters"
and this must be borne in mind when setting up the system.
https://w.wiki/NcY
.TP
.B genserkins.A\-\fIN
.br
.ns
.TP
.B genserkins.ALPHA\-\fIN
.br
.ns
.TP
.B genserkins.D\-\fIN
Parameters describing the \fIN\fRth joint's geometry.
.SS 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.
.SS pentakins \- Pentapod Kinematics
Gives five degrees of freedom in position and orientation (XYZAB). The
location of base and effector joints is defined by HAL parameters. The
forward kinematics iteration is controlled by HAL pins.
.TP
.B pentakins.base.\fIN\fB.x
.br
.ns
.TP
.B pentakins.base.\fIN\fB.y
.br
.ns
.TP
.B pentakins.base.\fIN\fB.z
.br
.ns
.TP
.B pentakins.effector.\fIN\fB.r
.br
.ns
.TP
.B pentakins.effector.\fIN\fB.z
Parameters describing the \fIN\fRth effector joint's radius and axial
position.
.br
.ns
.TP
.B pentakins.convergence\-criterion
Minimum error value that ends iterations with converged solution.
.br
.ns
.TP
.B pentakins.limit\-iterations
Limit of iterations, if exceeded iterations stop with no convergence.
.br
.ns
.TP
.B pentakins.max\-error
Maximum error value, if exceeded iterations stop with no convergence.
.br
.ns
.TP
.B pentakins.last\-iterations
Number of iterations spent for the last forward kinematics solution.
.br
.ns
.TP
.B pentakins.max\-iterations
Maximum number of iterations spent for a converged solution during current
session.
.br
.ns
.TP
.B pentakins.tool\-offset
TCP offset from effector origin along Z to implement RTCP function. To
avoid joints jump change tool offset only when the platform is not tilted.
.SS pumakins \- kinematics for puma typed robots
Kinematics for a puma-style robot with 6 joints
.TP
.B pumakins.A2
.br
.ns
.TP
.B pumakins.A3
.br
.ns
.TP
.B pumakins.D3
.br
.ns
.TP
.B pumakins.D4
Describe the geometry of the robot
.SS rosekins \- kinematics for a rose engine using
a transverse, longitudinal, and rotary joint (3 joints)
.SS rotarydeltakins \- kinematics for a rotary delta machine
Rotary delta robot (3 Joints)
.SS rotatekins \- Rotated Kinematics
The X and Y axes are rotated 45 degrees compared to the joints 0 and 1.
.SS scarakins \- kinematics for SCARA-type robots
(See switchkins documentation for more info)
.TP
.B scarakins.D1
Vertical distance from the ground plane to the center of the inner arm.
.TP
.B scarakins.D2
Horizontal distance between joint[0] axis and joint[1] axis, ie. the
length of the inner arm.
.TP
.B 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.
.TP
.B scarakins.D4
Horizontal distance between joint[1] axis and joint[2] axis, ie. the
length of the outer arm.
.TP
.B 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.
.TP
.B 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].
.SS 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)
.TP
.B tripodkins.Bx
.br
.ns
.TP
.B tripodkins.Cx
.br
.ns
.TP
.B tripodkins.Cy
The location of the three motors is (0,0), (Bx,0), and (Cx,Cy)
.SS xyzac\-trt\-kins \- 5 Axis mill (Table Rotary/Tilting)
Tilting table (A) and horizontal rotary mounted to table (C axis)
(5 Joints 0:x,1:y,2:z,3:a,4:c) with provisions to switch between
xyzac and trivkins kinematic types. The joint mapping can be
altered with the coordinates parameter in the same way as supported
by trivkins.
(See switchkins documentation for more info)
.SS xyzbc\-trt\-kins \- 5 Axis mill (Table Rotary/Tilting)
(5 Joints 0:x,1:y,2:z,3:b,4:c) with provisions to switch between
xyzbc and trivkins kinematic types. The joint mapping can be
altered with the coordinates parameter in the same way as supported
by trivkins.
(See switchkins documentation for more info)
.SS 5axiskins \- 5 Axis bridge mill
XYZBCW -- the W coordinate values (typically used for
tool motion) are incorporated into XYZ positioning.
(Only 5 joints are needed by the kinematics module but
an additional joint is needed to display W values).
(See switchkins documentation for more info)
By default, 5axiskins uses coordinates XYZBCW assigned
consecutively to joints 0..5. The module coordinates
parameter may be used to assign multiple joints to an
axis letter and/or to assign joints to additional
coordinates A,U,V with a one-to-one correspondence to
the assigned joints. Example: XYZBCWYV (8 joints total
numbered 0..7) uses two joints for Y (joints 1,6) and
adds an additional coordinate V that has a one-to-one
relation to joint 7.
Note: These kinematics may be used with the vismach
5axisgui providing that the joint-letter assignments
agree with the default ordering expected by it (XYZBCW
-> joints 0..5)
.SH SEE ALSO
\fIKinematics\fR section in the LinuxCNC documentation
The HAL component \fBuserkins.comp\fR is a template for making
kinematic modules using the halcompile tool. The unmodified
template supports an identity xyz configuration that uses
3 joints. See \fBuserkins\fR(9) for more info.