madl3x / x-scara

SCARA CNC and 3D printing machine
GNU General Public License v3.0
152 stars 37 forks source link

Calibration problem on a machine that is not X-SCARA #9

Open tsogoo opened 2 years ago

tsogoo commented 2 years ago

Hi. I created scara and configured:

  // Length of inner and outer support arms. Measure arm lengths precisely.
  #define SCARA_LINKAGE_1  135.0    // (mm)
  #define SCARA_LINKAGE_2  125.0    // (mm)

  // SCARA tower offset (position of Tower relative to bed zero position)
  #define SCARA_OFFSET_X     0      // (mm)

I approximated :

  #define SCARA_OFFSET_Y    -148    // (mm) I approximated it

Configured for my gears:

  #define DEFAULT_AXIS_STEPS_PER_UNIT   { 46, 40, 400, 418.5 } // For my printers gears

Then when I command M361 S0 E90 Elbow moves 90 degrees when I command M361 S45 E0 Shoulder moves 45 degrees but elbow degree around 30 to 40. Is it ok? If not what it should be?

And sent gcode to draw circle but it draws egg shape.

tsogoo commented 2 years ago

When I command M361 S45 E0 or M361 S90 E0 elbow doesn't go 0 degrees. and elbow stepper motor moves.

madl3x commented 2 years ago

define SCARA_LINKAGE_1 135.0 // (mm)

define SCARA_LINKAGE_2 125.0 // (mm)

This is not the X-SCARA project. Can I know what mechanical model are you referring to, first?

tsogoo commented 2 years ago

define SCARA_LINKAGE_1 135.0 // (mm)

define SCARA_LINKAGE_2 125.0 // (mm)

This is not the X-SCARA project. Can I know what mechanical model are you referring to, first?

Yes. I created my own model and I used mega2560. The firmware installed successfully. My models gear teeth is: shoulder 20 to 76, length is 135 elbow 16 to 76. lenght is 125, and no reduction gear. 245804855_907465246812387_8254422625795932161_n 245689520_420524659430740_4717021979397446522_n 242995154_586798205694619_1902074224044676067_n

It drew planetary gear like this.

tsogoo commented 2 years ago

Last time I configured DEFAULT_AXIS_STEPS_PER_UNIT for my gears. 76 % 20 3200 / 360 76 % 20 3200 / 360

#define DEFAULT_AXIS_STEPS_PER_UNIT   { 42.222222, 33.777777, 400, 418.5 }

but when I give m362 s90 e0 or m362 s0 e90 command, arms doesn't go current angles. Shoulder angle go greater than 90(~110), elbow angle go lower than 90 degrees(~40).

madl3x commented 2 years ago

From what I see in the pictures, your model has no mechanical crosstalk between elbow and shoulder, and X-scara does. X-scara shares with the shoulder the elbow reduction gear, which influences the elbow's movement when the shoulder moves.

Try patching Marlin/src/module/scara.cpp, and replace lines 339-375 with this: LE: I am not really sure if this will work, but let's try :)

/* forward kinematics transformation */
static  FORCE_INLINE void x_scara_fwdk(const float &a, const float &b) {
    const float S = a;
    const float E = b-a; // removing crosstalk (/3)

    const float a_sin = - sin(RADIANS(S)) * L1,
                a_cos =   cos(RADIANS(S)) * L1,
                b_sin = - sin(RADIANS(S+E)) * L2,
                b_cos =   cos(RADIANS(S+E)) * L2;

    cartes.set(a_sin + b_sin + scara_offset.x,
               a_cos + b_cos + scara_offset.y); 

    X_SCARA_DEBUG_LNPAIR(
      "FWDK S:", S," E:", E," -> X:", cartes.x," Y:", cartes.y);
}

/*  inverse kinematics transformation */
static FORCE_INLINE void x_scara_invk(const xyz_pos_t &raw) {

    const float x = - (raw.x - scara_offset.x);
    const float y =   (raw.y - scara_offset.y);

    float x2y2 = sq(x) + sq(y);
    float hypot = SQRT(x2y2);

    if(hypot == 0) hypot = 0.000001; // avoid division by zero

    float S = ATAN2(x,y) - ACOS((x2y2 + PK_DifLenSqrd )/(2*L1*hypot));
    float E =              ACOS((x2y2 - PK_SumLenSq   )/(PK_ProdOfLen)) + S; // removing crosstalk (/3)

    delta.set(DEGREES(S), DEGREES(E), raw.z);

    X_SCARA_DEBUG_LNPAIR(
      "INVK X:",raw.x," Y:", raw.y, " -> S:", DEGREES(S)," E:", DEGREES(E));
}
tsogoo commented 2 years ago

Hi. Thanks for your help. That code makes sense. I tried it but no luck. I assume /3 is depends on reduction gear's ratio. In my case its 1. So that fix seems correct. Is there any other calculation related to /3?

tsogoo commented 2 years ago

I found other calculations. Also, How do you calculate

 #define SCARA_OFFSET_Y 

Can I choose value randomly ?

madl3x commented 2 years ago

I found other calculations. Also, How do you calculate

 #define SCARA_OFFSET_Y 

Can I choose value randomly ?

I found other calculations. Also, How do you calculate

 #define SCARA_OFFSET_Y 

Can I choose value randomly ?

No, that value represents the center of your rectangular bed placement and ​is relative to the axis where your shoulder (proximal) joint starts. You must set this value with respect to the bed size so that the arm can address the entire bed area with no collision with the machine's body and without getting past the sum of link lengths (L1+L2).

For example, if your bed size is 200x200mm, the SCARA_OFFSET_Y must point to the bed center on the Y axis, which in this case, is 100 mm away from the upper side of the bed. When your machine goes to the negative side of the Y axis (i.e.: closer to the machine's body) (0,-100) you must be sure that the arm won't collide the body. When it goes to the positive side of the Y axis (0,100) (i..e: farther from the machine's body) you must be sure the arm can reach that position (i.e. the Y coordinate < L1 + L2).

For the X axis, there is nothing to do, it can be left 0. Unless you want the (0,0) coordinate to start from a corner of the bed.

So it's not random: SCARA_OFFSET_Y - BED_SIZE_Y/2 must not collide with the machine, and SCARA_OFFSET_Y + BED_SIZE_Y/2 must be reachable (< L1+L2).

tsogoo commented 2 years ago

So I can choose SCARA_OFFSET_Y in specific range. It doesn't effect to drawing shape (circle to ellipse). right? Maybe perfect elbow angle (SCARA_OFFSET_Y value) to increase quality, right?

I have also one problem. I fixed drawing egg problem. But now I have an ellipse issue. I think I configured arm lengths correct. And my models shoulder, elbow arm goes right angles (Goes 90 degrees approximately, I used formula but didn't go 90 degree correctly. So I had to use command M92 X Y to calibrate angles.).

madl3x commented 2 years ago

SCARA_OFFSET_Y won't give the ellipse problem. It's just an offset in cartesian space. If you missed the bed center by, let's say 10mm, then the machine will consider the (0,0) origin point as being 10mm from above or below the real bed center. The print geometry will not be affected.

What gives geometry problems is the elbow angle relative to the shoulder joint. If that angle has an offset from what the machine knows, then the geometry is affected. It's the most important calibration the machine needs to get accurate prints.

If this angle is not correct, then when you print a rectangular shape or a square it will look like a trapezoid, like this:

image

Depending on whether the elbow angle deviation is positive or negative, the upper side will be larger, or lower, but will end up being a trapezoid.

And my models shoulder, elbow arm goes right angles (Goes 90 degrees approximately, I used formula but didn't go 90 degree correctly. So I had to use command M92 X Y to calibrate angles.).

It must go 90 degrees correctly first. M92 sets the steps per unit, try going for G92 if you want to set the angles in place (without homing). Put the arm in the straight position, then:

Make the test again and see what's wrong. If it's still not moving correctly, recheck steps/unit.

An easy-to-make test, that should be faster than doing the actual printing, would be to print on paper (using a regular inkjet or laser printer) a square shape of known dimensions (50x50mm for example) and its center as a disc. Then move the square's center where the center of the machine is (where it homes), align the square to be parallel with the bed, and verify if the machine follows the square's lines correctly.

ToonKru3 commented 2 years ago

i have i same problem here when i calibrate move stright manually and then M362 E0 S0 and G0 X0 Y0 and i try test move x and y button by Repetier-Host is curve shape to trapezoid

ToonKru3 commented 2 years ago

Can you re-write step by step for calibrate abotu how to fix trapazoid. I have followed by your instruction but it's trapzoid (square shape) and oval (circle shape)

ToonKru3 commented 2 years ago

or some much detail video about how to set up step by step