CentroEPiaggio / kuka-lwr

Software related to the KUKA LWR 4+: for real and for simulation.
The Unlicense
101 stars 81 forks source link

FRI Interpolation Error #95

Open nicocadart opened 7 years ago

nicocadart commented 7 years ago

Hey,

First of all, thank you for your work on this nice interface. I recently discovered it.

However, when starting the command mode, I always get the "FRI interpolation error", which enables the brakes and then returns back to monitor mode. I tried to move the joints 1 (a1) and 3 (e1) to a bent position (~90 deg), but it doesn't change anything. I've found this error in KUKA documentation, describing a possible cause :

"The setpoint command from the external computer does not match with the system status [...]"

A suggested remedy is to check if when the drives are switched off, we always have : cmd.data.cmdJntPos = msr.data.cmdJntPos + msr.data.cmdJntPosFriOffset However this seems to be already checked in the friRemote.cpp.

Do you know how to fix it? Thanks for your help

marcoesposito1988 commented 7 years ago

Hi @nicocadart,

you mean joints a2 and a3, right? They are the only ones that can "bend" the robot; a1 and e1 are coaxial.

Do you have anything attached on the robot? I'm not totally sure, but that error could also pop up if you have a heavy tool which you didn't calibrate the robot for.

nicocadart commented 7 years ago

Hi @marcoesposito1988

By "bent" I meant that their angular position is greater than 45 degrees. However I tried with joints a2 and a3 and it doesn't change anything, the same error 'FRI Interpolation Error' occurs.

I don't have any tool yet on the robot, therefore the 'flange' tool is selected.

All controllers in any mode are doing the same error. After a few tries, the error occurs during the first loop in the lwr_hw_fri_node.cpp in the manager.update() function, when the controller is loaded.

graiola commented 7 years ago

Hi, I am facing the same problem, any news on that?

marcoesposito1988 commented 7 years ago

Are you trying to start the robot with any controller which is not joint_trajectory_controller? As far as I remember, that is not going to work. You have to start in position control, then change to impedance, otherwise you will get that error.

Yes, I feel your pain.

nicocadart commented 7 years ago

Yes the robot is started with the joint_trajectory_controller.

I may have achieved to solve the problem. It was happening when the startegy was switched (or when the first controller is loaded at the beginning), in the first loop iteration. The FRI sends then during one step of time a command with cmdFlag 0 (see setToKRLINT() in friremote.h), which isn't recognized as a known strategy by the KRC, resulting in the FRI Interpolation Error. To solve that, the FRI needs to be started after the strategy has been changed and the new controller loaded, or in other words cmdFlag != 0. I removed the call to startFRI() in doSwitch(), and added it at the end of the write(). I don't have the error anymore.

What do you think about this solution?

marcoesposito1988 commented 7 years ago

Very strange, that should not happen. Sounds like a bug, but I never encountered it.

Putting startFRI in write is conceptually wrong, since it's something you should do once and not every millisecond (or 10). But if that lets you use the robot, at least you have the time to solve the issue properly while you are able to work...

nicocadart commented 7 years ago

Yes I know this solution isn't ideal... However the startFRI isn't called every iteration. I added a bool needToStartFRI which is set to true only when doSwitch is called. Therefore, the call to startFRI in write() is done only if the controller has been switched just before.