pantor / ruckig

Motion Generation for Robots and Machines. Real-time. Jerk-constrained. Time-optimal.
https://ruckig.com
MIT License
640 stars 155 forks source link

Automatic Scaling for Increased Numerical Range #71

Closed Fubini2 closed 2 years ago

Fubini2 commented 2 years ago

Dear pantor,

we are testing your fabulous code in the environment of real-time control of laser scanners. These are characterized by the fact that the input data of the higher derivatives is very high. In addition, the interpolation cycle time is extremely short with a few micro seconds. Here we have found problems with the numerical stability of the solver for the zeros of the polynomials in the time_none() cases. However, we made good experiences here if we scale the input data from s to ms. In addition, we are currently considering whether we should always scale that the maximum jerk is exactly 1.0.

Could you imagine to scale always internally? From our point of view this would generally bring more stability into the algorithm.

In case you want to try this out, typical input data from us are e.g.

v_max = 400.0, a_max = 25600659.591502719, j_max=905096679918.78088 p0 = 0.0, v0 = 0.0 , a0 = 0.0 pf = 0.0, vf = -282.84271247461902, af = 0.0

The time optimal solution to this problem should be a positive acceleration trapezoid immediately followed by a negative acceleration trapezoid. Thus, solving one of the time_none() cases. However, the zeros polynomial solver does not find any roots.

Best wishes and keep up the good work Fubini

pantor commented 2 years ago

Hi @Fubini2,

much appreciated! Just to make sure, I've written a small paragraph about the numerical stability here:

The numerical exactness is tested for the final position and final velocity to be within 1e-8, for the final acceleration to be within 1e-10, and for the velocity, acceleration and jerk limit to be within of a numerical error of 1e-12. These are absolute values - we suggest to scale your input so that these correspond to your required precision of the system. For example, for most real-world systems we suggest to use input values in [m] (instead of e.g. [mm]), as 1e-8m is sufficient precise for practical trajectory generation. Furthermore, all kinematic limits should be below 1e12. The maximal supported trajectory duration is 7e3, which again should suffice for most applications seeking for time-optimality. Note that Ruckig will also output values outside of this range, there is however no guarantee for correctness.

Your use case has a very high jerk limit (9e12) which was not relevant for Ruckig for now, as we have control rates in the order of milliseconds for typical robotic applications. So in general it only makes sense to have a_limit < 2*v_limit/control_rate and j_limit < 2*a_limit/control_rate as otherwise the system doesn't have an effective acceleration or jerk limit due to the discrete control rate, but because of your very high control rate with microseconds this of course makes sense.

I'm very much interested to make your use case work in Ruckig. At first, you could try to scale your input even smaller, so e.g. to use

v_max = 0.4, a_max = 25600.659, j_max=905096679.918
p0 = 0.0, v0 = 0.0 , a0 = 0.0
pf = 0.0, vf = -0.282, af = 0.0

for input. Does trajectory generation then work reliably? Automatic scaling could be one solution for that. Ruckig even had automatic scaling once, however then we can't guarantee a numerical exactness (e.g. these 1e-8 for the final position), so I removed this feature. However I'm open to bring that back again, maybe with an option for disabling automatic scaling.

Another possibility would be to add a constant scale to these checks for numerical exactness (e.g. to use 1e-5). This would require a bit of hyper-parameter tuning on the user side, so I think this should not be the way to go.

Fubini2 commented 2 years ago

Hi @pantor,

thanks for you remark. I have seen your the comments on numerical stability and understand your remarks on guaranteed accuracy of your solution. I think optional scaling would be a good idea.

The above input data represents totally unscaled data. To test your code I implemented two different scaling strategies outside of ruckig

Fubini

pantor commented 2 years ago

Hey @Fubini2, I've got a few questions about your use-case of controlling laser scanners I which like to learn more about. Maybe you can drop me your mail address at info@ruckig.com?

pantor commented 2 years ago

I'll close this in favor of #123. The problem I have with automatic scaling is that it also changes the precision of the overall algorithm. Thanks so much for your input!