ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
3

Manipulator Shakes/Wobbles

asked 2014-04-24 13:33:57 -0500

b3l33 gravatar image

I am using a Universal Robots UR5 mounted to a cylindrical post using fixed joints (one to world, the other to the UR5).

When I drive it in Gazebo using Moveit! the model shakes/wobbles. It eventually settles down....

I am wondering if there is something that I'm doing wrong to induce this? Or if there are things I need to adjust to eliminate this?

edit retag flag offensive close merge delete

Comments

Has the cylindrical post a mass?

BennyRe gravatar image BennyRe  ( 2014-04-24 22:56:34 -0500 )edit

Yes. It has a mass of 50. I have since discovered that the manipulator exhibits the same behaviour if fixed directly to the ground as well. Please see the following youtube video for reference: http://youtu.be/RVYIK4C_mgk Any suggestions on what I may do to stabilize the robot's behaviour? Thank you!

b3l33 gravatar image b3l33  ( 2014-04-25 07:38:08 -0500 )edit

3 Answers

Sort by » oldest newest most voted
4

answered 2014-04-27 12:36:45 -0500

jalfonso gravatar image

Hi b3l33 The gains of the controller and the inertia of the model have default values. This cause the the arm has a lot of inertia and the controller is very slow and underdamped. The origin of the oscilations is the gravity, acting as a perturbation on the system. Other efect is a very large position error. When the arm stops, the hand is very down the goal state. You can see it in rviz.

I want to develope a best modell next week, but now you can use the following;

(This values are tested for hydro-dev branch of ros-industrial/universal_robot package.) In order to improve the behaviour, you should increase the gain of the controller, reduce the inertia of the links and increase the damping in the joins. You can change all p gain from 1.000 to 10.000 in the file,

ur_gazebo/controller/arm_controller_ur5.yam

shoulder_pan_joint: {p: 10000.0, i: 0.0, d: 0.0, i_clamp: 0.0, i_clamp_min: 0.0, i_clamp_max: 0.0}
shoulder_lift_joint: {p: 10000.0, i: 0.0, d: 0.0, i_clamp: 0.0, i_clamp_min: 0.0, i_clamp_max: 0.0}
elbow_joint: {p: 10000.0, i: 0.0, d: 0.0, i_clamp: 0.0, i_clamp_min: 0.0, i_clamp_max: 0.0}

Reduce inertia in all links to inertia to ixx="0.002" ixy="0.0" ixz="0.0" iyy="0.02" iyz="0.0" izz="0.002" in files

ur_description/ur5_joint_limited.urdf.xacro and ur_description/ur5_joint_limited.urdf.xacro

  <inertia ixx="0.002" ixy="0.0" ixz="0.0" iyy="0.02" iyz="0.0" izz="0.002"/>

And increase the damping in all joints to 0.5 in files

ur_description/ur5_joint_limited.urdf.xacro and ur_description/ur5_joint_limited.urdf.xacro

  <dynamics damping="0.5" friction="0.0"/>
edit flag offensive delete link more

Comments

Awesome - thank you! I will try these suggestions out. Am I correct in inferring that you will eventually add your changes into the ros-industrial package?

b3l33 gravatar image b3l33  ( 2014-04-29 04:40:34 -0500 )edit

Yes, I will propose add the changes to UR5 package maintainers. Meanwhile, you can use the above values​​.

jalfonso gravatar image jalfonso  ( 2014-04-29 05:10:12 -0500 )edit

Update: I tried the suggested settings. The wobbling appears to be much improved but still looks like it is vibrating. Execution is much faster and smoother. Wobbling is less violent - much better damped. This will prove to be much more usable! Thank you - this was helpful and informative.

b3l33 gravatar image b3l33  ( 2014-04-29 05:25:01 -0500 )edit

Another problem, is the arm apears in rviz in strange positions. Maybe is caused because you use demo.launch and a gazebo launch. First launch fake_controller . In order to avoid this situation, your launch file should include <arg name="fake_execution" value="false">

jalfonso gravatar image jalfonso  ( 2014-04-29 09:20:13 -0500 )edit

Thanks. I'm a little confused about what you mean by "First launch fake_controller". I am doing the following: (1) launching gazebo (2) launching rviz using a version of demo.launch with fake_execution = false.

b3l33 gravatar image b3l33  ( 2014-04-29 10:23:46 -0500 )edit

New update! I just realized you suggested setting iyy="0.02". I had been using 0.002 by mistake. When I corrected this the robot movement movement is VERY SMOOTH AND STABLE. THANK YOU!

b3l33 gravatar image b3l33  ( 2014-04-29 10:28:22 -0500 )edit

Check /joint_states topic is only published by gazebo using: rostopic info /joint_states If there are two publishers, and you use demo.launch, then comment or remove <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher"> <rosparam param="/source_list">[/move_group/fake_controller_joint_states]</rosparam> </node> Enjoy a rviz graphics without weird positions of arm.

jalfonso gravatar image jalfonso  ( 2014-04-29 12:12:12 -0500 )edit

Again THANK YOU! I get it now... Yes - this fixed the issue of "ghost state" :) I owe you one... or two. Here's a clip of the corrected/improved configuration: http://youtu.be/k5rzlfS1RvA

b3l33 gravatar image b3l33  ( 2014-04-29 12:54:25 -0500 )edit
0

answered 2014-07-25 10:28:31 -0500

arennuit gravatar image

Hi @jalfonso and @b3l33,

My UR5 is also wobbling despite the updated gains and parameters. I am using hydro under precise (12.04LTS).

I have cloned repo universal_robot from ROS-I and am on branch hydro-devel (current head: f39b2e75 and I also tested 8a15a0bc dating back to 23/05, which is the commit of hydro-devel at the time you wrote the previous messages).

I have modified the following files according to the previous message (with a sed):

  • arm_controller_ur5.yaml
  • ur5.urdf.xacro
  • ur5_joint_limited.urdf.xacro

As my setup does not work (actually it is a bit better with the updated gains but really bad compared to the results of b3l33 shown in his videos), I have a few questions:

  • the joint damping values are updated from 0.3/0.4 to 0.5, this is not a big modification, is this normal?
  • the previous message says all p gains should be updated, but only 3 out of the 6 are shown. Should we only update the 3 shown or all the 6? (I have tested both and it does not seem to change much)
  • the previous message says to change 2 files, but the 2 files indicated are the same (ur5_joint_limited.urdf.xacro). I thought you meant ur5_joint_limited.urdf.xacro and ur5.urdf.xacro, was my guess right?

Any idea of what else I could check to make things work as good as in b3l33's videos?

Also would you be kind enough to diff my .yaml and .urdf files here against yours? Just to make sure my edits are right... I have also joined my setup files (how I fix the base link to the world) just in case...

Thanks,

Antoine.

edit flag offensive delete link more
0

answered 2014-07-26 10:28:59 -0500

jalfonso gravatar image

Till end of weekend I will not have acces to my PC. I will chech your repo on monday. ;) jalfonso100

edit flag offensive delete link more

Comments

Thanks jalfonso100 :)

arennuit gravatar image arennuit  ( 2014-07-27 13:12:55 -0500 )edit

In ur_gazebo/controller/arm_controller_ur5.yam, Change parameters of all controllers to p: 10000.0, i: 50.0, d: 500.0, i_clamp: 0.0, i_clamp_min: -100.0, i_clamp_max: 100.0

jalfonso gravatar image jalfonso  ( 2014-07-28 19:40:10 -0500 )edit

I cant explain more because I only can write Solution and a few words in Comments. And I dont want modify the original answer. :(

jalfonso gravatar image jalfonso  ( 2014-07-28 19:46:04 -0500 )edit

Hola Alfonso, this is a good start. Unfortunately I am away from my machine and for some reason I do not manage to connect to it. I will try again later but I may have to wait until the week end when I come back in order to test. I can already thank you, I'll give more details at the week end :)

arennuit gravatar image arennuit  ( 2014-07-29 17:43:40 -0500 )edit

Hi Alfonso, I was able to test your updated parameter values. These work much better indeed, thanks a lot! I have refined the values using dynamic reconfigure (in rqt_gui). Do you have an idea why the values you initially gave to @b3l33 no longer work?

arennuit gravatar image arennuit  ( 2014-08-05 04:07:32 -0500 )edit

I have made a pull request with the new param values for the UR5 (dynamic params and PID gains) in https://github.com/ros-industrial/universal_robot/pull/85. To find the params, did you just play with the values or did you use identified inertias/damping and a know computation method for PID gains?

arennuit gravatar image arennuit  ( 2014-08-05 04:09:17 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2014-04-24 13:33:57 -0500

Seen: 4,855 times

Last updated: Jul 26 '14