Basic Kinematics - bdring/Grbl_Esp32 GitHub Wiki

Basic Kinematics

Overview

Grbl_ESP32 supports gcode for lines (G0, G1) and arcs (G2, G3), but in reality, Grbl_ESP32 replaces arcs with lots of very short line segments to generate arcs. Many CAM programs do the same thing. This is perfectly acceptable, because the planner is quite efficient and the default tolerance of this method 0.002mm.

Basic kinematics uses this same principle to change from the default cartesian coordinate system to the system requirements of the machine. It breaks down moves small enough that the non linear affects will not be seen.

Example

The Polar Coaster is a good example of this. It uses one axis of linear motion and one axis of rotary motion. Look at the polar_coaster.h machine definition file.

Implementation

An extra function was put in front of the normal function to draw a line. It looks for #define KINEMATICS. If it is not defined, it will call the normal line function. If is is defined, it call a function called inverse_kinematics(...). This file must be added by the user. It will break that line into many smaller lines, convert those to the new coordinate system and call the mc_line(...) function

Dealing with feed Rate

While you are converting to a new system, the tool is still moving through material in a real world XYZ regardless of the kinematics required to make this happen. The distance in total steps of the converted line may be a different amount of steps than the original line. To compensate for this you should calculate the two distances and apply that ratio to the original feed rate.

Position reporting

Typically the position is reported in the new system. On a polar machine, for example, it will report the current radius and degrees. This can be confusing to some people. If they send it to X10, Y10, it will report X14.14 Y 45. To address this there is a forward kinematics function that can be added. Put #define FWD_KINEMATICS_REPORTING in your machine definition file and define a void forward_kinematics(float *position) function in same file you put your inverse kinematics function. See polar_coaster.cpp for an example. This currently only works with WPos reporting. Set $10=2 to get that reporting mode.

CoreXY

CoreXY is a type of machine where 2 motors cooperate to create motion in the XY plane. This is usually done to simplify the machine and can move the heavy motors off of the moving parts to increase performance.

Traditional Grbl had this built in to the main code. It did that because it was the only exotic motion type it supported and CoreXY is relatively simple implementation. When Grbl_ESP32 added the capability to add any type of kinematic, it made no sense to leave one in the main code.

Restrictions

  • Only XY and can use the CoreXY
  • 3 Axes max (no ABC axes)
  • You cannot put more than one axis on a homing cycle
  • You cannot have any dual motor (ganged) axes.

Machine Definition

Add the following lines to your machine definition

#define CUSTOM_CODE_FILENAME    "../Custom/CoreXY.cpp"

#define USE_KINEMATICS      // there are kinematic equations for this machine
#define USE_FWD_KINEMATICS  // report in cartesian
#define USE_MACHINE_INIT    // There is some custom initialization for this machine
#define USE_CUSTOM_HOMING

If you are using a midTbot style machine add this line too.

#define MIDTBOT             // applies the geometry correction to the kinematics 

Setting up the motors

CoreXY coordinates 2 motors to move an end effector in XY. Even a move only in the X direction requires both motors to move. This is done through some kinematic equations. Internally Grbl_ESP32 applies things like resolution and direction to individual motors.

If the direction needs to be corrected you need to keep this in mind. The process below should be followed to get the direction working properly.

Completely build the XY assembly. Manually hold one motor still and turn the other by hand in the clockwise direction. Find the motor that moves the end effector in the positive X and positive Y direction at the same time while the other is held still. This motor will be connected to the X motor driver on your controller. The other will be connected to the Y motor on your controller.

The next step is to check that the motors are moving in the right direction. Check the current mode with a ? command. If it is in Alarm mode, clear it by sending $X. Then send G91G0. This will put Grbl into incremental mode, so it is easy to move. Send $Stepper/DirInvert= to clear any direction inverts.

Checking X Motor.

Send X5Y5. The X motor should spin clockwise and the end effector should move in positive X and Y. You can do this multiple times if you need to. If it does not move in the right direction, send $Stepper/DirInvert=X. This should reverse the X axis. Test by sending X5Y5 again. The motor and axes should not be moving in the correct direction.

Checking the Y motor.

Send X5Y-5. The Y motor should spin clockwise. If it does not add the Y axis to $Stepper/DirInvert=. So it would be =XY if both need inverting or =Y to change the Y only.