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

Mobile arm simulation behaves strangely when adding ros_control plugin for arm

asked 2018-03-02 11:32:39 -0600

raequin gravatar image

updated 2018-03-21 07:59:58 -0600

Greetings. My model combining a simple mobile base with the UR10 acts strangely when I add

<plugin name="ros_control" filename="libgazebo_ros_control.so"/>

which is needed for controlling the UR10 joints. The strange behavior is that the mobile robot resists motion (or maybe it's just the mobile base that does this). Two examples:

(1) If I publish a large velocity twist to the cmd_vel topic for the differential_drive_controller on the mobile base the two wheels spin quickly but the robot rotates only very slowly.

(2) If I publish a positive z-position to set_model_state, effectively dropping the robot from this height, it falls very slowly to the ground.

The "real time factor" is 1.00 so it's not as if the simulation is running slowly when the plugin is added. When I don't add the plugin the robot arm is floppy but it moves quickly, as one would expect (the base moves it around at the desired rate and it falls as fast as normal). The differential_drive_controller seems to be working fine and so does the arm_controller it's just that when I'm using the arm_controller the sim acts crazy. If I remove the diff-drive controller but keep arm_controller the weird behavior remains.

I will look through the husky simulator with UR5 enabled to try to find what is wrong with my robot.

When publishing an arm pose to arm_controller/command the manipulator moves at a reasonable speed relative to its base but the overall mobile robot is still very slow. For example, if I drop it from two meters and publish a manipulator pose the arm moves fine but the entire robot falls very slowly.

For reference, here is the source (except for ur10.urdf.xacro). The offending gazebo plugin tag is found in models/common.gazebo.xacro.

One other note: this question is also posted to answers.gazebosim.org . Is it frowned-upon behavior to post at both these sites?

*edit: First off, thanks for the information in the accepted answer. My inital attempt to resolve this was to replace PositionJointInterface in ur.transmission.xacro with VelocityJointInterface. This required changing

type: position_controllers/JointTrajectoryController

in arm_controller_ur10.yaml to

type: velocity_controllers/JointTrajectoryController

however, when I launch my simulation the following appears.

[ERROR] [1520431422.716199942, 0.480000000]: No p gain specified for pid.  Namespace: /arm_controller/gains/shoulder_pan_joint

Since I don't know how to specify gains for that controller, I tried another option you describe. For my second attempt, I reverted to the original configuration (PositionJointInterface with position_cotrollers) and added this line to my launch file.

  <rosparam file="$(find mobile_arm)/models/my_ur10/pid_for_gazebo_ros_control.yaml" command="load"/>

where pid_for_gazebo_ros_control.yaml contains just the following.

gazebo_ros_control:
  pid_gains:
    shoulder_pan_joint: {p: 100.0, i: 0.01, d: 10.0}
    shoulder_lift_joint: {p: 100.0, i: 0.01, d: 10.0}
    elbow_joint: {p: 100.0, i: 0.01, d: 10.0}
    wrist_1_joint: {p: 100.0, i: 0.01, d: 10.0}
    wrist_2_joint: {p: 100.0, i: 0.01, d: 10.0}
    wrist_3_joint: {p: 100.0, i ...
(more)
edit retag flag offensive close merge delete

Comments

Re edit1: You can see how to specify gains for the velocity controller here: https://github.com/ThomasTimm/ur_mode... . Note however that these values are for the real UR5. For my Gazebo UR5, I use {p: 100.0, i: 0.0, d: 0.1} .

Martin Günther gravatar image Martin Günther  ( 2018-03-08 06:02:55 -0600 )edit

The UR10 is heavier, so you probably have to increase the p value.

Martin Günther gravatar image Martin Günther  ( 2018-03-08 06:04:59 -0600 )edit
1

Re edit4: I don't think that's how it works. Gazebo9 added the option of specifying that flag in a function call, but the source code of the ros_control gazebo plugin has to be changed to actually call that function with the flag. Until then, installing gazebo9 solves nothing.

Martin Günther gravatar image Martin Günther  ( 2018-03-08 06:07:11 -0600 )edit

@raequin are you saying that the problem is not solved? You have accepted an answer already so if this is a new problem (even if related) please create a new question and reference this one.

jayess gravatar image jayess  ( 2018-03-20 16:53:15 -0600 )edit

@jayess excuse me if I have muddied the waters. The accepted answer pinpoints the cause of the problem and offers a couple of solutions. The latest edit I made to this question gives details of how, starting with the accepted answer, the problem was resolved in my case.

raequin gravatar image raequin  ( 2018-03-20 17:03:39 -0600 )edit

No problem, but the body of a question isn't the appropriate place for a solution to a problem (i.e., an answer). Can you please put your solution as an answer instead?

jayess gravatar image jayess  ( 2018-03-20 17:05:52 -0600 )edit

I've updated my answer, no need to add another answer.

Martin Günther gravatar image Martin Günther  ( 2018-03-21 07:10:55 -0600 )edit

Great! Thank you both.

raequin gravatar image raequin  ( 2018-03-21 08:00:17 -0600 )edit

1 Answer

Sort by » oldest newest most voted
5

answered 2018-03-05 03:28:49 -0600

updated 2018-03-21 07:09:58 -0600

It's this really annoying regression in Gazebo: https://github.com/ros-simulation/gaz... . Basically everyone using ros_control (and many other plugins) + Gazebo is affected by this, and it looks like it won't get fixed in ROS Kinetic / Gazebo 7. :(

For workarounds, see the issue I've linked to.

The problem is that there is a regression in the Joint::SetPosition() method in Gazebo. Previously, it only did just that (it set the joint angle). Later, the implementation of that method was changed so that it also reset the link velocity of the link connected to the joint to zero - this is why your robot is falling so slowly: Gravity pulls the robot down, but the joint controller always involuntarily stops that falling motion when it sets the joint angle. Since the gravity force now doesn't work properly, the mobile base loses proper contact to the ground (you can see that when you visualize contacts in the Gazebo GUI); this is why the base doesn't properly respond any more.

If you do any of the workarounds in the issue (adding pid_gains, using the VelocityJointInterface or EffortJointInterface instead of the PositionJointInterface), the ros_control Gazebo plugin won't call the Joint::SetPosition() method any more, thereby avoiding the problem.

Please note that you also have to do the workaround for any other Gazebo plugin that might call the Joint::SetPosition() method, such as the mimic joint plugin.

Edit 2018-03-21: Now there is a third option to avoid this bug (the first two being (1) adding pid_gains and (2) using the VelocityJointInterface or EffortJointInterface). Option (3) is to install Gazebo 9 (from deb packages, or from source) and the newest version of gazebo_ros_pkgs (from source until 2.5.15 is released). This bugfix has been added in PR 688, but only for Gazebo 9.

edit flag offensive delete link more

Comments

This seems like a clear case of a regression. Are there issues reported against Gazebo proper for this @Martin Günther? Or is it all in gazebo_ros_pkgs?

gvdhoorn gravatar image gvdhoorn  ( 2018-03-05 03:33:00 -0600 )edit
1

Yes, this is the relevant Gazebo issue: https://bitbucket.org/osrf/gazebo/iss... . It's linked from ros-simulation/gazebo_ros_pkgs#612 . I prefer pointing people to #612 instead of the actual Gazebo issue, since #612 has the workarounds.

Martin Günther gravatar image Martin Günther  ( 2018-03-05 04:07:22 -0600 )edit

Thank you very much. My work on resolving this has not thus far succeeded and the description seemed too long for a comment so I edited the question. Since I'm new to this site I did not know whether or not you'd be notified of that change. Hence this comment.

raequin gravatar image raequin  ( 2018-03-07 09:10:30 -0600 )edit

The third option is the one that I went with. It's a simple fix.

raequin gravatar image raequin  ( 2018-03-21 08:01:34 -0600 )edit

When moving this project to a different computer the system gives errors like

Could not load controller 'arm_controller' because controller type 'position_controllers/JointTrajectoryController' does not exist.

Is there something I need to do to have ROS use the latest gazebo_ros_kpgs?

raequin gravatar image raequin  ( 2018-04-24 13:13:32 -0600 )edit

Question Tools

3 followers

Stats

Asked: 2018-03-02 11:32:39 -0600

Seen: 2,326 times

Last updated: Mar 21 '18