Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Directional friction still broken. #2068

Closed
osrf-migration opened this issue Oct 11, 2016 · 36 comments
Closed

Directional friction still broken. #2068

osrf-migration opened this issue Oct 11, 2016 · 36 comments
Labels
bug Something isn't working major physics

Comments

@osrf-migration
Copy link

Original report (archived issue) by Mike Purvis (Bitbucket: mikepurvis).

The original report had attachments: fdir1.world


Per discussion on #463; in particular this comment:

https://osrf-migration.github.io/gazebo-gh-pages/#!/osrf/gazebo/issues/463/ode-fdir1-parameter-broken (#463)#comment-31218716

@osrf-migration
Copy link
Author

Original comment by Andrea Ruzzenenti (Bitbucket: aerydna).


I did some experiments and I found the origin of this issue.
The issue is not related with the variable 'fd2' mentioned in above comment (that is a different issue).
The computation is wrong because there's a bug in:

   if (fd != math::Vector3::Zero)
   {
     // fdir1 is in body local frame, rotate it into world frame
    fd = _collision1->GetWorldPose().rot.RotateVector(fd);
   }

The method GetWorldPose() does not return the transformation between the world and the collision reference frame. It returns the transformation between the origin of the model and the collision reference frame. So if the robot model is rotated respect to the world frame, fd is wrong. I tested this hypotesis by rotating the robot and observing that GetWorldPose() returns always the same value.

I thus fixed the code as follow:

   if (fd != math::Vector3::Zero)
   {
     // fdir1 is in body local frame, rotate it into world frame
    fd = _collision1->GetWorldPose().rot.RotateVector(fd);
    fd = _collision1->GetModel()->GetWorldPose().rot.RotateVector(fd);
   }

This hack fixes the calculation because the first line computes the transformation between the origin of the model and the collision reference frame frame while the second one returns the transformation between the world and the origin of the model.

Obviously this is just an hack that fixes the simulation.

The method _collision1->GetWorldPose() has to be fixed.

@osrf-migration
Copy link
Author

Original comment by Steve Peters (Bitbucket: Steven Peters, GitHub: scpeters).


  • set attachment to "fdir1.world"

Sorry for the delayed response. I'm surprised that the fdir1 parameter is not working. We have an integration test for it in physics_friction.cc that spawns several rings of boxes with the friction direction set along with different combinations of model, link, and collision rotation. One friction value is 100, and the other is zero. Then a lateral gravity component is applied, which cause the boxes to all slide along the direction in which friction is zero. The boxes are grouped so that they should travel in a line.

I've also exported and attached a world file from this test so you can tinker with it. The test is passing in our CI builds, but it could be that the test expectations are incorrect or that the test is too limited to show the error. Please let me know if you have a chance to look at this example.

@osrf-migration
Copy link
Author

Original comment by Steve Peters (Bitbucket: Steven Peters, GitHub: scpeters).


I'm wondering if this might be arise from other issues with contact parameters, specifically the min_depth and max_vel. If you View Contacts, they should ideally be consistent, but with the default parameter values, the contact behavior can be poor. See this gazebo_models pull request as an example. I'll write a tutorial about setting these parameters.

@osrf-migration
Copy link
Author

Original comment by Jacob Huesman (Bitbucket: jacobhuesman).


I haven't tried messing with the min_depth or max_vel parameters yet, so I can't comment on if those help or not. However from my recent experience with trying to get a skid steering robot to work in Gazebo, I'm pretty sure there is something wrong with the fdir1 parameter. Here's a link of the robot transitioning from the x direction to the y direction. As it transitions, the wheel's coefficients of friction in the x and y direction relative to the world appear to remain fixed, resulting in the robot barely being able to turn as it gets closer to the y direction. After implementing Andrea's hack it works as I'd expect it to, here's a link.

@osrf-migration
Copy link
Author

Original comment by Jeremy White (Bitbucket: knitfoo).


Forgive me; this is going to be one of those utterly useless comments, because I don't have the time to investigate and comment in detail. However, Steven, I used that world for a while, and I recall clearly being able to get what felt like a 'wrong' result. That is, if I recall right, it has gravity in x and z, and the friction behaves as expected. If you shift the gravity to y and z, though, you get a behavior that felt wrong. I specifically recall thinking that it did prove that fdir was in world coordinates, not object relative coordinates. If I was less lame, I'd retest with Andrea's patch and see if that makes it behave more as I would expect.

@osrf-migration
Copy link
Author

Original comment by Steve Peters (Bitbucket: Steven Peters, GitHub: scpeters).


Ok, I looked into this a bit more today. I'm pretty confident that fdir1 is often working as intended, though e75cdf6 did introduce a bug (when the second collision have fdir1 set). The broader issue is that I think the friction pyramid model is not well suited to things like a skid-steer robot, even if the fdir1 parameter is oriented with the wheel. It worked fine in the DRC for the polaris because it has Ackermann steering, but for skid-steer a friction cone model really needs to be used instead of a friction pyramid.

Fortunately, gazebo's ODE has a friction cone model added by @rosebudflyaway (pull request #1522)! The only drawback is that the only way to enable it is with a c++ API call to PhysicsEngine::SetParam, presumably from a plugin. Here's an example from the INTEGRATION_physics_friction test:

physics::PhysicsEnginePtr physics = world->GetPhysicsEngine();
const std::string frictionModel = "cone_model";
physics->SetParam("friction_model", frictionModel);

I'll work on making it easier to set this parameter, but can people give this a try to see if it helps with their use cases? Thanks.

@osrf-migration
Copy link
Author

Original comment by Steve Peters (Bitbucket: Steven Peters, GitHub: scpeters).


The changes in pull request #1522 are visible in this commit: 968dcca

@osrf-migration
Copy link
Author

Original comment by Jacob Huesman (Bitbucket: jacobhuesman).


I'll give it a try on our model sometime this week.

@osrf-migration
Copy link
Author

Original comment by Muhammad Haseeb (Bitbucket: hashashas).


Is there any update about this issue?. I am also facing the same directional frictional problem in my Gazebo 7 project. The fdir1 doesn't work the way it is described at Gazebo help section.

@osrf-migration
Copy link
Author

Original comment by Steve Peters (Bitbucket: Steven Peters, GitHub: scpeters).


Have you tried running the example code from my comment on Nov 11 inside a plugin? I think that will fix the issue.

I'm also adding an sdformat parameter in sdformat pull request 294 to make it easier to set this parameter.

@osrf-migration
Copy link
Author

Original comment by Martin Pecka (Bitbucket: peci1).


@scpeters : I've tried setting the friction cone computation for my tracked robot model and it gives more satisfactory results.

I just wonder why isn't this new functionality mentioned in the changelog.

Another thing I wonder is what's the meaning of fdir1 when using the friction cone...

@osrf-migration
Copy link
Author

Original comment by Steve Peters (Bitbucket: Steven Peters, GitHub: scpeters).


My apologies that the changes aren't present in the Changelog. I believe the friction cone model was added in version 6.0.0.

I believe the fdir1 parameter has no effect when the cone model is in use.

@osrf-migration
Copy link
Author

Original comment by zeyi wang (Bitbucket: zeyiwang).


Hello Steven, I am new to Gazebo, Where do I add the friction_model tag? Is it in the urdf file, or the world file?

@osrf-migration
Copy link
Author

Original comment by Steve Peters (Bitbucket: Steven Peters, GitHub: scpeters).


UPDATE: I misread what @zeyiwang asked in his question. The following describes how to update the friction coefficients of a collision shape, not the friction model of the solver. My apologies.

If you are creating an sdf model or world file, they should be placed in the surface of a collision, like in the following example:

  • #!/osrf/gazebo_models/src/ae8c18c22b4e3a7b7d4bd86f53bd466141c27408/table/model.sdf?fileviewer=file-view-default#model.sdf-16

If you are creating a urdf model, then you can use a <gazebo> tag with the name of the link to which friction should be added, like the following example:

@osrf-migration
Copy link
Author

Original comment by Martin Pecka (Bitbucket: peci1).


@scpeters I'm not sure you're right... It seems to me this is a world-wide setting in <world><physics><solver><ode><friction_model> ... If I look at SurfaceParams and ODESurfaceParams, there is no mention of the friction model setting.

@osrf-migration
Copy link
Author

osrf-migration commented Mar 22, 2017

Original comment by Martin Pecka (Bitbucket: peci1).


Anyways, there's still something rotten here even using cone_model.

I compared two vehicles. For the one to the left, I compute friction direction myself between collision checking and physics update. The vehicle to the right is just an omniwheel. Both are commanded the same commands - to rotate around their z axis.

The left vehicle has no problems using either pyramid_model or cone_model.

My investigation shows, that mu and mu2 are treated incorrectly in both pyramid_model with directional friction and cone_model.

Asymmetric friction coefficients

mu = 2, mu2 = 0.5

The vehicle to the right has the more serious problems, the more it is aligned with x axis - in both models.

Here with pyramid_model and direction1 set to [1, 0, 0]:
https://drive.google.com/file/d/0B_WCOb_4cMD7VEZzY1B1bE4wc00/view?resourcekey=0-W_VKbTGuYukEpIrvvV4SAA

Here with cone_model:
https://drive.google.com/file/d/0B_WCOb_4cMD7VlQ3dEptdmljZkU/view?resourcekey=0-1NieKQPtdSbPEGpj2h63Hg

It is evident that the cone_model helps a lot, but it's still not perfect.

Symmetric friction coefficients

mu = mu2 = 0.5

In this case, cone_model works as expected, while pyramid_model still has issues.

Here with pyramid_model and direction1 set to [1, 0, 0]:
https://drive.google.com/file/d/0B_WCOb_4cMD7clNqb1RQamFUVms/view?resourcekey=0-mRN5wrhOnHDMMzAXNr1cTQ

Here with cone_model:
https://drive.google.com/file/d/0B_WCOb_4cMD7YXZwY3lnOGV0bW8/view?resourcekey=0-KBSM9ghWNyz9JT1MyvSTNQ

Notes

I looked into the physics_friction.cc test, but I can't easily tell what's different in this case that it works in the test and not in my experiment. The only thing is torque comes into play in my experiments. I don't set torsional friction in any way, so I'd expect it behave the same in all cases.

@osrf-migration
Copy link
Author

Original comment by Steve Peters (Bitbucket: Steven Peters, GitHub: scpeters).


My apologies @peci1, I totally misread the comment by @zeyiwang. I thought he was asking how to change the friction coefficients on a collision, but he obviously wasn't in retrospect.

The friction model is indeed a global property of the solver. We have added an sdformat tag to physics.sdf as you noted, though it not yet checked when a physics engine is loaded. So the only way to set it currently is with a c++ API call to PhysicsEngine::SetParam. I had intended to make a pull request for this sooner, but I must have gotten distracted.

@osrf-migration
Copy link
Author

Original comment by zeyi wang (Bitbucket: zeyiwang).


Hi Steven and Martin, I figured how to use the cone model, but the result is still a bit less than perfect. Is it necessary to do the fix from Andrea (the first post)? If so, where is that fix implemented? I googled and found that piece in ODEPhysics.cc, but I couldn't find that file though...

@osrf-migration
Copy link
Author

Original comment by Martin Pecka (Bitbucket: peci1).


here

@osrf-migration
Copy link
Author

Original comment by zeyi wang (Bitbucket: zeyiwang).


Thank you for your reply Martin! So is ODEPhysics.cc in my computer? I went to gazebo/physics/ode in my computer and only found the header file ODEPhysics.hh. I have no idea where to implement that fix provided by Andrea.

@osrf-migration
Copy link
Author

Original comment by Martin Pecka (Bitbucket: peci1).


Ah, so... You'll need to build Gazebo from source to apply the fix. Make sure you have at least 10 gigs of disk space, 4 gigs of RAM, and >2 hours of free time =)

@osrf-migration
Copy link
Author

Original comment by zeyi wang (Bitbucket: zeyiwang).


Thanks!!!

@osrf-migration
Copy link
Author

Original comment by Steve Peters (Bitbucket: Steven Peters, GitHub: scpeters).


As I look at this more closely, @aerydna was absolutely correct from the beginning. My apologies for not noticing this sooner. I was somewhat blinded by the fact that I wrote a test that covers a very similar case with boxes at many different angles with the friction direction set. That test didn't catch this bug, though, because the boxes don't rotate during the test.

I will start by updating the test and then implement the fix suggested by @aerydna. Thanks for your patience with the cone_model suggestions.

@osrf-migration
Copy link
Author

Original comment by Steve Peters (Bitbucket: Steven Peters, GitHub: scpeters).


A little more detail, this bug doesn't affect the first link defined in a model, so my test absolutely couldn't demonstrate this bug because all the models had only a single link. I'll add a model with multiple links next.

@osrf-migration
Copy link
Author

Original comment by Steve Peters (Bitbucket: Steven Peters, GitHub: scpeters).


  • changed state from "new" to "resolved"

fixed by pull request #2702

@osrf-migration
Copy link
Author

Original comment by Martin Pecka (Bitbucket: peci1).


There’s still something broken about friction in Gazebo 9. And you don’t even need to play around with custom friction directions.

You can play with it yourself in Gazebo 9. Just make a copy of worlds/tracked_vehicle_wheeled.world, find the wheel_tracked_vehicle_controller plugin, and edit <track_mu> to 2.0 . Then use WSAD keys to rotate around. You’ll see that the robot is kind of prevented rotating “over” diagonals of the world. The plugin itself doesn’t touch anything else than <mu>, <mu2> and velocity of the joints. It also changes friction model to cone, but even leaving the default suffers from the same bug (even more).

Here’s a video: https://vimeo.com/373156495 . Sorry for the “jumping” glitches in the video. This is just how my Gazebo records MP4 or OGV videos. Do you have any recommendations on how to get better videos?

@osrf-migration osrf-migration added major physics bug Something isn't working labels Apr 19, 2020
@AndersEllinge
Copy link

I tried to use the worlds/tracked_vehicle_wheeled.world example out of the box as explained above and can confirm the 'broken' friction over the diagonals in Gazebo 9.

However I do believe that it is actually not broken, but due to the ODE physics, as when I increase the ERP constraint of the physics solver from 0.2 to 0.6 then this weird 'broken' behavior discussed above disappears.
If you try out the above example without increasing the ERP, then you can visualize the contact points in the gazebo client, and you will quickly notice that at the 'broken' diagonals there are only 3-4 contact points active, meaning not all wheels are actually touching the surface! This effectively means that the ODE solver has allowed for a tiny error in the wheel joints (explanation given here http://ode.org/ode-latest-userguide.html#sec_3_7_0), which in this scenario has 'raised' the wheel joints slightly above the surface hence not actually creating any friction/collision. Reducing this error (by increasing ERP) the wheels will be in contact with the surface alot more, hence the 'broken' behavior seemingly disappears.

The question is now rather, why does the ODE solver reach this specific solution of the joint positions slightly raised above the surface in such a repetitive fashion with a 'low' ERP constraint at the diagonals?

Please correct me if I am wrong, I just felt like sharing my discoveries as I am interested in reliably simulating a tracked vehicle.

@scpeters
Copy link
Member

scpeters commented Jan 5, 2021

@AndersEllinge can you confirm which version of gazebo9 you are using?

@peci1
Copy link
Contributor

peci1 commented Jan 6, 2021

@AndersEllinge That's an interesting hypothesis, though still not clear why would the joint lifting happen more in some directions. Could you make a short video/gif showing the behavior, so that we can comment on it?

@peci1
Copy link
Contributor

peci1 commented Jan 6, 2021

And do you set ERP globally for the whole world, or did you try setting it just for the wheel joints using http://sdformat.org/spec?ver=1.6&elem=joint#ode_erp ?

@AndersEllinge
Copy link

@scpeters I am using 9.15.0

@peci1 Here is a short video https://vimeo.com/497551878. I change the global ERP from 0.2 --> 0.6 using the GUI running the worlds/tracked_vehicle_wheeled.world example. I suppose the ERP can be individually set for each wheel joint, but have not tried it out.

@peci1
Copy link
Contributor

peci1 commented Jan 6, 2021

Okay, that looks pretty convincing. Could you maybe log the wheel positions to show how much do the wheels get lifted?

@AndersEllinge
Copy link

In the following screen shot I plot the Z position of the 4. and 7. right wheels pose, and the plot is started when the vehicle is 'stuck' and then starts moving to then become stuck again over a diagonal again. Just looking in general I can see lifts with a difference of up to 0.0001 using an ERP of 0.2

Screenshot from 2021-01-06 11-37-30

This screenshot shows the Z position of the 4. right wheel using an ERP of 0.6 and no significant difference is observed.
Screenshot from 2021-01-06 11-45-03

@peci1
Copy link
Contributor

peci1 commented Jan 6, 2021

Great, so this is as expected. I wouldn't start digging deeper into the linear complementarity problem formulation used in ODE to figure out why exactly this happens. If it's sufficient to raise ERP for the affected joints, this seems to be a solution.

It should, however, probably appear in some documentation. Where would be the best place(s)? Something like

Set ERP to a higher value like 0.6 for joints connecting links which are expected to be heavily affected by friction. With low ERP values, the joint may choose to 'avoid the contact' increasing the joint error rather than make the contact and apply the friction force.

@peci1
Copy link
Contributor

peci1 commented Aug 11, 2022

@scpeters
Copy link
Member

@osrf-migration or @scpeters or @chapulina: Could you please edit my migrated post #2068 (comment) and exchange the Google drive links with the following ones? As Google has changed the public sharing link format, I now get an access request from each visitor that tries to open the files.

New links are (in the same order):

Thanks!

@peci1 I just updated it

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working major physics
Projects
None yet
Development

No branches or pull requests

4 participants