-
-
Notifications
You must be signed in to change notification settings - Fork 19.3k
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
Comments
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! |
MP_SCARA is quite broken in bugfix 2.1.x I Enabled debugging 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 G28 Z works as expected G28 Z G28 Y moves Z up 5mm as expected, but then does nothing. G28 Y 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 Im not sure that G28 X or Y should actually do anything since there isn't really a X or a Y endstop. |
disabling #define VALIDATE_HOMING_ENDSTOPS does allow G28 to complete, but does not move X or Y steppers G28 |
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; } |
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
So I regressed bugfix 2.1.x to just the following and allowed it to home X and Y
And the large arm actually homed, but very very slowly. then after homing it flung itself wild to the other end of travel. no solution yet. |
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.. |
I commented out the return code for SCARA
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:
This commands the head to move 1.5f * max_length of each axis And in
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 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. :-) |
Ascii art of the mp_scara (shoulder joint)<==upper arm==>(elbow joint)<== forearm with a fixed hand==> 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) 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. |
This is the MP_SCARA https://www.thingiverse.com/thing:2487048 which is also what I tested on |
Technically they are the same. |
MP_SCARA has endstops in a weird location ie. 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 |
Yes, i took inspo from video, do you think i need to move endstops? |
If I understand correctly, I need to achieve that the first and second axis are homed at the same time? |
The patch I provided should make it work for you also. 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. |
Which version of MARLIN do you use? |
I cant find this piece of code, do i need too add it? |
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? |
development work is done on bugfix 2.1.x |
Can you send me please your configuratio or full marlin? |
Im using a different controller, and no hotend.. |
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 calcu
how did you get THETA1 and THETA2? |
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 |
so i randomlly fixed problem with moving, but now its laggy, its moving very slowly |
Here is a great article explaining how to get THETA1 and THETA2 in step 12 |
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. |
Oh, I think I figured it out. You most likely need to subtract the shoulder angle from the elbow angle in inverse_kinematics, I think forward_kinematics will need to be modified too.
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 |
Add to configuration.h or in which file? |
Scara.cpp, function forward_kinematics. Replace the existing similar code with that. |
Looks good. Give it a try and see if it works. |
I will try it, when i get to scara |
non straight lines are often the result of incorrect machine arm measurements |
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 |
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 ? |
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. |
Just for the feedback. 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. |
i will try |
Scara robot with Marlin Y axis Transition makes unnecessary rotation |
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? Is that correct? |
Yes, but M114 doesnt give me anything |
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): 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:
}` I also attach an excel table that I found here: 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: |
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. |
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 |
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. |
This fixes the direction. Here I've adjusted calculations and labels to have a clear view of what's going on. Legend: 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.
Sure, but I don't use an offset at the moment |
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
Configuration.h
andConfiguration_adv.h
.Additional information & file uploads
Config adv.txt
Config.txt
The text was updated successfully, but these errors were encountered: