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

Rotation error in Gazebo simulation

asked 2011-04-04 21:43:52 -0600

mbj gravatar image

updated 2011-04-04 22:00:55 -0600

Hi everywhere. I wrote the following robot model in URDF and then I built a controller to teleoperate with it.

The result, as you can see in the video is not the expected, since they rotate on itself doing strange things (which seems more difficult when the spin is somehow aligned with the axis of coordinates of the world). Any ideas? I tried to change values ​​Mu1, Mu2, Kp, Kd and others like selfCollide with no success. I compared with models such as the Erratic and PR2 and finds no difference to me.

Here is the video that I recorded with the problem.

Thanks!

P.S: I want to add that the result is the same in teleoperation and in applying joint efforts directly to the wheels. With this I want to say that there is not a problem of the controller.

edit retag flag offensive close merge delete

6 Answers

Sort by » oldest newest most voted
5

answered 2011-04-07 07:59:09 -0600

hsu gravatar image

Thanks for the videos, I think I understand the issue better now. (It would still be great if you can insert your URDF in the message directly as quoted text in your posting?)

The speed up and slow down you see is an artifact of the fact that the friction forces between the wheels and the ground is dominating the dynamics and also because ODE is solving friction forces using a friction pyramid rather than a friction cone. If you look more closely at each contact point between a wheel and the ground, initially the base resists rotation because the friction force in the direction perpendicular to the wheel alignment has a longer moment arm about the CG of your system then the friction force aligned with the wheel's rolling direction. Because of numerical errors and drift, the base is eventually perturbed from its axis aligned orientation, and once the perturbation is large enough, the artifact of friction pyramid takes over and starts rotating the base until you hit another axis alignment 90 degrees later.

Without digging further into the equations of motion, have you tried using a lower friction coefficient <mu> and see if the effect you described can be reduced?

The fix is by setting the friction pyramid axis in alignment with the wheel frame by setting dContactFdir1 for wheel contacts (see ODE manual for description). Gazebo does not have that API right now, but should be able to added it easily.

edit flag offensive delete link more

Comments

Thank you very much for your response hsu! Actually, I have tried almost all combinations of mu1 and mu2 possibles both kp and kd, however the most convincing result I have found is the exposed. If I haven't misunderstood you, dContactFDir1 defines the direction of friction mu1. This isn't implemented in the Gazebo API, but he uses it internally for some calculations like this. According to your explain, it isn't difficult to add this parameter to the API. I think that this isn't the right way, but I searched through the simulator files and I have found references in the files physics_xml_tags and ODEPhysics. It would have to add or modify some parameter/function here?
mbj gravatar image mbj  ( 2011-04-07 22:31:11 -0600 )edit
hsu gravatar image hsu  ( 2011-04-08 06:12:41 -0600 )edit
hsu gravatar image hsu  ( 2011-04-08 06:13:32 -0600 )edit
Hi John. Thank you again for answering me, all this is helping me a lot to understand the ROS working. Unfortunately, since you answered me, I've been trying to apply the changes you propose to me without success. I didn't want to ask you this but I'm already 3 days without any progress. Firstly, I installed a version from the ROS source to compile (http://www.ros.org/wiki/diamondback/Installation/Ubuntu/Source), I made the appropriate changes to simulator_gazebo and I compiled everything successfully (with rosmake). Unfortunately, testing with my model I have not found any significant change. Later, I tried to introduce errors intentionally in the code and compile the simulator (also with rosmake) to see if I'm compiling correctly. As I imagined, it gives no errors. What should I do to successfully compile the code and test the changes?
mbj gravatar image mbj  ( 2011-04-12 10:03:32 -0600 )edit
1

answered 2011-04-22 12:56:45 -0600

hsu gravatar image

updated 2011-04-22 12:58:06 -0600

here's a smooth sliding sim after all the fixes, running from trunk of simulator_gazebo and setting fdir1, mu1 and mu2 for the wheel geoms.

edit flag offensive delete link more

Comments

Can you please post which values did you use for fdir1, mu1 and mu2. Thanks a lot

Mario Garzon gravatar image Mario Garzon  ( 2012-10-16 03:20:11 -0600 )edit

Yes, would be nice to know values! Thanks :)

ZdenekM gravatar image ZdenekM  ( 2013-06-25 22:21:52 -0600 )edit
0

answered 2011-04-12 10:10:30 -0600

hsu gravatar image

updated 2011-04-12 10:11:47 -0600

To try the changes, you'll have to check out from trunk, look for the simulator_gazebo line in your ~/ros/.rosinstall file, modify it to point to trunk:

- svn: {local-name: stacks/simulator_gazebo, uri: 'https://code.ros.org/svn/ros-pkg/stacks/simulator_gazebo/trunk'}

then rebuild,

cd ~/ros
rosinstall .
roscd gazebo
make clean
rosmake gazebo

Make clean should force a recompile.

edit flag offensive delete link more
0

answered 2011-04-05 05:13:53 -0600

hsu gravatar image

Hi Mbj,

Please explain what was happening in the video, what control torques were applied and behaviors were expected. Also, it helps if you can post a link to your world file and urdf model.

Thanks,

John

edit flag offensive delete link more
0

answered 2011-04-05 06:51:44 -0600

mbj gravatar image

Hi John, first thanks for answering.

From 0:16 second of the video, the robot starts to rotate on itself. I do this by applying forces to the joints of the wheels, for example, positive to the right side (both rear and front wheel) and negative to the left side. The problem is, as you can see, the movement is not continuous, it slows down as they aligned with the axis of coordinates of the world (or so it seems).

The expected behavior was to rotate on itself without those little slow down. The physical model of the R2D2 URDF tutorials behaves correctly by applying the same efforts to the wheels.

I would like to point out that there isn't a controller problem. I get the same result with teleoperating with the robot and using pairs of forces with a script that launches the rosservice apply_joint_effort as I indicated.

Now I can't upload the code, but I do it tomorrow.

edit flag offensive delete link more
0

answered 2011-04-06 22:28:02 -0600

mbj gravatar image

Hello again, I can't upload the code but I've done some tests with R2D2 robot skid base of the tutorials and the result is the following.

http://www.youtube.com/watch?v=idhdCtDTlgs

As you can see, the elongated base with thin wheels robot behaves like in my case. In the second case (from the second 20), the robot rotates as expected and want for my robot. The efforts in both cases were the same.

I assumed it would be a problem in my previous robot code, but seeing this makes me wonder. Obviously, the real robot don't perform these decreases in speed when it rotates on itself. This is a bug in the simulator? I configured some parameter wrong?

Thanks for reading, any help is welcome.

edit flag offensive delete link more

Comments

Please use comments or edit your postings instead of answering your own question with more questions. Answers are not always displayed in chronological order.
tfoote gravatar image tfoote  ( 2011-04-07 08:11:16 -0600 )edit

Question Tools

Stats

Asked: 2011-04-04 21:43:52 -0600

Seen: 8,631 times

Last updated: Apr 22 '11