Gazebo | Ignition | Community
Ask Your Question
1

Mobile arm simulation behaves strangely when adding ros_control plugin

asked 2018-03-02 10:12:50 -0600

raequin gravatar image

updated 2018-03-02 11:37:03 -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. It falls so slowly that I was easily able to select the area to grab for this screenshot. (The gap between the mobile base and the arm base is normal for the UR10. It's present even with the ur_gazebo ur10.launch simulation.)

image description

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 two controllers both seem to be working well. It's just that things overall get weird when I add the arm_controller. If I keep it and remove the differential_drive_controller the strange behavior is still present.

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.

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
4

answered 2018-03-05 03:32:30 -0600

updated 2018-03-05 04:01:10 -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 flag offensive delete link more
0

answered 2018-03-05 02:34:49 -0600

Raskkii gravatar image

My suspicion is that the arm_controller is at fault here. I had a similar problem with the robot falling extremely slowly when I used PositionControllers for the two front wheels. In this case the front side of my robot was falling down slowly while the back side was sort of dangling since it was falling much faster. It seems to me that these types of controllers are trying to maintain the joint's absolute position in the world, so when you attempt to move the base, there is a lot of resistance.

Now I'm not exactly sure how the arm_controller works since I could not find a source for it. But if possible you might be better off trying to use a force or velocity controller on your arm.

edit flag offensive delete link more

Comments

From the accepted answer it seems that the simulation resets the twist to zero for a link using the SetPosition() method, which is how the ros_control_plugin operates, I believe. Thanks for your input.

raequin gravatar imageraequin ( 2018-03-05 08:42:15 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2018-03-02 10:12:50 -0600

Seen: 4,633 times

Last updated: Mar 05 '18