0
$\begingroup$

Gazebo Answers logo

Hello! I encounter an issue regarding the physical simulation of gazebo, which is that the object in the simulated world keeps rolling over forever and just does not stop. I have uploaded related files (including the model file and world file) to help solve the problem:

https://drive.google.com/folderview?id=0B49go8f2Nr2gZzY4R3VnNGJMNTQ&usp=sharing

Although I set the friction parameters for both the world and the object, the problem still exists. When I use box to approximate the object model, the object shakes forever and does not stop.

I use gazebo 1.9.1 in ubuntu precise 32bit. Thanks for any help!


Originally posted by mikegao88 on Gazebo Answers with karma: 5 on 2013-10-23

Post score: 0


Original comments

Comment by mikegao88 on 2013-10-25:
No one helps with this?

$\endgroup$

1 Answer 1

0
$\begingroup$

Gazebo Answers logo

When objects jitter, it's usually because the inertia values are bad or the physics timestep size is too large.

You can cause a sphere to slowly stop rolling by applying a velocity decay value.

I modified your test.world a bit, and the box seems stable:

<sdf version='1.4'>
  <world name='default'>
    <include>
      <uri>model://sun</uri>
    </include>

    <include>
      <uri>model://ground_plane</uri>
    </include>

    <physics type='ode'>
      <max_step_size>0.001</max_step_size>
      <real_time_factor>1</real_time_factor>
      <real_time_update_rate>1000</real_time_update_rate>
      <gravity>0 0 -9.8</gravity>
    </physics>


    <model name='batterie'>
      <pose>5.486 2.3746 0.5 0 -0 0</pose>
      <link name='link'>
        <inertial>
          <inertia>
            <ixx>1</ixx> <ixy>0</ixy> <ixz>0</ixz>
            <iyy>1</iyy> <iyz>0</iyz>
            <izz>1</izz>
          </inertia>
          <mass>1</mass>
        </inertial>

        <collision name='collision'>
          <geometry>
           <box>
              <size>0.15 0.3 0.075</size>
            </box>
          </geometry>
          <max_contacts>10</max_contacts>
        </collision>

        <visual name='visual'>
          <geometry>
            <box>
              <size>0.15 0.3 0.075</size>
            </box>
          </geometry>
        </visual>
      </link>
    </model>

  </world>
</sdf>

Originally posted by nkoenig with karma: 7676 on 2013-10-25

This answer was ACCEPTED on the original site

Post score: 0

$\endgroup$

Your Answer

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