Skip to content

Polar kinemcatics: adds velocity scaling#7172

Open
Neelix96 wants to merge 8 commits intoKlipper3d:masterfrom
Neelix96:polar-kinematics-velocity-scaling
Open

Polar kinemcatics: adds velocity scaling#7172
Neelix96 wants to merge 8 commits intoKlipper3d:masterfrom
Neelix96:polar-kinematics-velocity-scaling

Conversation

@Neelix96
Copy link

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.

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
@Neelix96
Copy link
Author

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.

@nefelim4ag
Copy link
Collaborator

nefelim4ag commented Jan 23, 2026

Please fix the tests.

My 2 cents.
I think it can be more intuitive to limit the rad/s, so we can test how fast the bed is accelerating/rotating at the edge.
And use that value in radians, as a limit, and downscale max velocity and maybe acceleration to account for rad/s and rad/s^2 limits.

(So, basically, have limits in rotations per second/radians per second or degrees per second).
(In this case, it is necessary to calculate how far/fast we will travel in radians, though..)

Your idea seems close to this, but it does that indirectly.

Thanks,
-Timofey

@Neelix96
Copy link
Author

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.
Thanks for the input!

Signed-off-by: Nils Hensch nils.hensch@gmx.de
@MRX8024
Copy link
Contributor

MRX8024 commented Jan 23, 2026

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
@nefelim4ag
Copy link
Collaborator

nefelim4ag commented Feb 1, 2026

JFYI, you probably want to update the example-polar.cfg and ./test/klippy/polar.test to add a test for your limits.

And you can run tests locally to reproduce and look at the log:

$ python3 scripts/test_klippy.py -d out/ ./test/klippy/polar.test -k
    Starting ./test/klippy/polar.test (example-polar.cfg)

    All 1 test cases passed
$ cat _test_.log

(I didn't verify the calculations; I'm a little puzzled)
But it seems to me, that:

peak_velocity = math.sqrt(move.max_cruise_v2)

So peak_velocity/min_dist seems confusing.

Also, you can reduce complexity by a simple return

if self.v_rad_max == 0:
    return
if min_dist == 0:
    return
# & etc

-Timofey

@nefelim4ag
Copy link
Collaborator

nefelim4ag commented Feb 1, 2026

Also, my pure guess, that you can simplify everything now, if you do:
(if origin is 0, 0)

rad_start = math.atan2(y1, x1)
rad_end = math.atan2(y2, x2)
math.atan2(180, 0) = 1.5707963267948966
math.atan2(-180, 0) = -1.5707963267948966
rad_end - rad_start = rad_dist # -3.14

So, if the output is close to math.pi, it is half of a full rotation.
So, if travel is planned to be 1s, that means we will rotate at 3.14 rads/s
Think I.
So, if max_rad_v is 1, we have to limit the speed/accel as you already do * 1 rads / 3.14 rads

Adds max_rad_velocity for reducing rotational velocity as variable to config reference

Signed-off-by: Nils Hensch nils.hensch@gmx.de
@Neelix96
Copy link
Author

Neelix96 commented Feb 1, 2026

JFYI, you probably want to update the example-polar.cfg and ./test/klippy/polar.test to add a test for your limits.

And you can run tests locally to reproduce and look at the log:

$ python3 scripts/test_klippy.py -d out/ ./test/klippy/polar.test -k
    Starting ./test/klippy/polar.test (example-polar.cfg)

    All 1 test cases passed
$ cat _test_.log

I will try to do that!

(I didn't verify the calculations; I'm a little puzzled) But it seems to me, that:

peak_velocity = math.sqrt(move.max_cruise_v2)

So peak_velocity/min_dist seems confusing.
I used 'v_rot' as angular velocity (i thought until a few minutes ago "rotational velocity" is the correct English word, but it isnt ... the variable will be renamed to v_angular). For simplicity, I assumed, that the maximum angular velocity will be at the closest point to the center (worst case). Since velocity vector and distance vector should be perpendicular in that case, 'v_angular = v_max / min_distance'. With the assumption, that move.max_cruise_v2 contains the squared max. velocity in that move, it would result in the formula I used. Everything was to simply compare it to the limiting variable v_rad_max (soon renamed). I can also do it the other way around, for me, it was just the more used way.
I hope I did understand your point right.

Also, you can reduce complexity by a simple return

if self.v_rad_max == 0:
    return
if min_dist == 0:
    return
# & etc

thx for the tip!

I will have to think about your other message :D

@Neelix96
Copy link
Author

Neelix96 commented Feb 1, 2026

Also, my pure guess, that you can simplify everything now, if you do: (if origin is 0, 0)

rad_start = math.atan2(y1, x1)
rad_end = math.atan2(y2, x2)
math.atan2(180, 0) = 1.5707963267948966
math.atan2(-180, 0) = -1.5707963267948966
rad_end - rad_start = rad_dist # -3.14

So, if the output is close to math.pi, it is half of a full rotation. So, if travel is planned to be 1s, that means we will rotate at 3.14 rads/s Think I. So, if max_rad_v is 1, we have to limit the speed/accel as you already do * 1 rads / 3.14 rads

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?

@nefelim4ag
Copy link
Collaborator

nefelim4ag commented Feb 1, 2026

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
If requested rad/s are higher than allowed, we scale down the Speed/Acceleration to meet the criteria
If not, Speed/Acceleration are same as it was.

So, I do not understand where the minimal distance could play a crucial role here.
Only if we try to account for microstep resolution, or something?
Like, we can't really limit anything that is inside one microstep for the rotational bed.

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,
-Timofey


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.

@Neelix96
Copy link
Author

Neelix96 commented Feb 1, 2026

I will add your solution, and we will see :D for now, it definitely seems like the more elegant version.

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:
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Typically, optional parameters begin with #, and default values ​​are specified after ":" if the value is static.

@Neelix96
Copy link
Author

Neelix96 commented Feb 8, 2026

Also, my pure guess, that you can simplify everything now, if you do: (if origin is 0, 0)

rad_start = math.atan2(y1, x1)
rad_end = math.atan2(y2, x2)
math.atan2(180, 0) = 1.5707963267948966
math.atan2(-180, 0) = -1.5707963267948966
rad_end - rad_start = rad_dist # -3.14

So, if the output is close to math.pi, it is half of a full rotation. So, if travel is planned to be 1s, that means we will rotate at 3.14 rads/s Think I. So, if max_rad_v is 1, we have to limit the speed/accel as you already do * 1 rads / 3.14 rads

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

@nefelim4ag
Copy link
Collaborator

nefelim4ag commented Feb 8, 2026

Ah,
For calibration,
One can use the FORCE_MOVE for the bed, to see when it will not be able to rotate/accelerate: https://www.klipper3d.org/G-Codes.html#force_move_1

About the time calculations, move is generated above:
https://github.com/Klipper3d/klipper/blob/master/klippy/toolhead.py#L400

So, you should be able to access move time from here:

        self.accel_t = accel_d / ((start_v + cruise_v) * 0.5)
        self.cruise_t = cruise_d / cruise_v
        self.decel_t = decel_d / ((end_v + cruise_v) * 0.5)

Where accel_t + cruise_t + decel_t is the total time, between start and the end position, I think.

Hmmm, but it calculates later, within the lookahead, Hmmm.

I guess, you can access the initial time estimation from move.min_move_t


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.

Within the current Cartesian motion planning, time is distance/velocity, so v=distance/time is a correct estimation.
Without radians/s limits, it will take about this time to move from the start pos to the end position.
So, requested radians/s at this point in the calculation is equivalent to the requested speed.
And the time for both is the same."


Where later, lookahead, SCV, and cruise ratio make our estimation more correct, closer to reality.
I'm not sure if it is worth it, to implement basic junction calculations or call them from polar kinematics with some dummy values to estimate the real average time/velocity.

Hope that explains something,
-Timofey

@Neelix96
Copy link
Author

Neelix96 commented Feb 9, 2026

ok, first a few assumptions from my side:

  • I assume that every requested motion is a line
  • The orientation of the line doesn't matter ( from (100, 0.5) to (-100, 0.5) is the same as (0.5, 100) to (0.5, -100) and so on)

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.
I also have a small test script for the v_angular velocity in this case:

x1=50
y1=0.25
x2=-50
y2=0.25
v_max = 80

time = math.sqrt((x2-x1)**2 + (y2-y1)**2) / v_max
rad_start = math.atan2(y1, x1)
rad_end = math.atan2(y2, x2)
rad_dist = (rad_end-rad_start+math.pi) % (2*math.pi) - math.pi # normalize it between -pi and pi
v_angular = abs(rad_dist / time)

print("Rad Start: {}, Rad End: {}, Rad Dist: {}, V_Angular: {}".format(rad_start, rad_end, rad_dist, v_angular))

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.
Here are a few test values with the same angle:

  • x1=50, y1=0.25, x2=-50, y2=0.25 -> Rad Start: 0.0049999583339583225, Rad End: 3.136592695255835, Rad Dist: 3.131592736921877, V_Angular: 2.5052741895375013
  • x1=100, y1=0.5, x2=-100, y2=0.5 -> Rad Start: 0.0049999583339583225, Rad End: 3.136592695255835, Rad Dist: 3.131592736921877, V_Angular: 1.2526370947687506

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

@nefelim4ag
Copy link
Collaborator

nefelim4ag commented Feb 9, 2026

few assumptions from my side

They are correct

But it should give the same.

There are the same travel speeds, different distances, so the average expected angular travel speed will be different.
That is the whole point of calculations in radians.
This is our first approximation.

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:
image
This is our second approximation.
One can use the stepper gear ratio, RT, and microstepping to increase resolution.

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)
polar_emulation.py

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.
But it will be conservative, for long moves around the origin point.

Where one can do a third approximation, and solve the equation for some small degrees:
360 / (400 * 256) = 0.003515625 degrees
That allows us to determine the distance in mm from one step, and then the angular speed.

Any next increase in calculation precision would require lookahead data, I think.

Hope that clarifies something,
-Timofey

@KevinOConnor
Copy link
Collaborator

KevinOConnor commented Feb 10, 2026

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:

  1. Moves that go to or through the 0,0 point need to be identified and modified. For example, a move from 100,100 to -100,-100 would go through the 0,0 point. Moves through the 0,0 point lead to internal math errors and infinite rotational velocity, so they need to be avoided. One simple way to avoid these problems is to identify troublesome moves and split them into two moves that are not suspect - for example, 100,100 -> -100,-100 could be changed to 100,100 -> 0.000001,-0.000001 -> -100,-100 . A "gcode move transform" could be used to do this splitting. You can look at how bed_mesh.py registers gcode transforms and splits moves as an example.
  2. Identify moves that travel near the 0,0 point and split them into smaller moves. For example, 100,100 -> 0.000001,-0.000001 could be replaced with a series of moves like 100,100 -> 20->20 -> 5,5 -> 2,2 -> 1,1 -> 0.8,0.8 -> ... -> 0x000001,-0.000001 . The same "gcode move transform" identified above could be used to do this splitting.
  3. Identify moves that travel near the 0,0 point and reduce their speed so as to avoid high angular velocity of the bed. This could be done in the same gcode move transform or it could be done in the kinematic classes.

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,
-Kevin

@Neelix96
Copy link
Author

Determine the actual peak rad/s value inside the move, and apply the limit by this value, instead of the average one.

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.
Especially if we start so look into steps, is there any speed benefit instead of using the current implementation, where the angular velocity is calculated using the minimum distance?

@nefelim4ag
Copy link
Collaborator

nefelim4ag commented Feb 10, 2026

And it doesn't care about steps size and so on.

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.

is there any speed benefit instead of using the current implementation, where the angular velocity is calculated using the minimum distance?

I may have misinterpreted something, but you didn't calculate the angular velocity.
You do calculate the min distance, but what you do with it later is unclear to me.

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:

x1=50
y1=0.25
x2=-50
y2=0.25
v_max = 80

ab_x = x2-x1
ab_y = y2-y1
ap_x = -x1
ap_y = -y1

ab_ap_dot_product = ab_x * ap_x + ab_y * ap_y # 5000
ab_length = math.sqrt(ab_x ** 2 + ab_y ** 2)     # 100

# Check if the projected point lies on the bounded line segment
if ab_ap_dot_product <= -0.1: # false
      dist = math.sqrt(ap_x ** 2 + ap_y ** 2)
elif ab_ap_dot_product >= ab_length ** 2: # false
      dist = math.sqrt(p2[0] ** 2 + p2[1] ** 2)
else:
     dist = abs(ab_x * ap_y - ab_y * ap_x) / ab_length # 0.25
min_dist  = dist
80 / min_dist = 80 / 0.25 = 320

Hmmm, it is close to my above calculations, where with defined quantization, the peak is about 251
Hmmm, magic.
If I increase quantization from 0.9 degrees -> 0.1 degrees, the peak should be about 320.
I would assume that my approach amplifies some numerical error.

Okay, I got what you meant. Your approach should work.
(I did calculations for different segments, and it still seems valid/close to approximation).

But that should be fixable.

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,
-Timofey

EDIT, I'm stupid, there should be 240 -> 320

@Neelix96
Copy link
Author

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.
For now, I don't have any idea, how to address the issue. I would personally put that into another pull request, since the current implementation at least adds the ability to move closer than the center. If you have any ideas how to tackle that problem, please share them with me :D, but again I would rather put that in a new pull request, after discussing it in the klipper discourse forum.

So what is the current status:

  • I have a working velocity down scaling based on the minium distance to the center, controlled by a max. angular velocity parameter
  • Configuration Reference for the new max_angular_velocity parameter
  • The build tests do not show any errors

Open General question:
Since the new parameter is optional, is there a need to add it to the example-polar.cfg and the test (wouldn't know what to test there, since it's machine dependent)?

Did I forget anything, or should I change something else?
Cheers,
Nils

@nefelim4ag
Copy link
Collaborator

nefelim4ag commented Feb 17, 2026

It is batch mode E2E tests,
Normally, you want to set some limit and add a G-Code line to trigger it.
Basically, the test should show that your code didn't crash at least
Taking into account the examples above, one may want to cover every case:

  • 100, 0 -> 1,0
  • 1, 1 -> 100, 1
  • 100, 1 -> 1, 1
  • 50, 1 -> -50, 1

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.

Can you elaborate and explain the issue? From what I understand, it works exactly as designed.
You got a small radius, it has been applied to the requested velocity, and a limit has been applied or not.

Both examples seem to me to have a minimal radius of 1 mm. So, the angular velocity limit will be the same.

Thanks,
-Timofey

@Neelix96
Copy link
Author

Thanks for the explanation, I hope I did add it right.

Sorry, I jumped ahead in my thoughts:
The code does work perfect for me. But when I tested your implementation idea with the rotation difference between the location vectors, I found a unelegant side effect of my code. Since my code assumes, that every at every min_dist value, the velocity vector is perpendicular to the angular velocity vector, some movements are slowed down too much. E.g. the following movements have the same speed:

  • 100, 0 -> 1, 0
  • 100, 1 -> -100, 1

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
I also don't think it is that relevant in real world prints, since there are mostly smaller movements. And like Kevin already mentioned, it would be smart to split moves in a future implementation, which would also reduce the impact of that problem.

Copy link
Collaborator

@nefelim4ag nefelim4ag left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

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 %)

@Neelix96
Copy link
Author

Yes, that summarizes it!
And on discourse is now the videos showing: Timeout without the Feature, movements with a high angular velocity limit and with a slow one.
https://klipper.discourse.group/t/angular-velocity-scaling-for-polar-3d-printers/25662

@KevinOConnor
Copy link
Collaborator

KevinOConnor commented Feb 21, 2026

Thanks. I have some questions and comments.

I don't understand what distance_line_to_point() does. From the name I'd guess it finds the distance between a line and a point, but it only passes in a line. Perhaps the name should be adjusted.

I don't understand what the three cases within distance_line_to_point() are for. What's the magic -0.1 represent?

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,
-Kevin

@nefelim4ag
Copy link
Collaborator

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).

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.
For example, this is the "new" config:

[printer]
min_radius: 15 # mm
angular_v_limit: 2 #  radians

We can estimate the max velocity at R as 15 * 2 = 30 mm/s
So, for example, any move with a velocity larger than 32mm at a 16mm radius will not be limited and will violate the "physical" limit.

Probably, the parameter can be handled another way, mark it as above .0 and default value to some "large" value, for example 6283, which is 6283 / 6.283 = 1000 RPS, where 6.283 ~= 2*PI.
or even simply define in RPS, because it is more intuitive
With note that one can "bisect" that value down, with moves close to the origin.

Also, with the known max_velocity, one can estimate that the limit of N will apply at a radius >= max_velocity / N, and print that out to the log if that simplifies something._

-Timofey

@Neelix96
Copy link
Author

Neelix96 commented Mar 5, 2026

Thanks for all the new input!
distance_line_to_point calculates the shortest distance from the center to the movement line. Technically the name is correct, but since you mentioned it, "distance_to_center" or "smallest_distance_to_center" would be less confusing and I will change that, when I'm back near my printer and my PC.

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
~Nils

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

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

4 participants