Gazebo | Ignition | Community
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

Inaccurate Pendulum Period

Hello,

I'm working on a pendulum model and I'm noticing some inaccuracies when running gazebo with the following world files and pendulum model. What I'm noticing is that the pendulum in the simulation has a wrong period (about a second later than expected). I expect the period to be 2.0071 - my pendulum has a length of 1 as seen in the model file - however after plotting the pose of the ball with respect to time I'm seeing that the period is actually ~2.84.

Currently I'm using ODE as the physics engine however Simbody and Bullet are giving the same results. Any ideas what might be causing this? Thanks!

Oh and I'm using gazebo-6.5.1

Model:

<?xml version='1.0'?>
<sdf version='1.5'>
  <model name='pendulum'>
    <link name='fixedPoint'>
      <pose>0 0 1 0 0 0</pose>
      <gravity>0</gravity>
      <visual name='visual'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <sphere>
            <radius>0.01</radius>
          </sphere>
        </geometry>
        <material>
          <lighting>1</lighting>
          <script>
            <uri>file://media/materials/scripts/gazebo.material</uri>
            <name>Gazebo/Grey</name>
          </script>
          <shader type='pixel'/>
          <ambient>0.3 0.3 0.3 1</ambient>
          <diffuse>0.7 0.7 0.7 1</diffuse>
          <specular>0.01 0.01 0.01 1</specular>
          <emissive>0 0 0 1</emissive>
        </material>
        <cast_shadows>1</cast_shadows>
        <transparency>0</transparency>
      </visual>
      <collision name='collision'>
        <laser_retro>0</laser_retro>
        <max_contacts>10</max_contacts>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <sphere>
            <radius>0.01</radius>
          </sphere>
        </geometry>
        <surface>
          <friction>
            <ode>
              <mu>1</mu>
              <mu2>1</mu2>
              <fdir1>0 0 0</fdir1>
              <slip1>0</slip1>
              <slip2>0</slip2>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0</restitution_coefficient>
            <threshold>1e+06</threshold>
          </bounce>
          <contact>
            <collide_without_contact>0</collide_without_contact>
            <collide_without_contact_bitmask>1</collide_without_contact_bitmask>
            <collide_bitmask>1</collide_bitmask>
            <ode>
              <soft_cfm>0</soft_cfm>
              <soft_erp>0.2</soft_erp>
              <kp>1e+13</kp>
              <kd>1</kd>
              <max_vel>0.01</max_vel>
              <min_depth>0</min_depth>
            </ode>
            <bullet>
              <split_impulse>1</split_impulse>
              <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>
              <soft_cfm>0</soft_cfm>
              <soft_erp>0.2</soft_erp>
              <kp>1e+13</kp>
              <kd>1</kd>
            </bullet>
          </contact>
        </surface>
      </collision>
    </link>

    <link name='ball'>
      <pose>0 0.008999 0.00004 0 0 0</pose>
      <gravity>1</gravity>
      <visual name='visual'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <sphere>
            <radius>0.1</radius>
          </sphere>
        </geometry>
        <material>
          <lighting>1</lighting>
          <script>
            <uri>file://media/materials/scripts/gazebo.material</uri>
            <name>Gazebo/Grey</name>
          </script>
          <shader type='pixel'/>
          <ambient>0.3 0.3 0.3 1</ambient>
          <diffuse>0.7 0.7 0.7 1</diffuse>
          <specular>0.01 0.01 0.01 1</specular>
          <emissive>0 0 0 1</emissive>
        </material>
        <cast_shadows>1</cast_shadows>
        <transparency>0</transparency>
      </visual>
      <collision name='collision'>
        <laser_retro>0</laser_retro>
        <max_contacts>10</max_contacts>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <sphere>
            <radius>0.1</radius>
          </sphere>
        </geometry>
        <surface>
          <friction>
            <ode>
              <mu>1</mu>
              <mu2>1</mu2>
              <fdir1>0 0 0</fdir1>
              <slip1>0</slip1>
              <slip2>0</slip2>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0</restitution_coefficient>
            <threshold>1e+06</threshold>
          </bounce>
          <contact>
            <collide_without_contact>0</collide_without_contact>
            <collide_without_contact_bitmask>1</collide_without_contact_bitmask>
            <collide_bitmask>1</collide_bitmask>
            <ode>
              <soft_cfm>0</soft_cfm>
              <soft_erp>0.2</soft_erp>
              <kp>1e+13</kp>
              <kd>1</kd>
              <max_vel>0.01</max_vel>
              <min_depth>0</min_depth>
            </ode>
            <bullet>
              <split_impulse>1</split_impulse>
              <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>
              <soft_cfm>0</soft_cfm>
              <soft_erp>0.2</soft_erp>
              <kp>1e+13</kp>
              <kd>1</kd>
            </bullet>
          </contact>
        </surface>
      </collision>
    </link>
    <joint name="world_J_fixedPoint" type="fixed">
      <parent>world</parent>
      <child>fixedPoint</child>
    </joint>

    <joint name="fixedPoint_J_ball" type="revolute">
      <child>fixedPoint</child>
      <parent>ball</parent>
      <pose>0 0 0 0 0 0</pose>
      <axis>
        <xyz>1 0 0</xyz>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
          <damping>0.000</damping>
          <friction>0.000</friction>
        </dynamics>
      </axis>
    </joint>
    <plugin name="monitorPose" filename="libmonitorPose.so"/>
  </model>
</sdf>

World:

<?xml version="1.0" ?>
<sdf version="1.4">
  <world name="default">
    <!--<include>-->
      <!--<uri>model://ground_plane</uri>-->
      <!--</include>-->
    <include>
      <uri>model://sun</uri>
    </include>
    <include>
      <uri>model://pendulum</uri>
    </include>
    <physics type="bullet">
      <max_step_size>0.00001</max_step_size>
      <real_time_update_rate>100000000</real_time_update_rate>
      <real_time_factor>1</real_time_factor>
    </physics>
  </world>
</sdf>

Inaccurate Pendulum Period

Hello,

I'm working on a pendulum model and I'm noticing some inaccuracies when running gazebo with the following world files and pendulum model. What I'm noticing is that the pendulum in the simulation has a wrong period (about a second later than expected). I expect the period to be 2.0071 - my pendulum has a length of 1 as seen in the model file - however after plotting the pose of the ball with respect to time I'm seeing that the period is actually ~2.84.

Currently I'm using ODE as the physics engine however Simbody and Bullet are giving the same results. Any ideas what might be causing this? Thanks!

Oh and I'm using gazebo-6.5.1

Model:

<?xml version='1.0'?>
<sdf version='1.5'>
  <model name='pendulum'>
    <link name='fixedPoint'>
      <pose>0 0 1 0 0 0</pose>
      <gravity>0</gravity>
      <visual name='visual'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <sphere>
            <radius>0.01</radius>
          </sphere>
        </geometry>
        <material>
          <lighting>1</lighting>
          <script>
            <uri>file://media/materials/scripts/gazebo.material</uri>
            <name>Gazebo/Grey</name>
          </script>
          <shader type='pixel'/>
          <ambient>0.3 0.3 0.3 1</ambient>
          <diffuse>0.7 0.7 0.7 1</diffuse>
          <specular>0.01 0.01 0.01 1</specular>
          <emissive>0 0 0 1</emissive>
        </material>
        <cast_shadows>1</cast_shadows>
        <transparency>0</transparency>
      </visual>
      <collision name='collision'>
        <laser_retro>0</laser_retro>
        <max_contacts>10</max_contacts>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <sphere>
            <radius>0.01</radius>
          </sphere>
        </geometry>
        <surface>
          <friction>
            <ode>
              <mu>1</mu>
              <mu2>1</mu2>
              <fdir1>0 0 0</fdir1>
              <slip1>0</slip1>
              <slip2>0</slip2>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0</restitution_coefficient>
            <threshold>1e+06</threshold>
          </bounce>
          <contact>
            <collide_without_contact>0</collide_without_contact>
            <collide_without_contact_bitmask>1</collide_without_contact_bitmask>
            <collide_bitmask>1</collide_bitmask>
            <ode>
              <soft_cfm>0</soft_cfm>
              <soft_erp>0.2</soft_erp>
              <kp>1e+13</kp>
              <kd>1</kd>
              <max_vel>0.01</max_vel>
              <min_depth>0</min_depth>
            </ode>
            <bullet>
              <split_impulse>1</split_impulse>
              <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>
              <soft_cfm>0</soft_cfm>
              <soft_erp>0.2</soft_erp>
              <kp>1e+13</kp>
              <kd>1</kd>
            </bullet>
          </contact>
        </surface>
      </collision>
    </link>

    <link name='ball'>
      <pose>0 0.008999 0.00004 0 0 0</pose>
      <gravity>1</gravity>
      <visual name='visual'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <sphere>
            <radius>0.1</radius>
          </sphere>
        </geometry>
        <material>
          <lighting>1</lighting>
          <script>
            <uri>file://media/materials/scripts/gazebo.material</uri>
            <name>Gazebo/Grey</name>
          </script>
          <shader type='pixel'/>
          <ambient>0.3 0.3 0.3 1</ambient>
          <diffuse>0.7 0.7 0.7 1</diffuse>
          <specular>0.01 0.01 0.01 1</specular>
          <emissive>0 0 0 1</emissive>
        </material>
        <cast_shadows>1</cast_shadows>
        <transparency>0</transparency>
      </visual>
      <collision name='collision'>
        <laser_retro>0</laser_retro>
        <max_contacts>10</max_contacts>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <sphere>
            <radius>0.1</radius>
          </sphere>
        </geometry>
        <surface>
          <friction>
            <ode>
              <mu>1</mu>
              <mu2>1</mu2>
              <fdir1>0 0 0</fdir1>
              <slip1>0</slip1>
              <slip2>0</slip2>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0</restitution_coefficient>
            <threshold>1e+06</threshold>
          </bounce>
          <contact>
            <collide_without_contact>0</collide_without_contact>
            <collide_without_contact_bitmask>1</collide_without_contact_bitmask>
            <collide_bitmask>1</collide_bitmask>
            <ode>
              <soft_cfm>0</soft_cfm>
              <soft_erp>0.2</soft_erp>
              <kp>1e+13</kp>
              <kd>1</kd>
              <max_vel>0.01</max_vel>
              <min_depth>0</min_depth>
            </ode>
            <bullet>
              <split_impulse>1</split_impulse>
              <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>
              <soft_cfm>0</soft_cfm>
              <soft_erp>0.2</soft_erp>
              <kp>1e+13</kp>
              <kd>1</kd>
            </bullet>
          </contact>
        </surface>
      </collision>
    </link>
    <joint name="world_J_fixedPoint" type="fixed">
      <parent>world</parent>
      <child>fixedPoint</child>
    </joint>

    <joint name="fixedPoint_J_ball" type="revolute">
      <child>fixedPoint</child>
      <parent>ball</parent>
      <pose>0 0 0 0 0 0</pose>
      <axis>
        <xyz>1 0 0</xyz>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
          <damping>0.000</damping>
          <friction>0.000</friction>
        </dynamics>
      </axis>
    </joint>
    <plugin name="monitorPose" filename="libmonitorPose.so"/>
  </model>
</sdf>

World:

<?xml version="1.0" ?>
<sdf version="1.4">
  <world name="default">
    <!--<include>-->
      <!--<uri>model://ground_plane</uri>-->
      <!--</include>-->
    <include>
      <uri>model://sun</uri>
    </include>
    <include>
      <uri>model://pendulum</uri>
    </include>
    <physics type="bullet">
      <max_step_size>0.00001</max_step_size>
      <real_time_update_rate>100000000</real_time_update_rate>
      <real_time_factor>1</real_time_factor>
    </physics>
  </world>
</sdf>

EDIT: (12/20/15 22:53 EST)

So after reading this Q&A I got the pendulum to work. I'm guessing physics simulators don't like really small numbers? Has anybody else had issues with this?