ros-industrial / kuka_experimental

Experimental packages for KUKA manipulators within ROS-Industrial (http://wiki.ros.org/kuka_experimental)
Apache License 2.0
268 stars 213 forks source link

Implementing PID or High Level Controller #164

Closed jaytjoa closed 2 years ago

jaytjoa commented 4 years ago

Hi, I have started a project to control a KR180. I made already the stabile RSI connection and controlled the robot already with the rqt joint trajectory controller. Meanwhile, I am testing to do the motion planning with the robot with MoveIt. The robot is moving according to the trajectory but sometimes the connection is broken and with higher velocity, the robot does have much jerk. I believe that some PID controller should be implemented here.

Has anybody done it before??

gavanderhoorn commented 4 years ago

If the input trajectories are not jerk limited and you have no additional other filtering, you could certainly introduce a form of close loop control between the JTC and the robot controller.

There are a few mitigation strategies that RSI already supports though that would not require adding a controller. Configuring the policy that determines what should be done when packets are lost is one (ie: stop or repeat previous command).

But it's certainly true that jerk is an issue: the JTC is simply not jerk-limited. See #126 and #89 for instance for similar issues.

jaytjoa commented 4 years ago

I am trying to implement this closed loop controller now. I planned several movements with OMPL (RRTConnect) for some position for A1 only and it seems to be by some position the connection is broken. I controlled the robot with T2 mode from KUKA. this closed loop controller now.

A question is why do we only implement the position_controller for the whole system here? When I streamed the the action feedback topic of joint trajectory action. It showed me only the update in the actual position and the actual velocity is completely zero. Any explanation??

And according to #123 . I see that most of the robot models here in the repo do not have a limit effort. And I compared it with another URDF data from another robots. Any method to calculate the limit effort?

gavanderhoorn commented 4 years ago

I am trying to implement this closed loop controller now. I planned several movements with OMPL (RRTConnect) for some position for A1 only and it seems to be by some position the connection is broken. I controlled the robot with T2 mode from KUKA. this closed loop controller now.

It's likely that the trajectory coming out of MoveIt is not sufficiently smooth for the KR C4 controller to execute successfully. The JTC then has a problem smoothly interpolating it.

A question is why do we only implement the position_controller for the whole system here?

I don't understand your question.

When I streamed the the action feedback topic of joint trajectory action. It showed me only the update in the actual position and the actual velocity is completely zero. Any explanation??

RSI does not provide any velocity feedback afaik. Or at least, our configuration does.

And according to #123 . I see that most of the robot models here in the repo do not have a limit effort. And I compared it with another URDF data from another robots. Any method to calculate the limit effort?

Robot OEMs typically don't give you that information. It may be available on the controller in some file, but you'd have to search for it.

gavanderhoorn commented 4 years ago

I am trying to implement this closed loop controller now.

If you're mostly looking to execute trajectories without faulting on discontinuities, it may be easier to add a low-pass filter on the RSI side.

It would most likely reduce tracking performance, but it would help with protecting the robot from jerky paths coming from the PC.

destogl commented 4 years ago

Maybe the solution would be to use some trajectory generator, e.g Reflexxes library. For us this is working great...

jaytjoa commented 4 years ago

Maybe the solution would be to use some trajectory generator, e.g Reflexxes library. For us this is working great...

do you have any reference or literature about it???

I am trying to implement this closed loop controller now. I planned several movements with OMPL (RRTConnect) for some position for A1 only and it seems to be by some position the connection is broken. I controlled the robot with T2 mode from KUKA. this closed loop controller now.

It's likely that the trajectory coming out of MoveIt is not sufficiently smooth for the KR C4 controller to execute successfully. The JTC then has a problem smoothly interpolating it.

A question is why do we only implement the position_controller for the whole system here?

I don't understand your question.

When I streamed the the action feedback topic of joint trajectory action. It showed me only the update in the actual position and the actual velocity is completely zero. Any explanation??

RSI does not provide any velocity feedback afaik. Or at least, our configuration does.

And according to #123 . I see that most of the robot models here in the repo do not have a limit effort. And I compared it with another URDF data from another robots. Any method to calculate the limit effort?

Robot OEMs typically don't give you that information. It may be available on the controller in some file, but you'd have to search for it. Hi, thank you for great responses and feedback.

Okay, in these weeks I have tried to implement the online PID controller as also smoothing filter for the signals.

First I made plot the position of joint A1 from the topic /joint_states and /joint_trajectory_action/feedback. When we observed the spline of the position it is shifted in some positions. spline position Furthermore I applied derivation of these points to obtain velocity and acceleration. At these points, I get these horrible plots. velocity

So, I come to a point to implement the discrete PID controller by making an interpolation from the generated goal points from JTA-goal, publishing it as a new topic and then applying message filter with the JTA-feedback and implement PID controller here, after that send a new topic and bypass the KUKA RSI HW Interface. But somehow this approach did not work well. The message filter did not do the approximated sync. like it is used to be.

Another approach that I think would work is to implement online smoothing algorithm. I somehow tested it only to a recorded data. savgol Do you think that it would be possible to record for example each 5 position data and calculate 4 velocities and apply some filter there like the savitzky-golay and then convert it again to position and send it to the robot?

gavanderhoorn commented 4 years ago

It might be beneficial if you could first describe your execution environment and how you have setup things.

Depending on whether the clock from the robot is used to sample the trajectory, or whether you are using the clock local to the PC, there is quite a bit of jitter introduced in the sampling routines, which could easily lead to the jitter you see in your plots.

The current implementation of kuka_rsi_hw_interface doesn't request a real-time scheduling priority, leaving it to the user to configure it afterwards (with nice and similar tools).

Configuring the hw interface with a real-time priority would immediately lead to the controllers being executed in hard real-time as well, which will significantly improve motion performance. It will not solve the fact that the JTC is not jerk-limited, which is in my experience the biggest problem here.

Reflexxes, mentioned by @destogl is also not jerk-limited (or at least the open-source version isn't iirc), but it can generate quite smooth trajectories which may work around this.

Adding additional filtering and other measures only makes sense in my opinion after fixing the trajectory generation and execution side.

Okay, in these weeks I have tried to implement the online PID controller as also smoothing filter for the signals.

did you do this on the KR C4 side, or locally on your ROS PC?

destogl commented 4 years ago

@jaytjoa sorry not to answer this earlier...

For testing reflexxes you can use the version integrated in ROS in KITrobotics/ipr_extern. Here you can find an example controller for this. You can simply integrate it into your package. I can not unfortunately provide you with complete package, because we didn't openned it yet...

I hope this can help you to save your problem :)

jaytjoa commented 4 years ago

@jaytjoa sorry not to answer this earlier...

For testing reflexxes you can use the version integrated in ROS in KITrobotics/ipr_extern. Here you can find an example controller for this. You can simply integrate it into your package. I can not unfortunately provide you with complete package, because we didn't openned it yet...

I hope this can help you to save your problem :)

Sorry for not being a while here, I did do another things meanwhile. Firstly I would like to thank you. I will have a look on this package explicitly.

It might be beneficial if you could first describe your execution environment and how you have setup things.

Depending on whether the clock from the robot is used to sample the trajectory, or whether you are using the clock local to the PC, there is quite a bit of jitter introduced in the sampling routines, which could easily lead to the jitter you see in your plots.

The current implementation of kuka_rsi_hw_interface doesn't request a real-time scheduling priority, leaving it to the user to configure it afterwards (with nice and similar tools).

Configuring the hw interface with a real-time priority would immediately lead to the controllers being executed in hard real-time as well, which will significantly improve motion performance. It will not solve the fact that the JTC is not jerk-limited, which is in my experience the biggest problem here.

Reflexxes, mentioned by @destogl is also not jerk-limited (or at least the open-source version isn't iirc), but it can generate quite smooth trajectories which may work around this.

Adding additional filtering and other measures only makes sense in my opinion after fixing the trajectory generation and execution side.

Okay, in these weeks I have tried to implement the online PID controller as also smoothing filter for the signals.

did you do this on the KR C4 side, or locally on your ROS PC?

I implemented it in the ROS PC.

gavanderhoorn commented 4 years ago

That would probably explain the "horrible" plots you show. Without deterministic timing on that PC, it's very easy to run into issues with latency and especially jitter. For filtering and real-time control, those can have catastrophic influence.

Finally: my suggestion was to implement some filtering on the side of the KR C4. RSI supports this, and it should be much easier to make that deterministic (as the entire controller is).

marbosjo commented 3 years ago

@destogl the controller you provided in this link is not available, could you reupload it?

We are planning to use reflexxes in a research experiment, it would be nice to have that example.

gavanderhoorn commented 2 years ago

Closing due to inactivity.