Home | Tutorials | Wiki | Issues
Ask Your Question
2

A simple question on changing bounce properties

asked 2013-01-11 16:30:07 -0500

Ben B gravatar image

updated 2013-01-11 16:32:03 -0500

Hi all,

I'm trying to model a ball. I'm not having any luck with making it bounce. I try to set the restitution coefficient in my URDF code, but when I look at the properties of the ball in Gazebo (ball1 -> ball -> link -> collision -> surface) the restitution_coefficient is still equal to zero.

I'm running Fuerte (which should correspond to Gazebo 1.0.2) on Ubuntu 12.04.

The URDF:

 <robot name="my_ball">
  <link name="ball">
    <inertial>
      <origin xyz="0 0 0" /> 
      <mass value="0.0027" />
      <inertia  ixx="0.00000072" ixy="0.0"  ixz="0.0"  iyy="0.00000072"  iyz="0.0"  izz="0.00000072" />
    </inertial>
    <visual>
      <origin xyz="0 0 0"/>
      <geometry>
        <sphere radius=".040" />
      </geometry>
    </visual>
    <collision>
      <origin xyz="0 0 0"/>
      <geometry>
        <sphere radius=".040" />
      </geometry>
      <surface>
           <bounce restitution_coefficient = "1"/>
      </surface>
    </collision>

  </link>
  <gazebo reference="ball">
    <material>Gazebo/Orange</material>
    <kd value = "100">
    <kp value = "999999">
        <mu1>1</mu1>
    <mu2>1</mu2>
  </gazebo>
</robot>

I'm loading the ball using:

rosrun gazebo spawn_model -file `pwd`/ballmodel.urdf -urdf -z 10 -x 1 -y -2 -model ball1

I've also tried a few different tags for the restitution coefficient including:

<surface>
...
<bounce restitution_coefficient="0.5" threshold="0.00"/>
...
</surface>

And:

<surface>
...
  <bounce>
       <restitution_coefficient="1"/>
   </bounce>
...
</surface>

and:

<surface>
...    
   <bounce>
       <restitution_coefficient> 1 </restitution_coefficient>
    </bounce>
</surface>
edit retag flag offensive close merge delete

Comments

@Ben B which URDF code worked finally?

peshala gravatar imagepeshala ( 2014-05-21 01:52:04 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
6

answered 2013-01-11 20:06:43 -0500

scpeters gravatar image

updated 2013-01-11 20:07:55 -0500

There's 3 parameters that must be set to enable bouncing. restitution_coefficient must be greater than 0, the bounce threshold must be small, and max_vel must be greater than zero.

Gazebo computes the relative velocity between two bodies in contact. If the relative velocity normal to the contact surface is greater than the bounce threshold, then a bounce may occur, but the bounce velocity will be limited by the max_vel parameter.

Here's an example sdf file that works in gazebo 1.3:

<?xml version="1.0" ?>
<sdf version="1.3">
  <world name="default">
    <include><uri>model://ground_plane</uri></include>
    <include><uri>model://sun</uri></include>
    <model name="ball">
      <pose>0 0 10.5 0 0 0</pose>
      <link name="link">
        <collision name="collision">
          <geometry>
            <sphere>
              <radius>0.5</radius>
            </sphere>
          </geometry>
          <surface>
            <bounce>
              <restitution_coefficient>0.5</restitution_coefficient>
              <threshold>0</threshold>
            </bounce>
            <contact>
              <ode>
                <max_vel>10</max_vel>
              </ode>
            </contact>
          </surface>
        </collision>
        <visual name="visual">
          <geometry>
            <sphere>
              <radius>0.5</radius>
            </sphere>
          </geometry>
          <material>
            <script>
              <uri>file://media/materials/scripts/gazebo.material</uri>
              <name>Gazebo/Grey</name>
            </script>
          </material>
        </visual>
      </link>
    </model>
  </world>
</sdf>
edit flag offensive delete link more
Login/Signup to Answer

Question Tools

2 followers

Stats

Asked: 2013-01-11 16:30:07 -0500

Seen: 2,869 times

Last updated: Jan 11 '13