Switchkins Master possible malfunction/bug.

More
02 Nov 2021 12:37 #224983 by Aciera
I have now tested this now on my mill (with an A-axis instead of the C-axis) and I can confirm the issue as reported.

Just a reminder that the problem does not occur if the first move after the switch is a cartesian move only, or a combined angular/cartesian move. The problem is there only if it is an angular move only


It actually seems to me that the issue only appears if the first line after the switch contains an angular move AND an 'redundant' linear move.

So this code very consistently shows the issue (although I did have the odd time when it actually worked as expected):

G0 X40 A0
kinematic switch here
G01 X40 A20 F100  <- this will execute as a rapid move


However this code works fine:

G0 X40 A0
kinematic switch here
G01 A20 F100 <- this move is executed with feedrate as specified



@NoJo Can you confirm the above on your setup. (Maybe you already stated further up but I didn't have time to read through the whole thread.)

I've run out of time for now but it is clear that the two comp files are not related to this issue as I can reproduce this on my own configuration.

Please Log in or Create an account to join the conversation.

More
02 Nov 2021 16:45 #225013 by NoJo
We have got the new sim working and have run the tests on the target hardware with the short circuit as requested. The short circuit makes no difference to the problem - ref the plots attached. The second plot is just zoomed in - please ignore the plot on joint.2.motion-pos-fb and axis.c.pos-cmd prior to the switch. I suspect these are happening as the homing does not complete due to the short circuit. However, the shape of the command after the swithkins switch clearly shows that the problem is still there irrespective of the short circuit.

With reference to the code - could I please request an update to the stest branch (as I am not able to rebuild the code myself at this stage). From my analysis of the debug prints, it seems the problem is originating in the call to getStraightVelocity from flush_segments. It would be useful to have the values printed in function getStraightVelocity if the value of debug_velacc is non-zero. So a build where

static int debug_velacc = 1;

would be appreciated.
Attachments:

Please Log in or Create an account to join the conversation.

More
02 Nov 2021 16:45 #225014 by Aciera
Looks like this happens only in G90 mode while (G93 & G91) and (G94 & G91) seem unaffected.
I also noticed that when using G93 the first move is faster than it should be but it is not as fast a G0 move.
And as already noted the issue does NOT appear if the first move includes a linear command (x,y,z) that is different from the current location (ie 'distance to go' DTG is non-zero). However the issue does NOT appear if only the z-DTG is zero. (this behaviour is the same in G17,G18 and G19)

@NoJo: could you verify that a DTG of zero for the Z axis does not cause the issue? So for example:

G0 X40 Z10 A0
kinematic switch here
G01 Z10 A20 F100 <- this move is executed with feedrate as specified

Please Log in or Create an account to join the conversation.

More
02 Nov 2021 16:46 - 02 Nov 2021 16:48 #225015 by NoJo
It is a relief that you can reproduce the problem. Thanks for the effort!
We have done the test as requested (ie first move after G12.1 does not specify an X axis value) - and can confirm that in this case, the problem is
not there.

(Only now saw your next post - will test and revert shortly)
Last edit: 02 Nov 2021 16:48 by NoJo.

Please Log in or Create an account to join the conversation.

More
02 Nov 2021 17:00 #225018 by Aciera
It seems to me that, in the cases where the issue appears, the smaller the linear DTG is the larger the feed rate becomes.
I'm not sure if this makes sense but I have run out of time for today.

Please Log in or Create an account to join the conversation.

More
02 Nov 2021 17:08 #225019 by NoJo
I ran the test
G0 X40 Z10 A0
kinematic switch here
G01 Z10 A20 F100 <- this move is executed with feedrate as specified
And confirm the move is correct in this case

Please Log in or Create an account to join the conversation.

More
07 Nov 2021 16:39 - 07 Nov 2021 16:58 #225561 by NoJo
I have managed to rebuild the linuxCNC software myself and as such can report on some progress on this issue.

In all tests below, I am using the ngc as follows 
G8 ;radius
G18
G01 X20       F800
G0 C0
G12.1
G01 X20  C20  F800 
G01 X-20 C20  F800
G01 X-20 C-20 F800
G01 X20  C-20 F800
G01 X20  C0   F800
G13.1

I believe the problem is arising due to the following lines in function handle_kinematicsSwitch:

      kinematicsForward(joint_posKinsSwitch,  &emcmotStatus->carte_pos_cmd,  &tmpFFlags, &tmpIFlags);                                           
      tpSetPos(&emcmotDebug->coord_tp, &emcmotStatus->carte_pos_cmd);


I printed the value of emcmotStatus->carte_pos_cmd.tran.x before and after the call to kinematicsForward. (kinematicsForward will be 
setting carte_pos_cmd.tran.x to the X axis Joint position). 

   Before : emcmotStatus->carte_pos_cmd X=-52.25000000
   After : emcmotStatus->carte_pos_cmd X=-52.2500000120

As the two values are not the same, the move is seen to be a Cartesian Move (very small...) as well as an Angular Move

(In previous posts I reported that in the case of the incorrect move, the values of vel, ini_maxvel and acc as output from functions getStraightVelocity/getStraightAcceleration in emccanon.cc were always set to zero. The values are in fact not zero, but very small. These very small values are generated as canon.cartesian_move && canon.angular_move are both non-zero (as dx is not zero). The value of out.tmax will 
be derived from the C axis move time (as this is the longest time), but the computation of out.dtot will use the dx value, which is very small - hence resulting in a very small out.vel value. The same applies in function getStraightAcceleration. I was able to get the correct vel and acc values by using a comparison to an EPSILON_ZERO value (rather than zero) in lines
        if (dx <= 0.0 && dy <= 0.0 && dz <= 0.0 &&
        du <= 0.0 && dv <= 0.0 && dw <= 0.0) {
and 
        if (da <= 0.0 && db <= 0.0 && dc <= 0.0) {
However - this did not solve the problem of the incorrect move....)

What I have established conclusively is that the incorrect move is as a result of the line 

    tpSetPos(&emcmotDebug->coord_tp, &emcmotStatus->carte_pos_cmd);

The small deltaX is somehow resulting in the trajectory planner generating the incorrect move we are seeing. I proved this by using the following code, which ensures that the value of emcmotStatus->carte_pos_cmd.tran.x passed to function tpSetPos does not result in tpSetPos seeing a small delta X:

      savedPosX =  emcmotStatus->carte_pos_cmd.tran.x;      
      kinematicsForward(joint_posKinsSwitch,  &emcmotStatus->carte_pos_cmd,   &tmpFFlags, &tmpIFlags);
      emcmotStatus->carte_pos_cmd.tran.x = savePosX ;                                             
      tpSetPos(&emcmotDebug->coord_tp, &emcmotStatus->carte_pos_cmd);

In this case, the move is generated correctly.

It has been reported previously that if in the first move after G12.1, X is not defined 
G12.1
G01 C20  F800 
the move is correctly generated. 

I can only assume that in this case, although the same small deltaX value exists, it is not used by the trajectory planner as X was not specified - but I have still to confirm this in the code.

I am hoping that this information will help those more closely acquainted with the source code to be able to hone in on the
problem and how best to address it. Perhaps one needs to relook at the calls in handle_kinematicsSwitch as these seem to be the root
cause of the problem.

I also think that one may be able to get the problem happening in the simulation by forcing the value returned by kinematicsForward to be a small delta from the joint position (as in the real world....). This is assuming that in the simulation, the joint actual positions are probably just set to the joint commanded positions, which would explain why until now the problem has not been reproduced in the simulation
Last edit: 07 Nov 2021 16:58 by NoJo. Reason: Incorrect terminology used

Please Log in or Create an account to join the conversation.

More
07 Nov 2021 17:43 - 08 Nov 2021 02:47 #225567 by dgarrett
You are correct, i've been working on the problem after
finally reproducing with real hardware this weekend
(my sim configs were too ideal) and posted a branch
with two commits:

branch: dgarr/stest3

If you and Aciera can test and veriy using a buildbot
deb, will merge to the master branch.  (the buildbot
is currently backlogged for a few hours)

749edfb04  is a fix (i think, not sure if there are
           unintended consequences)
80eb27741  is some additional cleanups

github.com/LinuxCNC/linuxcnc/commit/749edfb04
github.com/LinuxCNC/linuxcnc/commit/80eb27741
Last edit: 08 Nov 2021 02:47 by dgarrett.
The following user(s) said Thank You: tommylight

Please Log in or Create an account to join the conversation.

More
08 Nov 2021 11:19 #225662 by NoJo
Good news - I can confirm that with the updated file control.c the problem is resolved! Many thanks for your efforts.

If I may... as you will be updating the build I would suggest that the functions getStraightAcceleration and getStraightVelocity in emccanon.cc also be changed such that the comparisons use as EPSILOB_ZERO value (similar to TP_POS_EPSILON in tp.c) rather than expect a delta value of zero in the lines such as 
        if (dx <= 0.0 && dy <= 0.0 && dz <= 0.0 &&
        du <= 0.0 && dv <= 0.0 && dw <= 0.0) {
and 
        if (da <= 0.0 && db <= 0.0 && dc <= 0.0) {

I have two further questions I hope are a lot less complex than the previous one:
(1) I am needing to access the value G54_X (as stored in variable 5221) from my component. Can you advise / suggest how I can access it?
(2) I am needing to command the C Axis to do the homing function from my component. How can I generate that request? 
The following user(s) said Thank You: tommylight

Please Log in or Create an account to join the conversation.

More
08 Nov 2021 21:56 - 09 Nov 2021 01:46 #225724 by dgarrett
> ... I would suggest that the functions
> getStraightAcceleration and getStraightVelocity in
> emccanon.cc also be changed ...

Ref:
github.com/LinuxCNC/linuxcnc/blame/maste...ask/emccanon.cc#L643
github.com/LinuxCNC/linuxcnc/blame/maste...ask/emccanon.cc#L772

code not touched in at least 14+ years

Note that if an epsilon test had been incorporated in the
emccanon functions, the principal or "root cause" mistake in
handle_kinematicsSwitch() would be masked and lurk until exposed
in some future use case.


You could certainly make a pull request (especially if you
can provide evidence of a problem) and some developer with
in-depth knowledge of emccanon.cc may incorporate it.

Ref:
linuxcnc.org/docs/master/html/code/contr...ing-to-linuxcnc.html

> I have two further questions I hope are a lot less complex
> than the previous one:

Probably better to start new forum topics for questions not
closely related to existing topic.
Last edit: 09 Nov 2021 01:46 by dgarrett.
The following user(s) said Thank You: tommylight

Please Log in or Create an account to join the conversation.

Time to create page: 0.172 seconds
Powered by Kunena Forum