diff --git a/include/hpp/fcl/mesh_loader/assimp.h b/include/hpp/fcl/mesh_loader/assimp.h
index 8f0bce65999f345aa8e76a5e73d635332e0ca02c..c769d6781cbdfa86df496e8d1eb904fff6e34afc 100644
--- a/include/hpp/fcl/mesh_loader/assimp.h
+++ b/include/hpp/fcl/mesh_loader/assimp.h
@@ -64,15 +64,25 @@ namespace fcl
 
 struct TriangleAndVertices
 {
-  void clear()
-  {
-    vertices_.clear ();
-    triangles_.clear ();
-  }
   std::vector <fcl::Vec3f> vertices_;
   std::vector <fcl::Triangle> triangles_;
 };
 
+/**
+ * @brief      Recursive procedure for building a mesh
+ *
+ * @param[in]  scale           Scale to apply when reading the ressource
+ * @param[in]  scene           Pointer to the assimp scene
+ * @param[in]  node            Current node of the scene
+ * @param[in]  vertices_offset Current number of vertices in the model
+ * @param      tv              Triangles and Vertices of the mesh submodels
+ */
+unsigned buildMesh (const fcl::Vec3f & scale,
+                    const aiScene* scene,
+                    const aiNode* node,
+                    unsigned vertices_offset,
+                    TriangleAndVertices & tv);
+
 /**
  * @brief      Convert an assimp scene to a mesh
  *
@@ -92,7 +102,6 @@ inline void meshFromAssimpScene(const std::string & name,
   if (!scene->HasMeshes())
     throw std::invalid_argument (std::string ("No meshes found in file ")+name);
   
-  std::vector<unsigned> subMeshIndexes;
   int res = mesh->beginModel ();
   
   if (res != fcl::BVH_OK)
@@ -102,100 +111,13 @@ inline void meshFromAssimpScene(const std::string & name,
     throw std::runtime_error (error.str ());
   }
     
-  tv.clear();
-    
-  buildMesh (scale, scene, scene->mRootNode, subMeshIndexes, mesh, tv);
+  buildMesh (scale, scene, scene->mRootNode, 
+      (unsigned) mesh->num_vertices, tv);
   mesh->addSubModel (tv.vertices_, tv.triangles_);
     
   mesh->endModel ();
 }
 
-/**
- * @brief      Recursive procedure for building a mesh
- *
- * @param[in]  scale           Scale to apply when reading the ressource
- * @param[in]  scene           Pointer to the assimp scene
- * @param[in]  node            Current node of the scene
- * @param      subMeshIndexes  Submesh triangles indexes interval
- * @param[in]  mesh            The mesh that must be built
- * @param      tv              Triangles and Vertices of the mesh submodels
- */
-template<class BoundingVolume>
-inline void buildMesh (const fcl::Vec3f & scale,
-                const aiScene* scene,
-                const aiNode* node,
-                std::vector<unsigned> & subMeshIndexes,
-                const boost::shared_ptr < BVHModel<BoundingVolume> > & mesh,
-                TriangleAndVertices & tv)
-{
-  if (!node) return;
-  
-  aiMatrix4x4 transform = node->mTransformation;
-  aiNode *pnode = node->mParent;
-  while (pnode)
-  {
-    // Don't convert to y-up orientation, which is what the root node in
-    // Assimp does
-    if (pnode->mParent != NULL)
-    {
-      transform = pnode->mTransformation * transform;
-    }
-    pnode = pnode->mParent;
-  }
-  
-  for (uint32_t i = 0; i < node->mNumMeshes; i++)
-  {
-    aiMesh* input_mesh = scene->mMeshes[node->mMeshes[i]];
-    
-    unsigned oldNbPoints = (unsigned) mesh->num_vertices;
-    unsigned oldNbTriangles = (unsigned) mesh->num_tris;
-    
-    // Add the vertices
-    for (uint32_t j = 0; j < input_mesh->mNumVertices; j++)
-    {
-      aiVector3D p = input_mesh->mVertices[j];
-      p *= transform;
-      tv.vertices_.push_back (fcl::Vec3f (p.x * scale[0],
-                                          p.y * scale[1],
-                                          p.z * scale[2]));
-    }
-    
-    // add the indices
-    for (uint32_t j = 0; j < input_mesh->mNumFaces; j++)
-    {
-      aiFace& face = input_mesh->mFaces[j];
-      if (face.mNumIndices != 3) {
-        std::stringstream ss;
-#ifdef HPP_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES
-        ss << "Mesh " << input_mesh->mName.C_Str() << " has a face with "
-           << face.mNumIndices << " vertices. This is not supported\n";
-        ss << "Node name is: " << node->mName.C_Str() << "\n";
-#endif
-        ss << "Mesh index: " << i << "\n";
-        ss << "Face index: " << j << "\n";
-        throw std::invalid_argument (ss.str());
-      }
-      tv.triangles_.push_back (fcl::Triangle( oldNbPoints + face.mIndices[0],
-                                             oldNbPoints + face.mIndices[1],
-                                             oldNbPoints + face.mIndices[2]));
-    }
-    
-    // Save submesh triangles indexes interval.
-    if (subMeshIndexes.size () == 0)
-    {
-      subMeshIndexes.push_back (0);
-    }
-    
-    subMeshIndexes.push_back (oldNbTriangles + input_mesh->mNumFaces);
-  }
-  
-  for (uint32_t i=0; i < node->mNumChildren; ++i)
-  {
-    buildMesh(scale, scene, node->mChildren[i], subMeshIndexes, mesh, tv);
-  }
-}
-
-
 /**
  * @brief      Read a mesh file and convert it to a polyhedral mesh
  *
@@ -209,26 +131,31 @@ inline void loadPolyhedronFromResource (const std::string & resource_path,
                                  const boost::shared_ptr < BVHModel<BoundingVolume> > & polyhedron) throw (std::invalid_argument)
 {
   Assimp::Importer importer;
-  // // set list of ignored parameters (parameters used for rendering)
-  //    importer.SetPropertyInteger(AI_CONFIG_PP_RVC_FLAGS,
-  //                     aiComponent_TANGENTS_AND_BITANGENTS|
-  //                     aiComponent_COLORS |
-  //                     aiComponent_BONEWEIGHTS |
-  //                     aiComponent_ANIMATIONS |
-  //                     aiComponent_LIGHTS |
-  //                     aiComponent_CAMERAS|
-  //                     aiComponent_TEXTURES |
-  //                     aiComponent_TEXCOORDS |
-  //                     aiComponent_MATERIALS |
-  //                     aiComponent_NORMALS
-  //                 );
+  // set list of ignored parameters (parameters used for rendering)
+  importer.SetPropertyInteger(AI_CONFIG_PP_RVC_FLAGS,
+      aiComponent_TANGENTS_AND_BITANGENTS|
+      aiComponent_COLORS |
+      aiComponent_BONEWEIGHTS |
+      aiComponent_ANIMATIONS |
+      aiComponent_LIGHTS |
+      aiComponent_CAMERAS|
+      aiComponent_TEXTURES |
+      aiComponent_TEXCOORDS |
+      aiComponent_MATERIALS |
+      aiComponent_NORMALS
+      );
 
-  const aiScene* scene = importer.ReadFile(resource_path.c_str(), aiProcess_SortByPType| aiProcess_GenNormals|
-                                           aiProcess_Triangulate|aiProcess_GenUVCoords|
-                                           aiProcess_FlipUVs);
-  // const aiScene* scene = importer.ReadFile(resource_path, aiProcess_SortByPType|
-  //                                          aiProcess_Triangulate | aiProcess_RemoveComponent |
-  //                                          aiProcess_JoinIdenticalVertices);
+  const aiScene* scene = importer.ReadFile(resource_path.c_str(),
+      aiProcess_SortByPType |
+      aiProcess_Triangulate |
+      aiProcess_RemoveComponent |
+      aiProcess_ImproveCacheLocality |
+      // TODO: I (Joseph Mirabel) have no idea whether degenerated triangles are
+      // properly handled. Enabling aiProcess_FindDegenerates would throw an
+      // exception when that happens. Is it too conservative ?
+      // aiProcess_FindDegenerates |
+      aiProcess_JoinIdenticalVertices
+      );
 
   if (!scene)
   {
diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt
index c683748b8cfef837c7658e1bae159741ea26d06e..523a1974a7b6655d8b911fb324d678a83c601ba5 100644
--- a/src/CMakeLists.txt
+++ b/src/CMakeLists.txt
@@ -78,6 +78,7 @@ set(${LIBRARY_NAME}_SOURCES
   BVH/BV_splitter.cpp
   collision_func_matrix.cpp
   collision_utility.cpp
+  mesh_loader/assimp.cpp
   mesh_loader/loader.cpp
   )
 
diff --git a/src/mesh_loader/assimp.cpp b/src/mesh_loader/assimp.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..7e58853a73f8bdf86b1202e1e08b62cb933f3ca8
--- /dev/null
+++ b/src/mesh_loader/assimp.cpp
@@ -0,0 +1,111 @@
+/*
+ * Software License Agreement (BSD License)
+ *
+ *  Copyright (c) 2019, CNRS - LAAS
+ *  All rights reserved.
+ *
+ *  Redistribution and use in source and binary forms, with or without
+ *  modification, are permitted provided that the following conditions
+ *  are met:
+ *
+ *   * Redistributions of source code must retain the above copyright
+ *     notice, this list of conditions and the following disclaimer.
+ *   * Redistributions in binary form must reproduce the above
+ *     copyright notice, this list of conditions and the following
+ *     disclaimer in the documentation and/or other materials provided
+ *     with the distribution.
+ *   * Neither the name of Open Source Robotics Foundation nor the names of its
+ *     contributors may be used to endorse or promote products derived
+ *     from this software without specific prior written permission.
+ *
+ *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ *  POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#include <hpp/fcl/mesh_loader/assimp.h>
+
+namespace hpp
+{
+namespace fcl
+{
+  
+unsigned buildMesh (const fcl::Vec3f & scale,
+                    const aiScene* scene,
+                    const aiNode* node,
+                    unsigned vertices_offset,
+                    TriangleAndVertices & tv)
+{
+  if (!node) return 0;
+  
+  aiMatrix4x4 transform = node->mTransformation;
+  aiNode *pnode = node->mParent;
+  while (pnode)
+  {
+    // Don't convert to y-up orientation, which is what the root node in
+    // Assimp does
+    if (pnode->mParent != NULL)
+    {
+      transform = pnode->mTransformation * transform;
+    }
+    pnode = pnode->mParent;
+  }
+  
+  unsigned nbVertices = 0;
+  for (uint32_t i = 0; i < node->mNumMeshes; i++)
+  {
+    aiMesh* input_mesh = scene->mMeshes[node->mMeshes[i]];
+    
+    // Add the vertices
+    for (uint32_t j = 0; j < input_mesh->mNumVertices; j++)
+    {
+      aiVector3D p = input_mesh->mVertices[j];
+      p *= transform;
+      tv.vertices_.push_back (fcl::Vec3f (p.x * scale[0],
+                                          p.y * scale[1],
+                                          p.z * scale[2]));
+    }
+    
+    // add the indices
+    for (uint32_t j = 0; j < input_mesh->mNumFaces; j++)
+    {
+      aiFace& face = input_mesh->mFaces[j];
+      if (face.mNumIndices != 3) {
+        std::stringstream ss;
+#ifdef HPP_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES
+        ss << "Mesh " << input_mesh->mName.C_Str() << " has a face with "
+           << face.mNumIndices << " vertices. This is not supported\n";
+        ss << "Node name is: " << node->mName.C_Str() << "\n";
+#endif
+        ss << "Mesh index: " << i << "\n";
+        ss << "Face index: " << j << "\n";
+        throw std::invalid_argument (ss.str());
+      }
+      tv.triangles_.push_back (fcl::Triangle(vertices_offset + face.mIndices[0],
+                                             vertices_offset + face.mIndices[1],
+                                             vertices_offset + face.mIndices[2]));
+    }
+
+    nbVertices += input_mesh->mNumVertices;
+  }
+  
+  for (uint32_t i=0; i < node->mNumChildren; ++i)
+  {
+    nbVertices += buildMesh(scale, scene, node->mChildren[i], nbVertices, tv);
+  }
+
+  return nbVertices;
+}
+
+}
+
+} // namespace hpp