Joint following error in spite of large FERROR / MIN_FERROR values

More
24 Mar 2023 21:13 #267426 by dsz123
Howdy folks -

I'm setting up a new robot and running up against a bit of a configuration challenge (for me, anyway!). Still relatively new to LinuxCNC, but I have done a decent amount of reading and tried a few things already. The situation and a few questions follow...

I have a PUMA arm (I'm using the pumakins kinematics module). I've got a Mesa 7i80HDT and I'm using several 7i40-LV driver cards to connect to the DC servo motors. Encoders are all hooked up, and seem to be configured and working just fine. By that, I mean I can start LinuxCNC and see the various joints move in the UI, and am using the visualization provided in the vismach sample and can see the robot on screen do what I'm doing to the real robot. Cool.

This hardware robot has no limit switches, but it does have a "home position" - a cradle where I can move the arm to a known position. I have that position loaded in my configuration, and when I "HOME" the axes, the positions of the joints are set appropriately. Again, cool.

I'm now trying to move on to the servo tuning portion of configuration, but I am getting a ton of "Joint N following error" messages (where N varies depending on the situation). I have tried to set the parameters I know about in my INI to widen the window during tuning, but so far, nothing doing. Attached is a plot from halprobe with the results of trying to jog joint #3. As far as I can see, the plotted-in-red value of ferror doesn't actually exceed the FERROR or MIN_FERROR values (both set to 10.0), but I get a joint following error anyway. How come? There is a printed error in the command prompt window that might give a little more insight?
emc/task/taskintf.cc 942: Error on joint 3, command number 143

(the command number isn't always the same but I can't find a list of command numbers anywhere)

What are the units for FERROR and MIN_FERROR? My joints are set to ANGULAR and the [TRAJ]ANGULAR_UNITS is deg. If the error parameters are in the units of the joint, they're degrees, but even tiny movements of the joint trigger the joint following errors - way smaller than the 10.0 degrees they should be.
Also, what units are pos-fb and pos-cmd in? Again, I'm assuming degrees, but I can't find any connection between the jog numbers shown in AXIS (0.100, 0.010, 0.001, etc) and the numbers shown in the halprobe plot.

Thanks in advance for any tips or advice!

Best,
-Dave



 
Attachments:

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

More
24 Mar 2023 22:45 #267429 by dsz123
Some experimentation has led me to think this is a HAL problem, not an INI / FERROR problem. Of course if a moderator wants / is able to move this over to the HAL section, please make it happen and thank you.

I'm a little unclear on how to (virtually) connect the encoder (for me, hm2_7i80.0.encoder.XX) signals, the HAL pid thread (pid.XX) signals, and the LinuxCNC joint (joint.X) signals.

When I jog the axis/joint via the UI, it changes the joint.X.motor-pos-cmd value, right? So that clearly should connect to pid.X.command.

And that PID needs feedback, which ought to come from the encoder. Hence, pid.X.feedback should connect to hm2_7i80.0.encoder.XX.position

Finally, that PID generates output, which needs to go somewhere, so we connect pid.X.output to hm2_7i80.0.pwmgen.XX.value.

What's a little unclear is what to do about joint.X.motor-pos-fb signal. In the HAL file posted above, that was also connected to the encoder position (hm2_7i80.0.encoder.XX.position), which seems right. But somehow it was generating following errors even with minimal deviation.

Any insights? I'm assuming I missed something in there, but I can't quite tell what.

Thanks again,
-Dave
 

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

More
25 Mar 2023 17:20 #267479 by phasefreq
Some more context for folks- I shared my puma260 config with Dave; I have not played with it since I got stuck on this exact issue. I extended the puma560 example config to tie our puma260 encoders and motor pwms in while leaving as much as possible the same.

Pasting my reply to Dave's email here in case anyone knows what we're seeing:


This is the one thing I never got to the bottom of! What's wacky is that this does *not* occur when using the DH parameters from the puma 560 example! The only real difference aside from magnitudes of 560 vs 260 is that one negative sign- my guess is that some discontinuity in the pumakins is returning a large jump that exceeds one of the error thresholds. There is some relation too with max joint speeds in the INI- the puma560 example jogs "normal" speed in both joint mode and world mode; with the puma 260 DH params, I have to set the joint velocity and acceleration limits MUCH higher in order to jog even slowly in world mode.

The stopping point for finding and fixing the pumakins problem was figuring out how to debug it without starting up the whole thing, the gui, the hardware etc - if there is an easy way we can pull out and script just the pumakins stuff to compare the 560 params behavior vs the 260, I think there's a high likelyhood we will find the issue.


If anyone can suggest a path forward for Dave and I, we'd be greatly appreciative! I don't know the internals well enough to know where to dig.

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

More
26 Apr 2023 23:47 #270019 by dsz123
Hi again folks - reviving this thread because: a) I've made some amount of progress on this, and b) I'm still getting an unexpected error.

To summarize (latest HAL & INI files attached, btw):

I have a PUMA arm with brushed DC servos, and am using pumakins. When I start up the AXIS GUI, I can jog joints around with no problem - the PID/FF parameters aren't perfect, but seem good enough for the moment. I've gotten beyond the "joint following" errors that occur when I'm actually jogging motors. I can use the + and - buttons on each joint to make my robot arm move around. As previously mentioned, there are no limit switches in the hardware, but there is a cradle that puts the joints into a known state. The joint angles for that cradle/home position are what I've used for my "HOME" and "HOME_OFFSET" values for each joint in my INI file.

However, when I click on the "Home All" button, I immediately get a joint following error on J5 (in the terminal where I started LinuxCNC, it prints "joint 5 following error" and then "emc/task/taskintf.cc 942: Error on joint 5, command number NNN" where NNN changes). And when I use halscope to watch the relevant joint 5 parameters, I do actually see a big spike in the motor command position, followed by a lagging spike in the f-error value. Screenshot of halscope trace is attached. And for what it's worth, I don't feel any sort of jerk in the actual hardware, as evidenced by the fact that the position feedback doesn't really move.

Any idea why I'm seeing that spike in the first place? I wouldn't have imagined there would be a change in the commanded position when I click "Home all" - it would just adjust the position internally, since I don't actually want the robot to move, just update the values of the angles. Plus, the value of the peak of the spike seems to be suspiciously close to 360 degrees, rather than having anything to do with the HOME/HOME_OFFSET value.

Thanks much for any guidance you can provide.

-Dave



 
Attachments:

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

More
27 Apr 2023 18:42 #270075 by dsz123
I just tried loading in the same HOME and HOME_OFFSET values I use (the angles of each joint when the physical robot is resting in its cradle/home position) into the stock simulated PUMA configuration. I confirmed that the same jump in commanded position happens for J5 - it jumps by 360 degrees when I click the "Home All" button.

But of course, since this is simulated and the HAL file just directly connects the feedback to the commanded position, there's no following error raised.

So it does seem like something in the kinematics code cause this sudden jump. How come? Shouldn't it "listen" to my HOME and HOME_OFFSET values? What should I do about?

Thanks,
-Dave

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

Time to create page: 0.097 seconds
Powered by Kunena Forum