Polar kinemcatics: adds velocity scaling#7172
Polar kinemcatics: adds velocity scaling#7172Neelix96 wants to merge 8 commits intoKlipper3d:masterfrom
Conversation
Print near the origin lead in to fast motor movements, therefore the movement needs to be scaled down. The start of the scaling is done via a critical radius variable from the config Signed-off-by: Nils Hensch nils.hensch@gmx.de
|
Question for the reviewer: I changed max_velocity and max_accel from the PolarKinematics init function to self.max_velocity and self.max_accel, since the slow down part, needs those values (like it's done with self.max_z_velocity). I hope that won't be a problem. |
|
Please fix the tests. My 2 cents. (So, basically, have limits in rotations per second/radians per second or degrees per second). Your idea seems close to this, but it does that indirectly. Thanks, |
|
I tried extracting the rad/s, and also just limit the speed, if the bed really, but failed :D But if you just want it in rad/s, I should be able to do it. |
Signed-off-by: Nils Hensch nils.hensch@gmx.de
|
I think you should also add a mention of the new parameter in the config reference |
Changes the speed limit from a radius based variable to a rotation velocity limit. Signed-off-by: Nils Hensch nils.hensch@gmx.de
|
JFYI, you probably want to update the And you can run tests locally to reproduce and look at the log: (I didn't verify the calculations; I'm a little puzzled) So Also, you can reduce complexity by a simple -Timofey |
|
Also, my pure guess, that you can simplify everything now, if you do: So, if the output is close to |
Adds max_rad_velocity for reducing rotational velocity as variable to config reference Signed-off-by: Nils Hensch nils.hensch@gmx.de
I will try to do that!
thx for the tip! I will have to think about your other message :D |
That should work, Marlin does implement it similarly, I think. The one thing I'm still lost about: wouldn't you still have to compute the minimal distance? |
IDK what to do with it, like logic seems simple So, I do not understand where the minimal distance could play a crucial role here. But I'm not sure it can be solved or if it makes sense to be solved (extreme cases, our move is 1um for example) Hope that helps, I think the only optimization that can be done is if we can split the move somehow, so if the move is not strictly along the circle or along the radius, we may be overly conservative sometimes. But it should be generally covered with adequate limits, I think. |
|
I will add your solution, and we will see :D for now, it definitely seems like the more elegant version. |
docs/Config_Reference.md
Outdated
| max_z_accel: | ||
| # This sets the maximum acceleration (in mm/s^2) of movement along | ||
| # the z axis. The default is to use max_accel for max_z_accel. | ||
| max_rad_velocity: |
There was a problem hiding this comment.
Typically, optional parameters begin with #, and default values are specified after ":" if the value is static.
So i implemented it, and it kinds works, but I have trouble matching it to an angular velocity. Every idea I came up with, either contained a time, which I have no idea how to calculate (v=s/t doesn't work here, because the angle doesn't change linear) or is radius dependent. For now, the best solution for me would be to stay with my old code. But I'm open for ideas on how to fix the other code. If wanted, I can also push it here |
|
Ah, About the time calculations, move is generated above: So, you should be able to access move time from here: Where Hmmm, but it calculates later, within the lookahead, Hmmm. I guess, you can access the initial time estimation from
Within the current Cartesian motion planning, time is Where later, lookahead, SCV, and cruise ratio make our estimation more correct, closer to reality. Hope that explains something, |
|
ok, first a few assumptions from my side:
For the next, less assume instantaneous cartesian acceleration for a first approximation. If I tell klipper to move from (100, 0.5) to (-100, 0.5), then the rotational axis will rotate slowly in the beginning, accelerating until it reaches its peak on its closest to the center and then deceleration again. At least that is whats happening with the stock klipper setup. From that I would say, that the angular velocity is not uniform over the whole movement, therefore we can't say v_angular = angle delta / time. (with time = v_carth * distance_carth). The only way that might work in my opinion, would be with the minimum step time for that move. That script give for motions with the same angle difference (rad_dist) and min. distance to the center, but different lengths, different angular velocities (v_angular). But it should give the same.
The only point, where you can say v_angluar = v_cart is when the velocity vector is perpendicular to the position vector (I hope that is the correct translation). And that also happens to be at the smallest distance (following my assumptions), which would again lead to my previous implementation. Please correct me, if you spot a mistake in my assumptions, I just want to print next to the center :D |
They are correct
There are the same travel speeds, different distances, so the average expected angular travel speed will be different. If we want to do "close" to ideal implementation, and if you are concerned about different angular velocities, we can make our approximation more precise. Okay, I've reused your script and slightly updated it. This is our problem: I have no idea about practical rad/s values, but if you want, you can reuse the same logic as in the script (peak 250 rads/s) Determine the actual peak rad/s value inside the move, and apply the limit by this value, instead of the average one. This is a more correct solution than the use of average angular velocity. Where one can do a third approximation, and solve the equation for some small degrees: Any next increase in calculation precision would require lookahead data, I think. Hope that clarifies something, |
|
It's been a while since I looked at the polar kinematics. When I last looked though, I concluded there were three things that needed to be done:
It's been a while since I've looked at this, so take my comments with a "grain of salt". Maybe that helps a little though, |
But my implementation here, does already implement it in that way. The peak velocity will be at the closest distant and there, if perpendicular, max angular rotation is the same as the maximum speed. And it doesn't care about steps size and so on. The only downside currently is, that if the position vector of the minium radius point is not perpendicular, then we still scale it down. E.g. moving in a straight line from (100,0) to (1,0). But that should be fixable. |
The above suggestion doesn't care about step size, and so on; it is just some "small" constant to make calculations finite, where we can increase precision, by making more calculations or vice versa.
I may have misinterpreted something, but you didn't calculate the angular velocity. Because if you divide the average speed (80mm/s as in the example above) by the min distance 0.25mm as in the example above:
Okay, I got what you meant. Your approach should work.
I guess this can be handled with start/end angle calculations, because the angle difference will be equal to zero. Okay, then I guess, for the kinematic side limits, this should work. Thanks, EDIT, I'm stupid, there should be 240 -> 320 |
|
I tried some things over the last few days and I just can't get the "descaling" for straight lines to work. I mean, for perfect straight lines it works (e.g. (100,0) to (1,0)), but smaller movements like (1,1) to (2,0) just escalate. So what is the current status:
Open General question: Did I forget anything, or should I change something else? |
|
It is batch mode E2E tests,
Can you elaborate and explain the issue? From what I understand, it works exactly as designed. Both examples seem to me to have a minimal radius of 1 mm. So, the angular velocity limit will be the same. Thanks, |
|
Thanks for the explanation, I hope I did add it right. Sorry, I jumped ahead in my thoughts:
But the first one could have moved with normal speed. I was able to solve that specific problem, but didn't know how to interpolate for movements like (100, 0.1 -> 1, 0.1) correctly, without breaking other moves. So it is not really a problem, but more of a speed optimization thing :D |
There was a problem hiding this comment.
LGTM
So, to summarize my understanding, you compute the minimal radius for a move, which is used to compute the instant angular velocity at the minimal radius.
Where we assume there is some absolute angular velocity limit, which is used for the scaling.
Which can be tested with circular print/spiral or with FORCE_MOVE.
Possible future optimizations can be:
- Do not limit the move which are in line with the radius (point to point angular diff is zero)
- Use gcode transform to split the input G-code and avoid singularity at zero.
Thanks,
-Timofey
One can make a video on the discourse with proof of how it performs %)
|
Yes, that summarizes it! |
|
Thanks. I have some questions and comments. I don't understand what I don't understand what the three cases within The code doesn't look like it properly updates velocity for XYZ moves - for example a move from 0,1,100 to 0,-1,1 . It's not a show stopper, but for what it is worth, I'm not sure it's a good idea to limit the velocity of all moves. The concern is that it is easy for a user to accidentally set an angular velocity such that it is the limit for most moves throughout the bed. In that situation, basically every move gets a different top speed - which causes every move to get a different amount of pressure advance and every move to get a different set of input_shaper actions. This can cause subtle print issues with no clue to the user why. In contrast, if one were to only apply the limit to moves that come within some distance of the origin (eg, 15mm) then users have a better chance of understanding what velocities need to be adjusted (regular slicer velocity or angular velocity). I'd recommend against documentation like "A value of 0 deactivates the scaling. The default is 0." - I'd replace it with something like "The default is to not apply max angular velocity limits." . Cheers, |
My 2 cents, I think, it is hard to define a limit that way, because one can set the velocity to some high value, which will violate the angular velocity limit at the higher radius/distance. We can estimate the max velocity at R as 15 * 2 = 30 mm/s Probably, the parameter can be handled another way, mark it as above .0 and default value to some "large" value, for example Also, with the known -Timofey |
|
Thanks for all the new input! The three cases are the following: the start point is the nearest point, the end point is the nearest point and the nearest point lies on the line between start and end point. The magic -0.1 existed to catch some numeric error of which I was afraid at the time. I think I can set it to 0, but I would rather test it, before making a final statement. XYZ moves work completely fine for me. Since there is virtually no difference between (0,1,100)->(0,-1,1) and (0,1,1)->(0,-1,1) the movement is slowed down in the same way. Or did I misunderstood the problem? In my opinion the down scaling "safes" the print, since beyond the limit the printer will just stop printing or the motor will slip steps. Since it is an optional feature, I would set on the user to read the documentation? I could add a note to the parameter about your concerns. Otherwise a log entry about the critical radius for the max_velocity can be outputted, like Timofeys suggested. I will change the documentation about the default value. Thx for the input, looking forward for your reply |

Prints with the polar kinematic near the origin leads in to fast motor movements, therefore I implemented a simple linear downscaling of movements near the center. To check, if a movement will come too close to the center, the minimal distance of the movement line is calculated. If that distance is smaller than a critical value, configurable via the printer.cfg, it will reduce the speed and maximum acceleration based on the distance.