Gazebo | Ignition | Community
Ask Your Question
0

Simulated robot is building a tower of blocks in Gazebo 7, blocks are sliding

asked 2018-12-28 02:24:24 -0500

Fuzzmeister gravatar image

updated 2018-12-28 10:16:44 -0500

azeey gravatar image

I'm trying to have a Sawyer robot build a tower out of blocks but the blocks keep sliding off each other. I'm using Gazebo version 7. I've tried increasing the friction but it made no difference.

SDF file for blocks:

<robot name="block">
  <link name="block">
    <inertial>
      <origin xyz="0.025 0.025 0.025" />
      <mass value="0.5" />
      <!-- (1/12)*mass*(h^2 + d^2)  (1/12)*mass*(w^2 + d^2) (1/12)*mass*(w^2 + h^2) -->
      <!-- (1/12)*0.5*(0.045^2 + 0.045^2)  (1/12)*0.5*(0.045^2 + 0.045^2) (1/12)*0.5*(0.045^2 + 0.045^2) -->
      <inertia  ixx="0.00016874999" ixy="0.0"  ixz="0.0"  iyy="0.00016874999"  iyz="0.0"  izz="0.00016874999" />

    </inertial>
    <visual>
      <origin xyz="0.025 0.025 0.025"/>
      <geometry>
        <box size="0.045 0.045 0.045" />
      </geometry>
    </visual>
    <collision>
      <origin xyz="0.025 0.025 0.025"/>
      <geometry>
        <box size="0.045 0.045 0.045" />
      </geometry>
      <surface>
        <friction>
          <ode>
            <mu>9999999999.0</mu>
            <mu2>9999999999.0</mu2>
            <slip1>0.0</slip1>
            <slip2>0.0</slip2>
          </ode>
        </friction>
      </surface>
    </collision>
  </link>
  <gazebo reference="block">
    <material>Gazebo/Blue</material>
     <mu1>1000</mu1>
     <mu2>1000</mu2>
  </gazebo>
</robot>

SDF file for the world:

<?xml version="1.0" ?>
<sdf version="1.6">
  <world name="default">
    <include>
      <uri>model://ground_plane</uri>
    </include>

    <include>
      <uri>model://sun</uri>
    </include>

    <physics type="ode">
      <real_time_update_rate>1000.0</real_time_update_rate>
    </physics>

    <gravity>
      0.0 0.0 -9.81
    </gravity>

    <gui fullscreen='0'>
      <camera name='user_camera'>
        <pose frame=''>2.69836 -0.874828 2.04939 0 0.399643 2.75619</pose>
        <view_controller>orbit</view_controller>
        <projection_type>perspective</projection_type>
      </camera>
    </gui>

  </world>
</sdf>

SDF file for the tabletop the blocks are placed on top of:

<?xml version="1.0" ?>
<sdf version="1.4">
  <model name="cafe_table">
    <static>true</static>
    <link name="link">
      <collision name="surface">
        <pose>0 0 0.755 0 0 0</pose>
        <geometry>
          <box>
            <size>0.913 0.913 0.04</size>
          </box>
        </geometry>
      </collision>

      <collision name="column">
        <pose>0 0 0.37 0 0 0</pose>
        <geometry>
          <box>
            <size>0.042 0.042 0.74</size>
          </box>
        </geometry>
      </collision>

      <collision name="base">
        <pose>0 0 0.02 0 0 0</pose>
        <geometry>
          <box>
            <size>0.56 0.56 0.04</size>
          </box>
        </geometry>
      </collision>

      <visual name="visual">
        <geometry>
          <mesh>
            <uri>model://cafe_table/meshes/cafe_table.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
  </model>
</sdf>
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2018-12-28 11:06:45 -0500

chapulina gravatar image

This model of a stack of wood blocks like jenga should give you a starting point for which parameters to use. Note especially the <contact> tags.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2018-12-28 02:24:24 -0500

Seen: 405 times

Last updated: Dec 28 '18