KINEMATICS
KINEMATICS
KINEMATICS
Document History
All rights reserved. Reproduction in whole or in part prohibited without the prior written consent of the
copyright owner.
Eding CNC BV Plug-in-kinematics
Table of contents
Table of contents 3
1 Introduction 4
1.1 Definitions, acronyms and abbreviations 4
1.2 Context and scope 5
1.2.1 Part coordinates and standard kinematic configurations for CNC machines 5
1.2.2 Common kinematic configurations for CNC machines: 5
1.2.3 A completely different machine 6
1.2.4 Tangential bend knife kinematics 6
1.3 Software architecture 7
4 Specific kinematics 18
4.1 Delta Robot 18
Eding CNC BV Plug-in-kinematics
1 Introduction
1.1 DEFINITIONS, ACRONYMS AND ABBREVIATIONS
CNC Computerized Numerical Control
CPU Central Processor Unit, a PCB board with a Processor on it.
DXF Drawing Exchange Format) is a CAD data file format developed by Autodesk
FIFO First In First Out Buffer
HPGL Hewlet Packard Graphical Language
GUI/UI Graphical User Interface
INTERPRETER A software function that is able to read a text file and execute the commands
contained therein.
JOBFILE A job is the text file (G code) that will be executed by the interpreter.
GUI Graphical User Interface.
PWM Pulse Width Modulation
G-Code CNC specific language to control the movements and IO of a milling machine.
LAF Look Ahead Feed, advanced motion algorithm that ensures minimal
machining time.
Eding CNC BV Plug-in-kinematics
Configuration 1. Confuration 2.
5Axis Mill with 5Axis Mill
A rotary table sits vertically on the mill table The work piece rotates on the C-Axis which
The Spindle pivots on the B-Axis which is rotates on the A-Axis
attached to the Z-Axis
Configuration 3 Configuration 4
5Axis Gantry Router 5Axis Vertical Router
The Spindle is attached via the B-Axis to the The work piece sits on a rotating plate.
C-Axis to the Z-Axis
First thing to be noticed is the meaning of ABC in the coordinate system, where XYZ is the position of the tooltip,
ABC defines with 3 angles the orientation of the tool tip.
It is clear to see that if the angle of the tooltip is changed that several other motors have to move in order to keep
the position of the tool-tip at the same place.
Eding CNC BV Plug-in-kinematics
Several wheels with motors can scribe with sand. The sand figure is a Cartesian drawing.
It is clear that during a z-move, the XY axes should move as well with same distance as Z, in the direction such
that the sharp side of the knife moves under 45 degrees into the material. The user will program Z moves, the
interpreter will rotate the knife (C axis) into the correct XY direction. Then kinematics will add the XY correction
depending on the Z position.
Eding CNC BV Plug-in-kinematics
CNCAPI
Kinematic
Allow runtime
Calculations and Interpreter
access to
Limits
kinematics
Cartesian Positions
Interpreter
Queue
Cartesian Positions
Cartesian Positions
Motor
Positions
Backlash Compensation
Uncheck Trivial Kinematics and press save. Button “Kinematics Setup” becomes available, press it:
Make sure rotatekins.dll is setup as plugin kinematics DLL. Also check the C axis to be visible.
Eding CNC BV Plug-in-kinematics
You will see that USBCNC VITUAL C 0.9 is switched on. The kinematics are active now and the center of
rotation is the current positin.
Let’s try this, Move away from the center, use arrow right to move X+. You can use Shift to move faster.
Eding CNC BV Plug-in-kinematics
Now move the C, click in the C position readout and specify 270 degrees. Press OK, the C will move with
maximum velocity to 225 degree and watch what happens, the XY plane is rotated resulting in a move of 225
degrees.
Now try to move X and Y, to see clearly that the XY plane is rotated, press the Arrow Keys (with Shift) to see it:
Cool isn’t it ? You can use this on your normal Cartesian milling machine.
Eding CNC BV Plug-in-kinematics
These are the prototype definitions of the functions that must be made. This content is found in the “rotatekins.h”
header file. It is the same for all kinematic types.
There are only 5 functions the needs to be implemented, they are explained in next chapter.
/*
* Name: Kinematics Inverse, converts Cartesian coordinates to Motor coordinates
*
* Input: pos,
* pos.x, pos.y, pos.z, are the tool-tip position in millimeter.
* pos.a, pos.b, pos.c are the tool orientation angles in degrees.
* iflags, not used
*
* Output: joints,
* joints.jx, joints.jy. joints.jz joints.ja, joints.jb, joints.jc
* are the motor positions.
* Motor positions usually also in mm or degrees, depending on the motor setup.
* fflags, not used.
*
* Remark: This function is called by after the trajectory generation inside the cncserver.
* Typically calling frequency is 200 Hz (5 Milli second).
*
*
*/
int KINEMATICS_API _stdcall KinematicsInverse(CNC_CART_DOUBLE pos,
CNC_JOINT_DOUBLE *joints,
const CNC_KINEMATICS_INVERSE_FLAGS * iflags,
CNC_KINEMATICS_FORWARD_FLAGS * fflags,
double toolLength);
/*
* Name: Kinematics Forward, converts Motor coordinates to Cartesian coordinates
*
* Input: joints,
* joints.jx, joints.jy. joints.jz joints.ja, joints.jb, joints.jc
* are the motor positions.
* Motor positions usually also in mm or degrees, depending on the motor setup.
* fflags, not used.
*
* Output: pos,
* pos.x, pos.y, pos.z, are the tool-tip position in millimeter.
* pos.a, pos.b, pos.c are the tool orientation angles in degrees.
* iflags, not used
*
* Remark: This function is called after homing and after switching on kinematics, to obtain
* the actual Cartesian position given the actual motor positions.
*
*/
int KINEMATICS_API _stdcall KinematicsForward(CNC_JOINT_DOUBLE joints,
CNC_CART_DOUBLE *pos,
const CNC_KINEMATICS_FORWARD_FLAGS * fflags,
CNC_KINEMATICS_INVERSE_FLAGS * iflags,
double toolLength);
/*
* Name: KinematicsControl, general purpose communication with the kinematics module.
* Provide parameters and switching ON/OFF of the kinematics.
* This function can be used to change the kinematics behavior run-time.
*
* Input: ControlID, there is a list of predefined Control ID's and free user control ID's,
* see cnc_kin_types.h
*
* controlData, a buffer of data, double integer or char for communication to and from
Eding CNC BV Plug-in-kinematics
/*
* Name: KinematicsType, this function returns the kinematics type, See cnc_kin_types.h
*/
CNC_KINEMATICS_TYPE KINEMATICS_API _stdcall KinematicsType();
/*
* Name: KinematicsType, this function returns the kinematics version string
*/
char KINEMATICS_API * _stdcall KinematicsVersion(void);
Eding CNC BV Plug-in-kinematics
#include <math.h>
#include <stdio.h>
#include "rotatekins.h"
case CNC_KIN_CONTROL_ID_CLOSE:
/* nothing to do for this kins implementation */
printf("Kins closed\n");
break;
case CNC_KIN_CONTROL_ID_OFF:
/* disable kins */
kinEnabled = 0;
printf("Kins disabled\n");
break;
case CNC_KIN_CONTROL_ID_ON:
/* enable kins */
printf("Kins enabled\n");
kinEnabled = 1;
break;
case KIN_CONTROL_ID_USER1:
/* Set rotation point */
rotationPointX = controlData->dData[0];
rotationPointY = controlData->dData[1];
/* printf("Kins rotation point set to x=%f, y=%f\n", rotationPointX, rotationPointY); */
break;
case KIN_CONTROL_ID_USER2:
/* Set rotation angle */
rotationAngle = controlData->dData[0];
/* printf("Kins rotation angle set to ang=%f\n", rotationAngle); */
break;
case KIN_CONTROL_ID_USER3:
/* Get rotation point */
controlData->dData[0] = rotationPointX;
controlData->dData[1] = rotationPointY;
break;
default:
/* return error */
return (-1);
break;
/* return OK */
return(0);
}
/*
* This function is a local function, that rotates the XY plane.
Eding CNC BV Plug-in-kinematics
x = xr;
y = yr;
}
if (kinEnabled)
{
double motorX = joints.jx;
double motorY = joints.jy;
//Rotate, reverse
rotate_scale(true, rotationPointX, rotationPointY, motorX, motorY);
return 0;
}
Eding CNC BV Plug-in-kinematics
if (kinEnabled)
{
// C axis gives rotation for X,Y axes
// We keep the C value stored in rotation angle because we use it in
// the forward kinematics.
rotationAngle = pos.c;
joints->jx = pos.x;
joints->jy = pos.y;
joints->jz = pos.z;
joints->ja = pos.a;
joints->jb = pos.b;
joints->jc = 0; /* C axis is virtual, do not output to joint */
}
else
{
joints->jx = pos.x;
joints->jy = pos.y;
joints->jz = pos.z;
joints->ja = pos.a;
joints->jb = pos.b;
joints->jc = 0;
}
return 0;
}
During the motion, the user can communicate with the kinematics module by means of the CNCAPI
CncKinControl function. And so if he wishes adapt the motion of the system at run-time.
A-axis mapping Y to A movements which allows to mill on a cylinder as if it is the XY plane. A program with
XYZ coordinates is transformed to XAZ movements, the software calculates all that is needed, the user has to
calibrate the A axis rotation point and radius. See main software manual.
Parallel processing of 2 work pieces is supported by linking Z2ZC (or if 2 motors are used for the Y motion,
Y2YAZ2ZC
KIN ON
KIN OFF
KIN CTRL <CTRLID> <CTRL PAR1> …. <CTRL PAR6>
These are self-explaining. CTRL PAR1 to CTRL PAR6 are passed to the KinControl function via the buffer.
Configuration consists of a start variable number and the number of bytes that will be written to the user variables.
Eding CNC BV Plug-in-kinematics
Maximum number of variables is 12 and start value must be below 3980. To disable the functionality, set start
variable to 0.
3.1 LIMITS
There are in fact two places where limits are specified
The standard setup for motor X .. motor C, where position limits, velocity limits and acceleration limits
are specified.
The kinematic setup becomes available when a non-trivial kinematics type is setup. Here there are also
position limits and acceleration limits specified.
The second one is needed because the software cannot always limit the Cartesian move correctly with as only
knowledge the motor limits. A single Cartesian move can easily cause moves for multiple motors and also violate
the max velocities and accelerations of the motors.
For these cases where the software cannot determine the limits from the motor parameters, the kinematical
Cartesian limits will be used.
3.2 HOMING
Homing always takes place at motor level and kinematics are switches off wile homing.
In the home sequence (macro.cnc) at the end of the homing sequence a “KIN ON” command may be placed to
switch on the kinematics immediately after homing.
Eding CNC BV Plug-in-kinematics
4 Specific kinematics
Principle drawing
Eding CNC BV Plug-in-kinematics
linDeltaRadius = 125.000000
linDeltaArmLength = 250.000000
The positions:
The joint positions are defined from the same level, so when the end-effector is at Z = 0, then the joints level cabn
ce calculated from Pythargoras:
You must use this to define the home position for the joints in the Eding CNC setup.
The positions of the home sensors are defined in the joint space.
Eding CNC BV Plug-in-kinematics
Supose you have an arm length of 250mm and a radius of 125mm and you system can move 200mm up.
So the Z of the end-effector can be 200mm above zero.
The homeswitch position would be at:
A new function is defined to prepare the delta robot for homing, this function will move alle 3 joints until all 3
home sensors are activated.
When this is done, the EdingCNC software is still in Yrivial kinematisc mode, but can be switch to Linear Delta
Kinematics if the setup is correct.
The deltakins.dll is specified here and the graphics limits and velocities are setup.
Note that the position linits here are only for the graphics, the actual limits are determined by the software using the
inverse kinematics and the joint limits.
Eding CNC BV Plug-in-kinematics
After this is configured and the home sequence is performed, the kinematics kan be switched on, by command “kin
on” or in the GUI at the coordnates page.
For people who want to work only with kinematics, the can modyfy home all in the macro.cnc like this:
Sub Home_all
PrepareLineDeltaHome
Home X
Home Y
Home Z
Kin ON
endSub
Now the system will move with kinematics, try to move X and Y and Z and see what happens.