[CFC] Reduce 3D meshes complexity of the URDF model

Continuing the discussion from HowTo: Connect pypot to your simulated version of Poppy humanoid in V-REP:

Call for contributions

The current 3D model for simulation (for the moment V-REP only) is a bit too complex making the simulation quite slow. Therefore, it would be great to reduce the meshes complexity to improve the overall performance.

In this kind of model, there are actually 2 bodies per part. The physical body is used to compute collision between parts while the visual body is the one displayed. Both have to be simplify to improve the overall performances.

The simulated robot is generated from a URDF file available here. This URDF links to the visual meshes (STL) available here and currently links to the same meshes for the collision bodies (which is not optimized):

<link name="pelvis">

  <inertial>
    <origin xyz="-0.000134932459328483 -0.000399086261064929 0.00195556930608449" rpy="0 0 0"></origin>
    <mass value="0.18520035953947"></mass>
    <inertia ixx="0.000101804322229161" ixy="3.56589402562651E-08" ixz="-1.38613151054156E-05" iyy="0.000142404075398435" iyz="-3.50682832702007E-06" izz="9.38193247222871E-05"></inertia>
  </inertial>

  <visual>
    <origin xyz="0 0 0" rpy="0 0 0"></origin>
    <geometry>
      <mesh filename="package://meshes/pelvis.STL"></mesh>
    </geometry>
    <material name="">
      <color rgba="0.9 0.9 0.9 1.0"></color>
    </material>
  </visual>

  <collision>
    <origin xyz="0 0 0" rpy="0 0 0"></origin>
    <geometry>
      <mesh filename="package://meshes/pelvis.STL"></mesh>
    </geometry>
  </collision>

</link>

It is needed to create alternative meshes for the collision and simplify the visual meshes. To do so the MeshLab software appears as a very good candidate.

Step 1: Simplify collision bodies

Currently, physical bodies are the same as the visual body so they are waaayyy too complex for efficient collisions computation.
The first step is to create an alternative very-simplified version and as convex as possible. The convex hull algorithm seems a good starting point but may not be adapted for all parts.

Then export the alternative mesh and link it properly in the URDF file, for example:

 <collision>
    <origin xyz="0 0 0" rpy="0 0 0"></origin>
    <geometry>
      <mesh filename="package://meshes/pelvis-collidable.STL"></mesh>
    </geometry>
  </collision>

Step 2: Simplify the visual bodies

For the visual bodies, we only have to reduce the number of triangle to improve the display framerate. Meshlab has a lot of tool to do it, here is an example:

Bonus step: create a script to automatically perform all these operations

On Poppy Humanoid, there are many moving parts (26) so generating all these meshes each time the robot is upgraded seems quite boring… Meshlab permits to create scripts, maybe there is something to do with this feature ?

Contributions guidelines

You can fork the Poppy Humanoid repository and work directly on meshes available in hardware/URDF/meshes. Then create a pull request to integrate your awesome changes :wink:

1 Like

I started to work on it and created a branch simplify_meshes accessible here: https://github.com/poppy-project/poppy-humanoid/tree/simplify_meshes

A first commit:

Hi Matthieu,

Can you just explain very quickly how you did it, because I don’t know Meshlab and I guess I can be faster if I use the same method as you.

Regards.

Here is how I do it but I’m also new to Meshlab and never used it before so it is certainly not the best way to do it.

How to generate the respondable meshes

1- Open your STL file (here is l_thigh.stl)

And enable Show Layer Dialog in View

2- Create the convex Hull


If everything goes fine, you will have a nice convex shape like this one:

Alternatively you may obtain a fully black mesh like this:

To fix that, you just have to inverse the face orientation:


3- Duplicate the convex_hull layer

It allows to keep a copy, very useful as there is NO undo feature (!!!) in meshlab…

4- Simplify the mesh:

You will begin with a mesh with hundreds of faces (here 1666):

Use Quadric Edge Collapse Decimation:

In the dialog box, use parameters as follow:

Then click Apply several times, it will apply the filter with a 10% reduction each times but be careful, you cannot undo your action so if you simplify to much the mesh, you will have to redo everything since step 3…

It is a bit tricky to evaluate how “good” the final simplified mesh is and if you have simplify too much or not enough… At the end, you have to obtain a shape simple enough to simplify computation but precise enough to have a coherent behavior with the real robot…

After a dozen of filter applications, you obtain a very simplify mesh with 30-80 faces:

5- Export the new mesh

Then you just have to

  • select the correct layer,
  • Export Mesh As,
  • select .stl,
  • and add _respondable in the name.

DONE

Note

The convex hull may not be the best way to create a representative respondable shape for Poppy Humanoid as they are a lot of non convex parts. Collisions may not be so realistic.
Is someone know a better way to create a simple envelope of the shape ?

1 Like

6 new shapes made this morning (I made a pull request). I wonder if to transform a concave shape like neck.stl in a convex one will have consequences on the behavior in V-REP ?

What is shin_respondable.stl ? I can’t find this shape in the URDF file.

First try to import poppy in V-REP with URDF model and new respondable shape. Very strange Poppy…

There is something wrong with some shapes in the branches simply_meshes. For example, l_foot respondable is not at the right place after an URDF import.
I tried to rebuild the l_foot with mesh_lab and it works correctly,…

Maybe when I exported the STL, meshlab changed the origin ? Did you do something different than my tutorial ?

Nothing different from your tutorial. I just remove the handle in the back of poppy to build the chest.
Import tested in V-REP, no problem (just an error message about join name ’ ’ that doesnt’ exist ??). The simulation speed seems to be ten times faster !

and simplification for the visual part :

Now Poppy_VREP is really really faster… let me quickly test it :smile:

2 Likes

Yes, really better in V-REP !

1 Like

Hey very nice work.

I have just trouble with the URDF import in vrep. When I run the simulation with the new Poppy it kind of explodes … Did you have similar issue ?

EDIT: It is when I activate the “alternate responsive layer” so this is due to the interferences between responsible shapes and I guess we will have to do it by hand.

It works without “alternate respondable layer” is this option really necessary ?

But poppy is taken from epileptic seizure if I activate the option…

I think this is the reason. 2 non-consecutives shapes are in contact. Maybe to cut some parts of the original shape before to aply the hull convex filter could be the way…

It permits to have contact between parts so the arms cannot go trough the legs. It makes simulation more realistic.

You can launch the current official vrep-scene: poppy-shell humanoid --vrep
then test poppy.compliant = True and you will see it is fun how it falls.

Yes, it is like poppy was unplugged, out af supply !

I checked, where the shapes were in contact and in fact there are only two shapes in interaction. So, I redesigned these two shapes and now it works with respondable mask. I’m going to make a pull request.

1 Like

Merged in master!

Mega thanks for @juju

2 Likes