Robotics StackExchange | Archived questions

Importing models on gazebo

I have a model that I consists of a shelf and some boxes in it. image description

I made this model on other programs like blender or google sketchup and imported on gazebo as Collada file.

I'm facing two issue on the gazebo model:

  1. On importing the collada file from any other software no texture is applied.

  2. The figure shows the collision of my model. That is correct. However, when my robot bump against one of the box it does not move. My model is set static.

This is my sdf file:

   <?xml version='1.0'?>
   <sdf version='1.6'>
   <model name='blender_shelf'>
     <link name='link_0'>
     <pose frame=''>0 0 0 0 -0 0</pose>
        <inertial>
          <mass>1</mass>
          <inertia>
           <ixx>0.166667</ixx>
           <ixy>0</ixy>
           <ixz>0</ixz>
           <iyy>0.166667</iyy>
           <iyz>0</iyz>
           <izz>0.166667</izz>
        </inertia>
      </inertial>
   <visual name='visual'>
    <pose frame=''>0 0 0 0 -0 0</pose>
    <geometry>
      <mesh>
        <uri>/home/bruno/tests/blender_files/populated-_shelf.dae</uri>
        <scale>1 1 1</scale>
      </mesh>
    </geometry>
    <material>
      <lighting>1</lighting>
      <script>
        <uri>file://media/materials/scripts/gazebo.material</uri>
        <name>Gazebo/Grey</name>
      </script>
      <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 frame=''>0 0 0 0 -0 0</pose>
    <geometry>
      <mesh>
        <uri>/home/bruno/tests/blender_files/populated-_shelf.dae</uri>
      </mesh>
    </geometry>
    <surface>
      <friction>
        <ode>
          <mu>1</mu>
          <mu2>1</mu2>
          <fdir1>0 0 0</fdir1>
          <slip1>0</slip1>
          <slip2>0</slip2>
        </ode>
        <torsional>
          <coefficient>1</coefficient>
          <patch_radius>0</patch_radius>
          <surface_radius>0</surface_radius>
          <use_patch_radius>1</use_patch_radius>
          <ode>
            <slip>0</slip>
          </ode>
        </torsional>
      </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>
<static>0</static>
<allow_auto_disable>1</allow_auto_disable>
</model>
</sdf>

Asked by bxl on 2017-12-05 15:34:39 UTC

Comments

Answers

  1. Inside populated-_shelf.dae, make sure the texture URI (a png file perhaps?) is correct, it's a good idea if it starts with model:// or file://
  2. You said your model is set static, but the code says it isn't: <static>0</static>. This means the shelf should move. Maybe you're not bumping strong enough? Try pushing it with the Force / Torque tool. Note that the shelf and the boxes are being treated as a single solid mass, you'll need to tweak some things if you want the boxes to move independently.

Update

For the boxes to move independently, they must consist of separate links on SDF, each with its own mass, visual and collision.

I recommend you look at an example, such as Polaris Ranger EV or Zephyr Delta Wing. Look for the submesh tags and see how they correspond to geometries / nodes on the COLLADA file.

Asked by chapulina on 2017-12-05 15:44:17 UTC

Comments

  1. I checked out the model path and it is right. I even tried the full path.
  2. @chapulina I do want each box and the shelf to behavior independently one from the other. What you mean "by tweak some things"

Asked by bxl on 2017-12-05 17:04:57 UTC

I updated the question regarding the independent boxes. For the texture, have you tried running Gazebo on verbose mode? It usually prints a message when it can't find textures.

Asked by chapulina on 2017-12-05 17:15:00 UTC

I've performed some tests on the init_from tag and when i used modelss full path gazebo raisedtexture error`. However, for the path I'm using it does not shows any error and does not load the texture.

Asked by bxl on 2017-12-06 15:38:26 UTC

I just noticed you're setting the material to Gazebo/Grey, that's probably overriding the texture on the collada file.

Asked by chapulina on 2017-12-07 13:26:50 UTC

Regarding the texture, the gazebo material was overridden the texture on collada file.

Asked by bxl on 2017-12-08 12:37:52 UTC