-
-
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 |
okay, i get it, now... why its moving "laggy"? |
I'm using bugfix2.1x branch Homing function is back to normal after applying ellensp's patch. But the arms' moving is not working properly.
After the changes above, my arm moves normally. |
Can you please share your modified file? |
here is my patch. My branch is bugfix-2.1.x |
moving is working, but i thing inverse kinematics not working |
Probably because the inverse kinematics is left handed but you want right handed? |
I think, its possible to do this in marlin? |
Maybe you can try to add some console output in I think maybe you need to makesure your version of inverse kinematics matches your machine, I'm not sure which kind of inverse kinematics you are using, left handed or right handed? |
my scara is similiar to this https://www.youtube.com/watch?v=8qc044LY6hc&t=798s |
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: