0
$\begingroup$

Gazebo Answers logo

Hello,

I am trying to set different friction coefficients in the different x-y link direction. For that i am using the <mu> , <mu2> and <fdir1> tags provided especially for that purpose. But for some reason the friction coefficients are applied by GAZEBO in the world frame and not the link frame.

In order to test the issue I placed same box, with different <mu> and <mu2> on the ground plane in two orientation (perpendicular to each other) and applied increasing gravity in x direction.

Here is the sdf of the ground plane (i use same friction in both directions) :

<?xml version="1.0" ?>
<sdf version="1.5">
      <model name="ground_plane">
        <static>true</static>
        <link name="link">
          <collision name="collision">
            <geometry>
              <plane>
                <normal>0 0 1</normal>
                <size>100 100</size>
              </plane>
            </geometry>
            <surface>
              <friction>
                <ode>
                  <mu>100</mu>
                  <mu2>100</mu2>
              <fdir1>1 0 0</fdir1>
                </ode>
              </friction>
            </surface>
          </collision>
          <visual name="visual">
            <cast_shadows>false</cast_shadows>
            <geometry>
              <plane>
                <normal>0 0 1</normal>
                <size>100 100</size>
              </plane>
            </geometry>
            <material>
              <script>
                <uri>file://media/materials/scripts/gazebo.material</uri>
                <name>Gazebo/Grey</name>
              </script>
            </material>
          </visual>
            </link>
          </model>
    </sdf>

 

Here is the sdf of a box that i use for tests (i set high friction in x direction, and low friction in y direction) :

<?xml version="1.0"?>
<sdf version="1.4">
  <model name="cube1">
    <static>false</static>
    <link name="link">
       <pose>0 0 0.5 0 0 0</pose>
       <collision name="collision">
        <geometry>
            <box>
              <size>2 1 1</size>
            </box>
        </geometry>
        <surface>
          <friction>
            <ode>
              <mu>0.3</mu>
              <mu2>100</mu2>
          <fdir1>1 0 0</fdir1>
            </ode>
          </friction>
         </surface>
    </collision>

      <inertial>
        <pose>0 0 -0.4 0 -0 0</pose>
        <mass>50</mass>
        <inertia>
          <ixx>1</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>1</iyy>
          <iyz>0</iyz>
          <izz>1</izz>
        </inertia>
      </inertial>

      <visual name="visual">
         <geometry>
            <box>
              <size>2 1 1</size>
            </box>
        </geometry>
          <material>
            <script>
              <uri>file://media/materials/scripts/gazebo.material</uri>
              <name>Gazebo/Grey</name>
            </script>
          </material>
      </visual>

    </link>
  </model>
</sdf>

As i increase the gravity in x (world) direction both boxes start to slide simultaneously and with the same speed. if i increase the gravity in y (world) direction the boxes do not move.

image description

What am i doing wrong here ?


Originally posted by dmeltz on Gazebo Answers with karma: 127 on 2015-09-10

Post score: 3

$\endgroup$

3 Answers 3

0
$\begingroup$

Gazebo Answers logo

I also ran into similar issues (see this question about parameters for a skid steered robot). My impression is that fdir1 doesn't work correctly for many use cases. There has been a ODE fdir1 parameter broken issue on Bitbucket that has been marked resolved, but it appears that expected behavior when fdir1 is defined for both surfaces is not clear currently (see the create unit test for fdir1 issue). You could try not specifying fdir1 for your ground plane and see if that changes anything.


Originally posted by Stefan Kohlbrecher with karma: 473 on 2015-09-10

This answer was NOT ACCEPTED on the original site

Post score: 3


Original comments

Comment by jwhite on 2016-10-08:
I believe there is a fairly obvious bug introduced in 2014; I've added more details in the https://bitbucket.org/osrf/gazebo/issues/463/ode-fdir1-parameter-broken issue report.

$\endgroup$
0
$\begingroup$

Gazebo Answers logo

Hi,

Here I leave an example of how it could be done. In current version of gazebo there is no bugs as fas as I'm concerned, as fas as URDFs go. Here is the video response.

simple_box_friction_Y.urdf

simple_box_friction_X.urdf

You basically have to use the gazebo tag and set the mu and mu2 accordingly


Originally posted by Duckfrost with karma: 209 on 2017-09-27

This answer was NOT ACCEPTED on the original site

Post score: 1

$\endgroup$
0
$\begingroup$

Gazebo Answers logo

this pull request may be relevant. It fixes friction direction for gazebo7 and has also been merged forward to 8


Originally posted by iche033 with karma: 1018 on 2017-09-27

This answer was NOT ACCEPTED on the original site

Post score: 1

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.