Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[BUG] SCARA axis homing #27575

Open
1 task done
Sejkorka opened this issue Dec 8, 2024 · 77 comments
Open
1 task done

[BUG] SCARA axis homing #27575

Sejkorka opened this issue Dec 8, 2024 · 77 comments

Comments

@Sejkorka
Copy link

Sejkorka commented Dec 8, 2024

Did you test the latest bugfix-2.1.x code?

Yes, and the problem still exists.

Bug Description

Hi, I have a problem with marlin and its SCARA function, it's my graduation paper, I have already printed the complete scara, most things work, if not at least half.
But what doesn't work is the homing of the "X" axis, the limit switches work normally and M119 shows them as triggers when they should be.
The "X" axis does not homing, it seems to me that once the "Y" axis is homed so is the "X" axis.

Bug Timeline

No response

Expected behavior

No response

Actual behavior

No response

Steps to Reproduce

No response

Version of Marlin Firmware

2.0.9

Printer model

MP_SCARA

Electronics

BOARD_RAMPS_14_EFB

LCD/Controller

No response

Other add-ons

No response

Bed Leveling

None

Your Slicer

None

Host Software

Repetier Host

Don't forget to include

  • A ZIP file containing your Configuration.h and Configuration_adv.h.

Additional information & file uploads

Config adv.txt
Config.txt

@thinkyhead
Copy link
Member

This part of the code doesn't get enough attention. When I was last working on a SCARA style robot it had a single free arm, so it had to home both its first and second joints. I've never seen the Morgan and MP SCARA robots do their homing, but the provided code is supposed to have done the right thing at one time.

Anyway, it sounds like you'll need to dig into the homing code and debug it to work for your machine, or recruit some help to figure it out. The Marlin Discord server is a pretty good place to find help. Once you have it sorted out it would be great if you could submit the fix to the main project. SCARA is a rare thing, but we do want it to work!

@ellensp
Copy link
Contributor

ellensp commented Dec 10, 2024

MP_SCARA is quite broken in bugfix 2.1.x

I Enabled debugging
#define DEBUG_LEVELING_FEATURE
M111 S32

All the following G28 test where done on a freshly reset board.

G28 gives me this log on a standard G28, Z axis moves up and then it errors..

G28
18:54:25.501 > >>> G28 X0.00 Y199.07 Z0.00
18:54:25.501 > Machine Type: SCARA
18:54:25.501 > Probe: NONE
18:54:25.501 > remember_feedrate_scaling_off: fr=66.67 100%
18:54:25.501 > Raise Z before homing:
18:54:25.501 > do_z_clearance(5.00 [0.00 to 5.00], 0)
18:54:25.501 > do_blocking_move_to_z(5.00, 4.00)
18:54:25.501 > >>> do_blocking_move_to X0.00 Y199.07 Z0.00
18:54:25.501 > > X0.00 Y199.07 Z5.00
18:54:25.501 > destination= X0.00 Y199.07 Z5.00 : prepare_fast_move_to_destination
18:54:25.501 > destination= X0.00 Y199.07 Z5.00 : prepare_fast_move_to_destination
18:54:27.481 > echo:busy: processing
18:54:27.858 > <<< do_blocking_move_to X0.00 Y199.07 Z5.00
18:54:27.858 > current_position= X0.00 Y0.00 Z5.00 : sync_plan_position
18:54:27.858 > do_blocking_move_to_xy(-300.00, -300.00, 28.28)
18:54:27.858 > >>> do_blocking_move_to X0.00 Y0.00 Z5.00
18:54:27.858 > > X-300.00 Y-300.00 Z5.00
18:54:27.858 > <<< do_blocking_move_to X0.00 Y0.00 Z5.00
18:54:27.858 > echo:Homing Failed
18:54:27.858 > Error:Printer halted. kill() called!

G28 Z works as expected

G28 Z
19:08:29.178 > >>> G28 X0.00 Y199.07 Z0.00
19:08:29.178 > Machine Type: SCARA
19:08:29.178 > Probe: NONE
19:08:29.178 > remember_feedrate_scaling_off: fr=66.67 100%
19:08:29.178 > >>> homeaxis(Z)
19:08:29.178 > Home Fast: -150.00mm
19:08:29.178 > >>> do_homing_move X0.00 Y199.07 Z0.00
19:08:29.178 > ...(Z, -150.00, [4.00])
19:08:29.178 > current_position= X0.00 Y199.07 Z0.00 : sync_plan_position
19:08:31.158 > echo:busy: processing
...
19:08:59.142 > echo:busy: processing
19:08:59.377 > <<< do_homing_move X0.00 Y199.07 Z-150.00
19:08:59.378 > Move Away: 3.00mm
19:08:59.378 > >>> do_homing_move X0.00 Y199.07 Z-150.00
19:08:59.378 > ...(Z, 3.00, [4.00])
19:08:59.378 > current_position= X0.00 Y199.07 Z0.00 : sync_plan_position
19:09:00.928 > <<< do_homing_move X0.00 Y199.07 Z3.00
19:09:00.928 > Re-bump: -6.00mm
19:09:00.928 > >>> do_homing_move X0.00 Y199.07 Z3.00
19:09:00.928 > ...(Z, -6.00, 1.00)
19:09:00.928 > current_position= X0.00 Y199.07 Z0.00 : sync_plan_position
19:09:01.151 > echo:busy: processing
19:09:03.148 > echo:busy: processing
19:09:04.182 > <<< do_homing_move X0.00 Y199.07 Z-6.00
19:09:04.182 > >>> set_axis_is_at_home(Z)
19:09:04.182 > current_position= X0.00 Y199.07 Z0.00 :
19:09:04.182 > <<< set_axis_is_at_home(Z)
19:09:04.182 > current_position= X0.00 Y199.07 Z0.00 : sync_plan_position
19:09:04.182 > <<< homeaxis(Z)
19:09:04.182 > current_position= X0.00 Y199.07 Z0.00 : sync_plan_position
19:09:04.182 > >>> do_move_after_z_homing X0.00 Y199.07 Z0.00
19:09:04.182 > do_z_clearance(5.00 [0.00 to 5.00], 1)
19:09:04.182 > do_blocking_move_to_z(5.00, 4.00)
19:09:04.182 > >>> do_blocking_move_to X0.00 Y199.07 Z0.00
19:09:04.182 > > X0.00 Y199.07 Z5.00
19:09:04.182 > destination= X0.00 Y199.07 Z5.00 : prepare_fast_move_to_destination
19:09:04.201 > destination= X0.00 Y199.07 Z5.00 : prepare_fast_move_to_destination
19:09:05.144 > echo:busy: processing
19:09:06.554 > <<< do_blocking_move_to X0.00 Y199.07 Z5.00
19:09:06.554 > <<< do_move_after_z_homing X0.00 Y199.07 Z5.00
19:09:06.554 > restore_feedrate_and_scaling: fr=66.67 100%
19:09:06.554 > X:0.00 Y:199.07 Z:5.00 E:0.00 Count A:2581B:2581 Z:8000
19:09:06.554 > SCARA Theta:90.01 Psi:90.01
19:09:06.554 >
19:09:06.554 > <<< G28 X0.00 Y199.07 Z5.00
19:09:06.554 > ok

G28 Y moves Z up 5mm as expected, but then does nothing.

G28 Y
19:11:21.900 > >>> G28 X0.00 Y199.07 Z0.00
19:11:21.900 > Machine Type: SCARA
19:11:21.900 > Probe: NONE
19:11:21.900 > remember_feedrate_scaling_off: fr=66.67 100%
19:11:21.900 > Raise Z before homing:
19:11:21.900 > do_z_clearance(5.00 [0.00 to 5.00], 0)
19:11:21.900 > do_blocking_move_to_z(5.00, 4.00)
19:11:21.900 > >>> do_blocking_move_to X0.00 Y199.07 Z0.00
19:11:21.900 > > X0.00 Y199.07 Z5.00
19:11:21.900 > destination= X0.00 Y199.07 Z5.00 : prepare_fast_move_to_destination
19:11:21.900 > destination= X0.00 Y199.07 Z5.00 : prepare_fast_move_to_destination
19:11:23.865 > echo:busy: processing
19:11:24.254 > <<< do_blocking_move_to X0.00 Y199.07 Z5.00
19:11:24.254 > current_position= X0.00 Y199.07 Z5.00 : sync_plan_position
19:11:24.254 > restore_feedrate_and_scaling: fr=66.67 100%
19:11:24.254 > X:0.00 Y:199.07 Z:5.00 E:0.00 Count A:2581B:2581 Z:8000
19:11:24.254 > SCARA Theta:90.01 Psi:90.01
19:11:24.254 >
19:11:24.254 > <<< G28 X0.00 Y199.07 Z5.00
19:11:24.254 > ok

G28 X moves Z up 5mm as expected, but then does nothing.

G28 X

19:18:41.893 > >>> G28 X0.00 Y199.07 Z0.00
19:18:41.893 > Machine Type: SCARA
19:18:41.893 > Probe: NONE
19:18:41.893 > remember_feedrate_scaling_off: fr=66.67 100%
19:18:41.893 > Raise Z before homing:
19:18:41.893 > do_z_clearance(5.00 [0.00 to 5.00], 0)
19:18:41.893 > do_blocking_move_to_z(5.00, 4.00)
19:18:41.893 > >>> do_blocking_move_to X0.00 Y199.07 Z0.00
19:18:41.893 > > X0.00 Y199.07 Z5.00
19:18:41.893 > destination= X0.00 Y199.07 Z5.00 : prepare_fast_move_to_destination
19:18:41.893 > destination= X0.00 Y199.07 Z5.00 : prepare_fast_move_to_destination
19:18:43.857 > echo:busy: processing
19:18:44.247 > <<< do_blocking_move_to X0.00 Y199.07 Z5.00
19:18:44.247 > current_position= X0.00 Y199.07 Z5.00 : sync_plan_position
19:18:44.247 > restore_feedrate_and_scaling: fr=66.67 100%
19:18:44.247 > X:0.00 Y:199.07 Z:5.00 E:0.00 Count A:2581B:2581 Z:8000
19:18:44.247 > SCARA Theta:90.01 Psi:90.01
19:18:44.247 >
19:18:44.247 > <<< G28 X0.00 Y199.07 Z5.00
19:18:44.247 > ok

Im not sure that G28 X or Y should actually do anything since there isn't really a X or a Y endstop.
But G28 should most definely home all axies.

@ellensp
Copy link
Contributor

ellensp commented Dec 10, 2024

disabling #define VALIDATE_HOMING_ENDSTOPS does allow G28 to complete, but does not move X or Y steppers

G28
19:43:25.835 > >>> G28 X0.00 Y199.07 Z0.00
19:43:25.835 > Machine Type: SCARA
19:43:25.835 > Probe: NONE
19:43:25.835 > remember_feedrate_scaling_off: fr=66.67 100%
19:43:25.835 > Raise Z before homing:
19:43:25.835 > do_z_clearance(5.00 [0.00 to 5.00], 0)
19:43:25.835 > do_blocking_move_to_z(5.00, 4.00)
19:43:25.835 > >>> do_blocking_move_to X0.00 Y199.07 Z0.00
19:43:25.835 > > X0.00 Y199.07 Z5.00
19:43:25.835 > destination= X0.00 Y199.07 Z5.00 : prepare_fast_move_to_destination
19:43:25.835 > destination= X0.00 Y199.07 Z5.00 : prepare_fast_move_to_destination
19:43:27.800 > echo:busy: processing
19:43:28.194 > <<< do_blocking_move_to X0.00 Y199.07 Z5.00
19:43:28.194 > current_position= X0.00 Y0.00 Z5.00 : sync_plan_position
19:43:28.194 > do_blocking_move_to_xy(-300.00, -300.00, 28.28)
19:43:28.194 > >>> do_blocking_move_to X0.00 Y0.00 Z5.00
19:43:28.194 > > X-300.00 Y-300.00 Z5.00
19:43:28.194 > <<< do_blocking_move_to X0.00 Y0.00 Z5.00
19:43:28.194 > >>> homeaxis(Z)
19:43:28.194 > Home Fast: -150.00mm
19:43:28.194 > >>> do_homing_move X0.00 Y0.00 Z5.00
19:43:28.194 > ...(Z, -150.00, [4.00])
19:43:28.194 > current_position= X0.00 Y0.00 Z0.00 : sync_plan_position
19:43:29.807 > echo:busy: processing
19:43:31.804 > echo:busy: processing
19:43:32.452 > <<< do_homing_move X0.00 Y0.00 Z-150.00
19:43:32.453 > Move Away: 3.00mm
19:43:32.453 > >>> do_homing_move X0.00 Y0.00 Z-150.00
19:43:32.453 > ...(Z, 3.00, [4.00])
19:43:32.453 > current_position= X0.00 Y0.00 Z0.00 : sync_plan_position
19:43:33.810 > echo:busy: processing
19:43:34.003 > <<< do_homing_move X0.00 Y0.00 Z3.00
19:43:34.003 > Re-bump: -6.00mm
19:43:34.003 > >>> do_homing_move X0.00 Y0.00 Z3.00
19:43:34.003 > ...(Z, -6.00, 1.00)
19:43:34.003 > current_position= X0.00 Y0.00 Z0.00 : sync_plan_position
19:43:35.808 > echo:busy: processing
19:43:37.172 > <<< do_homing_move X0.00 Y0.00 Z-6.00
19:43:37.172 > >>> set_axis_is_at_home(Z)
19:43:37.172 > current_position= X0.00 Y0.00 Z0.00 :
19:43:37.172 > <<< set_axis_is_at_home(Z)
19:43:37.172 > current_position= X0.00 Y0.00 Z0.00 : sync_plan_position
19:43:37.172 > <<< homeaxis(Z)
19:43:37.172 > current_position= X0.00 Y0.00 Z0.00 : sync_plan_position
19:43:37.172 > >>> do_move_after_z_homing X0.00 Y0.00 Z0.00
19:43:37.172 > do_z_clearance(5.00 [0.00 to 5.00], 1)
19:43:37.172 > do_blocking_move_to_z(5.00, 4.00)
19:43:37.172 > >>> do_blocking_move_to X0.00 Y0.00 Z0.00
19:43:37.172 > > X0.00 Y0.00 Z5.00
19:43:37.172 > destination= X0.00 Y0.00 Z5.00 : prepare_fast_move_to_destination
19:43:37.191 > destination= X0.00 Y0.00 Z5.00 : prepare_fast_move_to_destination
19:43:37.798 > echo:busy: processing
19:43:39.545 > <<< do_blocking_move_to X0.00 Y0.00 Z5.00
19:43:39.545 > <<< do_move_after_z_homing X0.00 Y0.00 Z5.00
19:43:39.545 > restore_feedrate_and_scaling: fr=66.67 100%
19:43:39.545 > X:0.00 Y:0.00 Z:5.00 E:0.00 Count A:-2147483648B:-2147483648 Z:8000
19:43:39.545 > SCARA Theta:-74893488.00 Psi:-74893488.00
19:43:39.545 >
19:43:39.545 > <<< G28 X0.00 Y0.00 Z5.00
19:43:39.545 > ok

@ellensp
Copy link
Contributor

ellensp commented Dec 10, 2024

This answer that question, only G28 Z will fuction

  void homeaxis(const AxisEnum axis) {

    #if ANY(MORGAN_SCARA, MP_SCARA)
      // Only Z homing (with probe) is permitted
      if (axis != Z_AXIS) { BUZZ(100, 880); return; }

@ellensp
Copy link
Contributor

ellensp commented Dec 10, 2024

I want back to 2.0.5 to find one that can home, and I notice that is_scara is not set for the mp_scara,

ie 2.0.5 does not limit homeaxis to Z_AXIS

void homeaxis(const AxisEnum axis) {

  #if IS_SCARA
    // Only Z homing (with probe) is permitted
    if (axis != Z_AXIS) { BUZZ(100, 880); return; }
  #else

So I regressed bugfix 2.1.x to just the following and allowed it to home X and Y

#if ENABLED(MORGAN_SCARA)  

And the large arm actually homed, but very very slowly. then after homing it flung itself wild to the other end of travel.
So it seems like the axis is not being setup correctly.
...

no solution yet.

@Sejkorka
Copy link
Author

This answer that question, only G28 Z will fuction

  void homeaxis(const AxisEnum axis) {

    #if ANY(MORGAN_SCARA, MP_SCARA)
      // Only Z homing (with probe) is permitted
      if (axis != Z_AXIS) { BUZZ(100, 880); return; }

But there has to be soome way to do it, i look at the video from "How To Mechatronics" he build SCARA and for him MARLIN worked, but his MARLIN not working for me..

@shimaode
Copy link

I commented out the return code for SCARA

  void homeaxis(const AxisEnum axis) {

    #if ANY(MORGAN_SCARA, MP_SCARA)
      // Only Z homing (with probe) is permitted
      // if (axis != Z_AXIS) { BUZZ(100, 880); return; }

And in my case, the x axis can home in normal speed but it's not guaranteed to back to home position every time, sometimes it just stops before it even hit the endstop. And the y axis is going wild in an unnormal speed.

Looking into the homing code, this should be causing the problem:

const float move_length = 1.5f * max_length(TERN(DELTA, Z_AXIS, axis)) * axis_home_dir;
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Home Fast: ", move_length, "mm");
do_homing_move(axis, move_length, 0.0, !use_probe_bump);

This commands the head to move 1.5f * max_length of each axis

And in do_homing_move:

  #if IS_SCARA
    // Tell the planner the axis is at 0
    current_position[axis] = 0;
    sync_plan_position();
    current_position[axis] = distance;
    line_to_current_position(real_fr_mm_s);

line_to_current_position will call into planner.buffer_line and finally call into MP_SCARA's inverse_kinematics to translate this target position into MP_SCARA's arm angles.

The problem of the above code is that this homing target position calculated from 1.5 * max_length of axis is not guaranteed to get a valid arm angles after being sent into MP_SCARA's inverse_kinematics, it could be beyond the reach of the arms and get you a wrong arm angle, depends on your settings of the SCARA.

That's why in my case, the x axis can do homing normally and the y axis can not, because this homing position for x axis happens to be in the reach of the arms but the y axis is not so lucky.

Also this homing position for x axis just rotate my arm for under 90 degrees in my case, so when the arm is too far away from the endstop, it just stops before hits the endstop.

I think for SCARA, homing should be just keep rotating the arm until the endstops are hit instead of trying to use a far away position and do IK to that position for homing.

Not sure my ideas are right, correct me if I'm wrong. :-)

@ellensp
Copy link
Contributor

ellensp commented Dec 18, 2024

Ascii art of the mp_scara (shoulder joint)<==upper arm==>(elbow joint)<== forearm with a fixed hand==>
So we are using same terminology...

I have this homing but the arm must be positioned so the upper arm hits its endstop first, ie the forearm should point away from the endstops. (I can see no way around this as the upper arm must be in correct location before the forearm can get near its endstop)

diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp
index 820089d7ee..4e9cec1003 100644
--- a/Marlin/src/module/motion.cpp
+++ b/Marlin/src/module/motion.cpp
@@ -2467,7 +2467,7 @@ void prepare_line_to_destination() {
       #endif
     }

-    #if ANY(MORGAN_SCARA, MP_SCARA)
+    #if ENABLED(MORGAN_SCARA)
       // Tell the planner the axis is at 0
       current_position[axis] = 0;
       sync_plan_position();
@@ -2665,7 +2665,7 @@ void prepare_line_to_destination() {

   void homeaxis(const AxisEnum axis) {

-    #if ANY(MORGAN_SCARA, MP_SCARA)
+    #if ENABLED(MORGAN_SCARA)
       // Only Z homing (with probe) is permitted
       if (axis != Z_AXIS) { BUZZ(100, 880); return; }
     #else
@@ -3054,7 +3054,7 @@ void set_axis_is_at_home(const AxisEnum axis) {
     }
   #endif

-  #if ANY(MORGAN_SCARA, AXEL_TPARA)
+  #if IS_SCARA
     scara_set_axis_is_at_home(axis);
   #elif ENABLED(DELTA)
     current_position[axis] = (axis == Z_AXIS) ? DIFF_TERN(HAS_BED_PROBE, delta_height, probe.offset.z) : base_home_pos(axis);

Config files needs this added #define FEEDRATE_SCALING (without this the homing feed rate are all over the place)
Also disable #define VALIDATE_HOMING_ENDSTOPS

The XY homing procedure is it does a quick home on X and Y ie both move at once (this is required to keep the forearm pointing in the same direction during moving home)

Then the upper arm is re-homed, then the forarm is homed.

finally scara_set_axis_is_at_home is called to set home position to homeposition = { SCARA_OFFSET_THETA1, SCARA_OFFSET_THETA2} from Configuration.h

The homes reliably for me, but I have not tested anything else, especially not the sacra kinematics.

@Sejkorka
Copy link
Author

Sejkorka commented Dec 18, 2024

20241218_062724.jpg

This is my scara

@ellensp
Copy link
Contributor

ellensp commented Dec 18, 2024

This is the MP_SCARA https://www.thingiverse.com/thing:2487048 which is also what I tested on

@Sejkorka
Copy link
Author

Sejkorka commented Dec 18, 2024

Technically they are the same.

@ellensp
Copy link
Contributor

ellensp commented Dec 18, 2024

MP_SCARA has endstops in a weird location

ie.

IMG_20241218_184452

Yours is much more like https://howtomechatronics.com/projects/laser-engraving-with-diy-arduino-scara-robot-complete-guide/

The video https://www.youtube.com/watch?v=1QHJksTrk8s shows the endstops are independent. So a little different from the MP_SCARA

@Sejkorka
Copy link
Author

Sejkorka commented Dec 18, 2024

Yes, i took inspo from video, do you think i need to move endstops?

@Sejkorka
Copy link
Author

Sejkorka commented Dec 18, 2024

If I understand correctly, I need to achieve that the first and second axis are homed at the same time?

@ellensp
Copy link
Contributor

ellensp commented Dec 18, 2024

The patch I provided should make it work for you also.
You just don't have the issue where by the forearm needs to be out of the way, before homing.

It will still quick home until either the upper arm or forearm endstop is triggered, then it will re home upper arm then forearm

@Sejkorka
Copy link
Author

The patch I provided should make it work for you too.
You just don't have the issue where the forearm needs to be out of the way before homing.

It will still quick home until either the upper arm or forearm endstop is triggered, then it will re home upper arm then forearm

Great, I'll try it as soon as I get to work.

@Sejkorka
Copy link
Author

I commented out the return code for SCARA

  void homeaxis(const AxisEnum axis) {

    #if ANY(MORGAN_SCARA, MP_SCARA)
      // Only Z homing (with probe) is permitted
      // if (axis != Z_AXIS) { BUZZ(100, 880); return; }

And in my case, the x axis can home in normal speed but it's not guaranteed to back to home position every time, sometimes it just stops before it even hit the endstop. And the y axis is going wild in an unnormal speed.

Looking into the homing code, this should be causing the problem:

const float move_length = 1.5f * max_length(TERN(DELTA, Z_AXIS, axis)) * axis_home_dir;
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Home Fast: ", move_length, "mm");
do_homing_move(axis, move_length, 0.0, !use_probe_bump);

This commands the head to move 1.5f * max_length of each axis

And in do_homing_move:

  #if IS_SCARA
    // Tell the planner the axis is at 0
    current_position[axis] = 0;
    sync_plan_position();
    current_position[axis] = distance;
    line_to_current_position(real_fr_mm_s);

line_to_current_position will call into planner.buffer_line and finally call into MP_SCARA's inverse_kinematics to translate this target position into MP_SCARA's arm angles.

The problem of the above code is that this homing target position calculated from 1.5 * max_length of axis is not guaranteed to get a valid arm angles after being sent into MP_SCARA's inverse_kinematics, it could be beyond the reach of the arms and get you a wrong arm angle, depends on your settings of the SCARA.

That's why in my case, the x axis can do homing normally and the y axis can not, because this homing position for x axis happens to be in the reach of the arms but the y axis is not so lucky.

Also this homing position for x axis just rotate my arm for under 90 degrees in my case, so when the arm is too far away from the endstop, it just stops before hits the endstop.

I think for SCARA, homing should be just keep rotating the arm until the endstops are hit instead of trying to use a far away position and do IK to that position for homing.

Not sure my ideas are right, correct me if I'm wrong. :-)

Which version of MARLIN do you use?

@Sejkorka
Copy link
Author

void homeaxis

I cant find this piece of code, do i need too add it?

@Sejkorka
Copy link
Author

After some testing, I found that I need to force the X motor, or X axis, or as Marlin calls it, the A axis, to rotate in the opposite direction. But only when homing. I tried switching the homing direction and also reversing the motor's operation. I think there must be a mistake somewhere or rather a problem in the homing process. I will try more experiments tomorrow. Do you think you could provide me with your config file?

@ellensp
Copy link
Contributor

ellensp commented Dec 18, 2024

development work is done on bugfix 2.1.x

@Sejkorka
Copy link
Author

development work is done on bugfix 2.1.x

Can you send me please your configuratio or full marlin?

@ellensp
Copy link
Contributor

ellensp commented Dec 19, 2024

Configuration.zip

Im using a different controller, and no hotend..

@ellensp
Copy link
Contributor

ellensp commented Dec 19, 2024

In Marlin is https://github.com/MarlinFirmware/Marlin/blob/bugfix-2.1.x/Marlin/src/inc/Conditionals-5-post.h#L288-L295

#if IS_SCARA
  #if ENABLED(AXEL_TPARA)
    #define PRINTABLE_RADIUS (TPARA_LINKAGE_1 + TPARA_LINKAGE_2)
  #else
    #define QUICK_HOME   //  <<------------------------  disable this line 
    #define PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
  #endif
#endif

that forces quick home, I would disable this line for your thing.

@Sejkorka
Copy link
Author

How did you calcu

In Marlin is https://github.com/MarlinFirmware/Marlin/blob/bugfix-2.1.x/Marlin/src/inc/Conditionals-5-post.h#L288-L295

#if IS_SCARA
  #if ENABLED(AXEL_TPARA)
    #define PRINTABLE_RADIUS (TPARA_LINKAGE_1 + TPARA_LINKAGE_2)
  #else
    #define QUICK_HOME   //  <<------------------------  disable this line 
    #define PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
  #endif
#endif

that forces quick home, I would disable this line for your thing.

how did you get THETA1 and THETA2?

@Sejkorka
Copy link
Author

Sejkorka commented Dec 19, 2024

Homing is working, thank you so much, but next problem is here, when i type G0 X0 Y0 scara moves oposite direction, its moving towards switch

@Sejkorka
Copy link
Author

so i randomlly fixed problem with moving, but now its laggy, its moving very slowly

@shimaode
Copy link

How did you calcu

In Marlin is https://github.com/MarlinFirmware/Marlin/blob/bugfix-2.1.x/Marlin/src/inc/Conditionals-5-post.h#L288-L295

#if IS_SCARA
  #if ENABLED(AXEL_TPARA)
    #define PRINTABLE_RADIUS (TPARA_LINKAGE_1 + TPARA_LINKAGE_2)
  #else
    #define QUICK_HOME   //  <<------------------------  disable this line 
    #define PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
  #endif
#endif

that forces quick home, I would disable this line for your thing.

how did you get THETA1 and THETA2?

Here is a great article explaining how to get THETA1 and THETA2 in step 12
https://www.instructables.com/Single-Arm-SCARA-Plotter-With-HOMING/

@dekutree64
Copy link

dekutree64 commented Jan 11, 2025

I've done all I can remotely. You'll have to put some debug prints in the code to monitor the angular and cartesian coordinates to figure out what it's thinking.

One more thing just to be clear, the cartesian coordinate space is from the robot's perspective. Imagine you are the robot and it is your right arm. +Y is forward, +X is to your right.

Here's a diagram from my wall-mounted SCARA printer that might help.
CoordinateSystem

@Sejkorka
Copy link
Author

I've done all I can remotely. You'll have to put some debug prints in the code to monitor the angular and cartesian coordinates to figure out what it's thinking.

One more thing just to be clear, the cartesian coordinate space is from the robot's perspective. Imagine you are the robot and it is your right arm. +Y is forward, +X is to your right.

Here's a diagram from my wall-mounted SCARA printer that might help. CoordinateSystem

and is there any way to help via discord via camera? or something like that? to see exactly what he's doing?

@Sejkorka
Copy link
Author

I'm starting to think that the firmware is ignoring the set zero distance of the x-axis from the zero point of the workspace. It's just a guess, but no matter what I try it still hits the structure with the other arm, I tried to recalculate the steps and it didn't help, after setting a smaller number of steps it doesn't hit anymore, but that's because it doesn't hit the given distance and at that moment the distance traveled doesn't correspond to reality.

@Sejkorka
Copy link
Author

So i get it to moving and engraving, but there is little problem, lines are not straight, and i set home offset to right cornet but scarais moving to left corner

Image
Image

@Sejkorka
Copy link
Author

I've done all I can remotely. You'll have to put some debug prints in the code to monitor the angular and cartesian coordinates to figure out what it's thinking.

One more thing just to be clear, the cartesian coordinate space is from the robot's perspective. Imagine you are the robot and it is your right arm. +Y is forward, +X is to your right.

Here's a diagram from my wall-mounted SCARA printer that might help. CoordinateSystem

do you have idea, which can cause this problem?

@dekutree64
Copy link

Oh, I think I figured it out. You most likely need to subtract the shoulder angle from the elbow angle in inverse_kinematics,
delta.set(DEGREES(THETA1), DEGREES(THETA2 - THETA1), raw.z);
What I said before about delta.x and y being relative to global X axis was not quite correct. It's only THETA1,2,3 that are always relative to global X. The original MPSCARA uses a belt system that results in the second arm segment maintaining its orientation relative to the global X axis when the shoulder axis is moved, so in that case delta.y is also relative to global X. But in your case the elbow motor rides along with the shoulder rotation, so delta.y is relative to the first arm segment.

I think forward_kinematics will need to be modified too.

   const float a_sin = sin(RADIANS(a)) * L1,
                a_cos = cos(RADIANS(a)) * L1,
                b_sin = sin(RADIANS(b+a)) * L2,
                b_cos = cos(RADIANS(b+a)) * L2;

This is why we don't have easy-to-use SCARA code :) There are too many variations in arm construction, so even if we did have code for all of them, it would be confusing to figure out exactly which one you need. Mine is the worst of all, because it has both motors stationary like MPSCARA, but different reduction ratios on the shoulder and elbow so it doesn't perfectly cancel out the shoulder rotation like MPSCARA. I solved it by adding a new #define SCARA_CROSSTALK_FACTOR and doing delta.set(DEGREES(THETA1), DEGREES(THETA2 - THETA1 * SCARA_CROSSTALK_FACTOR), raw.z); in inverse_kinematics, and RADIANS(b + a * SCARA_CROSSTALK_FACTOR) in forward_kinematics. Perhaps we should integrate it into the main branch. For mine it's 0.33333, but it would work for yours too with crosstalk factor 1, and 0 for MPSCARA.

@Sejkorka
Copy link
Author

const float a_sin = sin(RADIANS(a)) * L1,
a_cos = cos(RADIANS(a)) * L1,
b_sin = sin(RADIANS(b+a)) * L2,
b_cos = cos(RADIANS(b+a)) * L2;

Add to configuration.h or in which file?

@dekutree64
Copy link

Scara.cpp, function forward_kinematics. Replace the existing similar code with that.

@Sejkorka
Copy link
Author

Image

Image

Image

Is this ok?

@dekutree64
Copy link

Looks good. Give it a try and see if it works.

@Sejkorka
Copy link
Author

I will try it, when i get to scara

@Sejkorka
Copy link
Author

Looks good. Give it a try and see if it works.

it doesn't work, it tries to go against the endstop and the square is the same shape just smaller in size, I'll attach a picture.

Image

@ellensp
Copy link
Contributor

ellensp commented Jan 24, 2025

non straight lines are often the result of incorrect machine arm measurements
arm measurements are between center points of rotation

@Sejkorka
Copy link
Author

non straight lines are often the result of incorrect machine arm measurements
arm measurements are between center points of rotation

if L1 is the arm that is closer to the base then everything is correct, especially what happened now is that instead of going to the right corner, the scara goes somewhere in the middle and when engraving it goes against the limit switches

@dekutree64
Copy link

Let's try this... mark bed zero with a piece of tape or something, home the printer, and take a photo from above. Print out delta.x, delta.y, current_position[X_AXIS] and current_position[Y_AXIS].

Then command it to move to some other position (anywhere that doesn't crash into itself) and take another photo from above and print out those variables.

Also post the whole SCARA section from Configuration.h.

That may be enough information for me to figure out what it's thinking.

@Sejkorka
Copy link
Author

Let's try this... mark bed zero with a piece of tape or something, home the printer, and take a photo from above. Print out delta.x, delta.y, current_position[X_AXIS] and current_position[Y_AXIS].

Then command it to move to some other position (anywhere that doesn't crash into itself) and take another photo from above and print out those variables.

Also post the whole SCARA section from Configuration.h.

That may be enough information for me to figure out what it's thinking.

Maybe a stupid question but how do I print delta.x and delta ?

@dekutree64
Copy link

Hmm, I can't remember how I did it before. Fishing through the code, I think M114 will work. It looks like it prints "Raw:" followed by the current_position values and "ScaraK:" followed by the delta values.

@Sejkorka
Copy link
Author

Image
This is my setup, if i set it to marlin and upload it to scara, after this i sent G00 X0 Y0, the scara wants to move towards the limit switch

@Sejkorka
Copy link
Author

also i get this when compiling

Image

@Ovaday
Copy link

Ovaday commented Jan 25, 2025

Just for the feedback.
I use latest Marlin 2.1.2.5.

I've built the same robot but with BTT_SKR_MINI_E3 controller and have the same issue.

In default configurations it only homes Z, after some adjustments (motion.cpp) it homes X, but with Y does some weird moves far from the defined range.

@Sejkorka if it's possible, can you please create a repository with your current working code? There's quite much that needs to be adjusted or was adjusted as I see from the discussion.
Would be really appreciated.

@Sejkorka
Copy link
Author

Just for the feedback. I use latest Marlin 2.1.2.5.

I've built the same robot but with BTT_SKR_MINI_E3 controller and have the same issue.

In default configurations it only homes Z, after some adjustments (motion.cpp) it homes X, but with Y does some weird moves far from the defined range.

@Sejkorka if it's possible, can you please create a repository with your current working code? There's quite much that needs to be adjusted or was adjusted as I see from the discussion. Would be really appreciated.

i will try

@Sejkorka
Copy link
Author

For a bed there are only two possible (X0,Y0) positions Front left or back right.

Your diagram seems to show your trying to set X0,Y0 to back left, an invalid settings.

i try back right

Image

and this happened

Image

@TexeCode07
Copy link

TexeCode07 commented Jan 25, 2025

Scara robot with Marlin Y axis Transition makes unnecessary rotation
Scara Arm(2 link) on Marlin firmware making revolution when x <=0 and coordinates changes on y axis mean after passing 0 makes one more rotation. Note both arm can move 360 no obstacle inbetween in hardware.
SEE LOGS
Recv:19:57:07.686: X:0.00 Y:220.00 Z:0.00 Count A:150B:155 Z:0
Recv:19:57:07.688: SCARA Theta:90.00 Psi:90.12
Recv:19:57:15.210: X:0.00 Y:220.00 Z:0.00 Count A:150B:155 Z:0 (3)
Recv:19:57:15.210: SCARA Theta:90.00 Psi:90.12
Recv:19:57:28.232: X:0.00 Y:20.00 Z:0.00 Count A:290B:11 Z:0
Recv:19:57:28.232: SCARA Theta:174.00 Psi:6.40
Recv:19:57:33.356: X:-10.00 Y:20.00 Z:0.00 Count A:335B:56 Z:0
Recv:19:57:33.356: SCARA Theta:201.00 Psi:32.56
Recv:19:57:43.649: X:-10.00 Y:0.00 Z:0.00 Count A:446B:159 Z:0
Recv:19:57:43.649: SCARA Theta:267.59 Psi:92.44
Till here the theta is +ve and when it goes y passes axis it take one more rotation as per kinematics to -49 degree
Recv:19:57:49.740: X:-10.00 Y:-10.00 Z:0.00 Count A:-83B:-383 Z:0
Recv:19:57:49.743: SCARA Theta:-49.80 Psi:-222.67
Recv:19:57:54.751: X:-10.00 Y:-20.00 Z:0.00 Count A:-57B:-350 Z:0
Recv:19:57:54.751: SCARA Theta:-34.20 Psi:-203.49
is this the same unnecessary rotation
Thank You : )

@dekutree64
Copy link

If I'm understanding the drawing correctly, then SCARA_OFFSET_X is 150, SCARA_OFFSET_Y is -150, and after homing the physical elbow is unbent, and M114 output is this?
Raw: 425.289, -223.763, 0
ScaraK: -15, 0

Is that correct?

@Sejkorka
Copy link
Author

If I'm understanding the drawing correctly, then SCARA_OFFSET_X is 150, SCARA_OFFSET_Y is -150, and after homing the physical elbow is unbent, and M114 output is this?
Raw: 425.289, -223.763, 0
ScaraK: -15, 0

Is that correct?

Yes, but M114 doesnt give me anything

@Ovaday
Copy link

Ovaday commented Jan 25, 2025

Hej @Sejkorka I'm still waiting your repository - sadly I haven't figured out how to fix the homing issue.

Rather what I found is huge error in Theta2 calculations. I don't actually know what causes this issue, but I've tried to change symbols, guess, do some subtractions, spent 5 hours on it - I haven't figured out what influences the following behavior, see row "t_soll" (Theta2 should be) and "t_calc" (how Marlin calculates Theta2):

Image

There are no error when X is in 0, but calculated Theta2 goes somewhere when we move X.

"t_ist" is my calculations, if converted to degrees and inverted (x -1) is then value that is usable for our case.

Here is my raw early fix on how kinematics have worked on my robot:
`
void inverse_kinematics(const xyz_pos_t &raw) {
const float x = raw.x, y = raw.y,
L1_sq = sq(L1), L2_sq = sq(L2), c = HYPOT(x, y), c_sq = sq(c),
THETA3 = ATAN2(y, x),
THETA1 = THETA3 - ACOS((c_sq + L1_sq - L2_sq) / (2.0f * c * L1)),
THETA2 = THETA3 - ACOS((c_sq + L2_sq - L1_sq) / (2.0f * c * L2));

const float C2 = (sq(x) + sq(y) - L1_sq - L2_sq)/(2.0f * L1 * L2);
const float S2 = sqrtf(1-sq(C2));
const float myTheta_psi_raw = atan2f(C2, S2);
const float J2_degree = DEGREES(THETA2);

const float MyTheta_psi_V2 = myTheta_psi_raw;
const float myJ2_degree_V2 = DEGREES(MyTheta_psi_V2);
const float myJ2_degree_180_V2 = 180+myJ2_degree_V2;

delta.set(DEGREES(THETA1), myJ2_degree_180_V2, raw.z);
//delta.set(raw.x, raw.y, raw.z);


  //DEBUG_POS("SCARA IK", raw);
  //DEBUG_POS("SCARA IK", delta);
  SERIAL_ECHOLNPGM("  SCARA (x,y) ", x, ",", y," Theta1=", THETA1, " Theta2=", THETA2," J2_degree=", J2_degree);
  SERIAL_ECHOLNPGM("  mySCARAv2 (C2,S2) ", C2, ",", S2, "MyTheta_psi_V2=", MyTheta_psi_V2, " myJ2_degree_V2=", myJ2_degree_V2," myJ2_degree_180_V2=", myJ2_degree_180_V2);
//

}`

I also attach an excel table that I found here:
https://www.instructables.com/DIY-SINGLE-ARM-SCARA-ROBOT/

I would like to prettify our adjustments and customizations, test them and make a merge request at the end + add customizations like swap rotations of axis by just a variable, etc.

Here's an excel that can be useful:
Instructable_Robot_Arm_Simulation.xls

@Sejkorka
Copy link
Author

Hey @Sejkorka I'm still waiting for your repository - sadly I haven't figured out how to fix the homing issue.

Rather what I found is a huge error in Theta2 calculations. I don't actually know what causes this issue, but I've tried to change symbols, guess, do some subtractions, spent 5 hours on it - I haven't figured out what influences the following behavior, see row "t_soll" ( Theta2 should be) and "t_calc" (how Marlin calculates Theta2):

Image

There are no errors when X is in 0, but calculated Theta2 goes somewhere when we move X.

"t_ist" is my calculations, if converted to degrees and inverted (x -1) is then value that is usable for our case.

Here is my raw early fix on how kinematics have worked on my robot:
`
void inverse_kinematics(const xyz_pos_t &raw) {
const float x = raw.x, y = raw.y,
L1_sq = sq(L1), L2_sq = sq(L2), c = HYPOT(x, y), c_sq = sq(c),
THETA3 = ATAN2(y, x),
THETA1 = THETA3 - ACOS((c_sq + L1_sq - L2_sq) / (2.0f * c * L1)),
THETA2 = THETA3 - ACOS((c_sq + L2_sq - L1_sq) / (2.0f * c * L2));

const float C2 = (sq(x) + sq(y) - L1_sq - L2_sq)/(2.0f * L1 * L2);
const float S2 = sqrtf(1-sq(C2));
const float myTheta_psi_raw = atan2f(C2, S2);
const float J2_degree = DEGREES(THETA2);

const float MyTheta_psi_V2 = myTheta_psi_raw;
const float myJ2_degree_V2 = DEGREES(MyTheta_psi_V2);
const float myJ2_degree_180_V2 = 180+myJ2_degree_V2;

delta.set(DEGREES(THETA1), myJ2_degree_180_V2, raw.z);
//delta.set(raw.x, raw.y, raw.z);

//DEBUG_POS("SCARA IK", raw);
//DEBUG_POS("SCARA IK", delta);
SERIAL_ECHOLNPGM(" SCARA (x,y) ", x, ",", y," Theta1=", THETA1, " Theta2=", THETA2," J2_degree=", J2_degree);
SERIAL_ECHOLNPGM(" mySCARAv2 (C2,S2) ", C2, ",", S2, "MyTheta_psi_V2=", MyTheta_psi_V2, " myJ2_degree_V2=", myJ2_degree_V2," myJ2_degree_180_V2=", myJ2_degree_180_V2);
//
}`

I also attach an excel table that I found here:
https://www.instructables.com/DIY-SINGLE-ARM-SCARA-ROBOT/

I would like to prettify our adjustments and customizations, test them and make a merge request at the end + add customizations like swap rotations of axis by just a variable, etc.

Here's an excel that can be useful:
Instructable_Robot_Arm_Simulation.xls

Yes im trying to upload, but it will be best if i send you a link to onedrive.

https://1drv.ms/f/c/667a584a1d9aa10f/ErxI_rMKsANNu7y5Qfk3fpUBBdgosy7mkd1tdi20UrTNzA

I will try your fix as soon as possible.

@dekutree64
Copy link

Here is my raw early fix on how kinematics have worked on my robot:

void inverse_kinematics(const xyz_pos_t &raw) {
const float x = raw.x, y = raw.y,
L1_sq = sq(L1), L2_sq = sq(L2), c = HYPOT(x, y), c_sq = sq(c),
THETA3 = ATAN2(y, x),
THETA1 = THETA3 - ACOS((c_sq + L1_sq - L2_sq) / (2.0f * c * L1)),
THETA2 = THETA3 - ACOS((c_sq + L2_sq - L1_sq) / (2.0f * c * L2));

See my earlier comments from Dec 29 and Jan 23. One should be THETA3 + ACOS(... and the other should be THETA3 - ACOS(... and which is which determines whether the arm is right-handed or left-handed. Also apply the offset const float x = raw.x - scara_offset.x, y = raw.y - scara_offset.y, which was originally only used by MORGAN_SCARA but is very useful for MPSCARA too.

@dekutree64
Copy link

dekutree64 commented Jan 26, 2025

Yes, but M114 doesnt give me anything

Hmm, try adding #define M114_DETAIL 1 in Configuration.h. I don't know if that's the proper way to enable it, but the code in M114.cpp is wrapped with #if that define.

I'd like to see your scara_set_axis_is_at_home, too. Reading back through the thread it's unclear which version you're using. The one in the main branch is broken, and shimaode gave conflicting instructions on how to fix it. This is another reason I never did a pull request after getting my arm to work, because I don't know if the home position should be defined as a cartesian x,y pair or angle pair. I use angles because it's easier to finetune, but I think the original MPSCARA used cartesian.

Also what are your settings for INVERT_X_DIR, INVERT_Y_DIR, X_HOME_DIR and Y_HOME_DIR? It sounds like there was some confusion regarding those before I joined in, which may be coming back to bite you now.

@Ovaday
Copy link

Ovaday commented Jan 26, 2025

Here is my raw early fix on how kinematics have worked on my robot:

void inverse_kinematics(const xyz_pos_t &raw) {
const float x = raw.x, y = raw.y,
L1_sq = sq(L1), L2_sq = sq(L2), c = HYPOT(x, y), c_sq = sq(c),
THETA3 = ATAN2(y, x),
THETA1 = THETA3 - ACOS((c_sq + L1_sq - L2_sq) / (2.0f * c * L1)),
THETA2 = THETA3 - ACOS((c_sq + L2_sq - L1_sq) / (2.0f * c * L2));

See my earlier comments from Dec 29 and Jan 23. One should be THETA3 + ACOS(... and the other should be THETA3 - ACOS(... and which is which determines whether the arm is right-handed or left-handed.

This fixes the direction.
My code adjustment is not about the direction, but about the error when I move the X axis. I made a calculations with a graph to test that out:

Image

Here I've adjusted calculations and labels to have a clear view of what's going on.

Legend:
angle_soll is mathematically correct angle
angle_marlin is how how Marlin calculates that with Minus sign
angle_plus sign - how Marlin calculated that with Plus sign
angle_mine what works for my robot
angle_transp is 270-angle_mine, to compare with angle_soll that these calculations are correct.

If you look close, green line have just an offset with yellow (calculated with negative sign) when X=0, but error starts to grow when we have X != 0.

Assumption: something wrong with Marlin Theta2 calculation and the formula that is used is not universal.

Also apply the offset const float x = raw.x - scara_offset.x, y = raw.y - scara_offset.y, which was originally only used by MORGAN_SCARA but is very useful for MPSCARA too.

Sure, but I don't use an offset at the moment

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

No branches or pull requests

7 participants