Problem with path planner

I have a problem with path planner. I made custom mechanical system with 3DOF, direct movement is fine, but linear absolute/relative doesn’t work as it should and also speed is reduced.
Depending on the way I want to go: if it is positive movement, it will give back error “jump in axes“, even though I do want to move to position I was in previously. If I want to move in negative direction, it sometimes moves, but it is not linear movement and it keeps going back and forth while trying to close the distance by small incremets (picture below)

I took a look and the speed is getting reduced, so dynamic planner can have enough time to compute. And the robot will behave properly in both direction and linear movement, if I move only by 1mm increments (did a G-code to make a square, increase of 100mm in one go was not possible or it did the movement above, when switched to 100mm by 1mm increments , it is behaving as it should).

Can I get somehow into the settings of the planner to change some settings to hopefully solve this?

Current version of AS: 4.10.6.39
RunTime: F4.53
mappMotion: 5.21.2
mappServices: 5.21.0

Hello,

you can only Access the Settings of the Path-Planner which are accessible by the mappMotion Configuration Files. There are no “hidden parameters” available.

The error “jump in axes“ typical indicates that the inverse mathematics is not correct or switching between possible solutions and by this a huge jump in axis position is calculated. The system can detect this issue and sends the alarm.

Please test the Transformation in an ST-Task and make the proof that Inverse->Direct->Inverse does always result in a good loop.

Please also take care that you use only local Variables in Transformation Instance. These Functions will be called simultanious inside the PathPlanner. It is mandatory that they will not conflict each other.

The Transformation should not behave different by speed.
There must be some mathematical function in your code changing its behaviour due to the distance of the points. Could this be possible?

If it is a puplic development you can share more Data with the community to go into a depper investigation of the mathematics.
If it is not possible to share more data i would recommend to contact local support in Czechia. The Office in Bruno does have a very good knwoledge about Transformations.

Greetings
Michael

2 Likes

Hello,
thank you for your response. If I use Gcode program (that is making a square) by small increments, the geometry is sound, so I think the kinematics should be alright. Just in case it would be caused by global variables, I only used local variables (except this reference variable, where I do have length of arms and variable to choose which solution to choose, but I hard coded one just in case without solution or automatic finding of closest distance), but it didn’t solve the problem.

image
To be more clear, I traced what is happening. These charts are for X,Y, path speed and 2 Angles joints (3rd one will be same as 2nd) if I input linear movement of -100 in X, 0 change for Y.

And this is the Gcode program for square, which moves first -100 in X and the final path made. For feed rate I inputted 12000, which should be mm/min, so speed of 200, which wasn’t achieved, but I guess that is to maintain linear movement. Limit wise for axes it still should be doable to reach the speed/higher speed at least (all have same Velocity and Accel/Decel values).

The only custom functions I am using is my own Atan2, which I tested in different project, so it should be fine, but I did add WrapToPi function, so maybe I did a mistake there.

WrapToPi := angle;

IF WrapToPi > pi THEN
	WrapToPi := WrapToPi - 2.0*pi;
ELSIF WrapToPi < -pi THEN
	WrapToPi := WrapToPi + 2.0*pi;
END_IF;

And the thing why I think something is messing with the speed of my axes is due to this error, that keeps happening even if I am performing Direct movement to just firstly align axes to 10°,20°,20° from which I am making my analysis of behaviour. It says it is reducing the velocity of the movement, which is a bit strange, because if I trace it and I have wanted speed of 10 with Accel/Decel 500, it will reach the speed according to trace(1st trace), but if I put it to maximum of the axes limits, it won’t reach the speed(2nd trace), which is why I thought the speed is getting reduced.

I did also try to mess with axesgroup parameters for Geometry planning and Trajectory planning, but it didn’t help and behaviour stayed the same. On the picture they are almost unchanged, but I did changed TCP resolution to be more leniant and with the Limit time check resolution and buffer time for Trajectory planning.

Hello,

i will start with this warning, which limits your dynamic of the movement.

mapp Motion V 5.31 -2140987188: Invalid LimitRatio for {Joint axis}
Calculating the length of the permitted stop trajectory

You current Settings result in a maximum Stop Trajectory of 160 * 0.01 s = 1,6s
This means, all movements of the PathPlanner are restricted to this stop time.
If the Acceleration or Jerk are very low, your Velocity gets limited to match a maximum of 1,6s to stop the movement.

Currently you use a Acceleration of 5000 mm/s² and a Jerk of 1 mm/s³
The Jerkvalue is way to small to reach a relevant speed in the time of 1,6 s.

100 mm/s / 5000 mm/s² = 0,02 s
With your maximum acceleration you would have ramped up to max velocity in 0,02s.

5000 mm/s² / 1 mm/s³ = 5000 s
But you will reach your maximum acceleration with this Jerk after 5000 s.

Typical Values for Jerk are 1-20 * Acceleration. I would suggest you start with 5000 mm/s³.

It might be the cause that you did not had a look at the unit, and mixed it up with the jerk-filter on an ACOPOS Axis, which has the Unit in Seconds. But here in PathPlaner we have mesurement units / s³.

As by the other warning mentioned Torque limits are only supported by mechanical systems with a dynamic model. We do not jet have a interface for the Coustom Mechanical System to define the dynamic model. Please set the Torque Limit to “not Used”. If you need to secure your axis, please use a torque limit on the singel axis.
For example with “MC_LimitLoad”.



I would suggest that you reduce the resolution for the TCP to a typial value.
100 µm should be ok for typical machines. I do not think that your mechanic will have this resolution.

Lets see how this will change the behaviour. And then interate frome there.

Greetings
Michael

Hello,

thank you for the detailed response! These changes solved the lack of speed, but unfortunately they didn’t change the behaviour of movement. I tried to do some changes to Geometry and Trajectory planning parameters, but unfortunately, there is not a single change in behaviour. I made a simple table to represent, what the limit values were and what changes I did. Would you have some idea how to continue from here?

Hello,

I would not have expected any change due to this Parameters.
Those Parameters are mostly used to affect calculation ressources and cpu performance.

What does 4mm max; 25mm max… mean?
Is there an error after this distance.

The geometric calculations are done via the transformation functions only. If there is an geometric error you have to analyse the Transformation functions. Do you expect the inputs in the same fromat as supplied by the PathPlaner, …

Greetings
Michael

A few things I would add:

You mention about Inverse Kinematics function, but if I recall correctly, there is also a velocity version that needs to be implemented. When I’ve seen issues like this in the past it was in my velocity function because I was expecting it to use the Jacobian, but it actually expects what I think is more of a geometric differentiation, which has some nuance.

The other thing I would look at is how you are selecting solutions, for two reasons.

Base on how far apart the positions are, you could be getting wildly different previous positions, which can make selecting solutions difficult. If you get positions far apart, you might be selecting solutions that are incorrect. If you are commanding waypoints that are very close it could be that you are never seeing those far off planned positions and always select the correct solution, which could explain the behavior difference.

The other thing is that your rollover only handles a single turn, so if you are more than PI off (which may or may not be possible in your implementation) it will still be outside of PI. Again, depending on what you are doing, your wrap to PI could cause a jump. When I was using the Custom Kinematics in mapp motion it didn’t support wrapping axes, I don’t know if that has changed or if you have it configured correctly to do it.

2 Likes

Please double check the ‘inverse derivative’ function as recommended. This is (with the ‘inverse’ function) a base step for a geometry planning of interpolated movements (G00, G01, G02, MoveLinear, …).

Similarly, ‘direct’ + ‘direct derivative’ functions serve for point-to-point movements (G100, G101, MoveDirect, …).

The error ‘Jump in axes positions detected’ indicates that integration steps (based on the ‘inverse derivative’) failed to reach the target. It’s either a singularity, or some issue with the transformation functions. That also would explain why short movements are ok for you (a difference is small enough for its threshold).

It is a good idea to test all four main custom transformation functions (‘direct’, ‘inverse’, ‘direct derivative’, ‘inverse derivative’) as proposed in help.

3 Likes

Hello,
thank you all for your responses. I will try to answer all questions.

@michael.bertsch Those distances mean, what is the maximum possible distance of proper behaviour. So if I would do linear distance of 4mm in that direction, it behaves properly, more than that and it behaves wrongly. About the expect inputs in the same format, I am not sure what you mean exactly. The units are of distance (mm) are correct and the angle, which is in degrees gets converted in functions and then back to degrees, when I am sending it out. I am using Monitoring elements, to see, what is Path planner sending as wanted path, and it is generating those non-linear paths I send in the first post, or proper one, if the increments are small.

@Josh_Polansky I am using Jacobian for calculations and for this specific method I am reducing the 3x3 Jacobian into reduced 2x2 Jacobian, which I tested with my colleague in MATLAB and it is working fine there, but I will discuss the geometric differentiation with him as well tomorrow. As for choosing the solutions. I am normally doing it as a Case select and is determined by variable inside a reference enum, which also has the lengths of the arm links, tolerance etc. Right now, I hard coded single solution without any switching of solutions to eliminate possible mistakes. Later on, I will of course require switching, but that is still bit far off as of now. For the WrapToPi, I didn’t find any function inside AS, so I had to do my own, but I do not think the mistake is there.

@zbynek_uher I did my roundtrip test with just purely static numbers, and the result is fine and as expected, some more dynamic check I will be able to do after discussion with my colleague tomorrow. Another thing that surprised me a bit and it might be the issue, after I checked the help link for the test of inverse derivative, you are using TCP pos, TcpDer and Joint ref pos. I am used to different approach, where inverse derivative function is working with values of joint angles and TCP speeds, so for my inverse derivative function, I am only using Joint Ref Pos and TcpDer, which I might have misunderstood a bit. Does it require for me to actually recalculate the entire inverse kinematics first inside it? Right now it won’t be an issue, since I am only testing single solution, but later on (if it will even be possible to implement everything we want), it will create some very big function block, if I will need to do both inverse and inverse derivative in the same block.

Thank you again for your responses!

Well, JointRefPos for inverse derivative function are the last accepted joints. Let’s imagine principally that we are searching for a (so far unknown) red joint curve related to a (known) blue TCP curve.

The geometry calculator (precisely: mapp Motion module PathFinalizer) starts first with points like 1,2,3, and 4 (the beginning is the end of previous geometry, so it is already known).

  • Let’s say a system is happy with a red part before the point 1
  • But there is already some curvature in the red between points 1 and 2, so therefore additional points 5,6,7,8 are added (=inverse derivative calls)
  • And let’s assume a part between 1 and 2 is fine now, and the system makes the same between 2 and 3, i.e. points 9,10,11,12
  • Let’s say red segments 2-9 and 9-10 are then evaluated as good enough but 10-11 needs to be done more fine, i.e. new points 13,14,15
  • Etc.

Note 1: The reference joints jump around a bit therefore, and definitely don’t match to given TcpPos.

Note 2: Once the blue input TCP path is not a line but e.g. an arc or some spline, one enjoys non-constant input TcpDer as well.

I am with you that a majority of mechanical systems needs joints corresponding to TcpPos in order to calculate joint derivatives. Therefore, since mapp Motion version 6.2, the AddInput substructure was added to McPathGenCusMechInvDerType with JointPos corresponding to TcpPos. That change makes a usage of JointRefPos obsolete, and prevents user from a special inverse call inside inverse derivative function.

Sorry for the late reply, but this has solved the issue for me. In version 6.2., I will be using the AddInput from now on, but this project was done in 4.10., so I had to recalculate my inverse function. And also thank you on the clarification with the path creation.