Gazebo | Ignition | Community
Ask Your Question
0

Inaccurate Pendulum Period

asked 2015-12-20 16:30:30 -0600

theNerd247 gravatar image

updated 2015-12-20 20:51:27 -0600

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 ...
(more)
edit retag flag offensive close merge delete

Comments

Can you please share what you did to get "the pendulum to work"? Thanks!

hsu gravatar imagehsu ( 2015-12-20 23:11:25 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2015-12-20 22:45:08 -0600

hsu gravatar image

What governing equations do you use to find the exact solution? (Your model (as posted) does not have any inertia blocks, hence, mass is 1 kg and MOI is 1 kg m^2, and you'll probably need the equations for compound pendulum to compute the period).

You can refer to the simple pendulum integration test that checks for simple pendulum period correctness.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2015-12-20 16:30:30 -0600

Seen: 367 times

Last updated: Dec 20 '15