diff --git a/CMakeLists.txt b/CMakeLists.txt
index 3fc08c3492e503ee4bcf2bd798519441e603411a..92d1b512c26869a0f17be780f5a2f64957c30a9b 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -97,10 +97,8 @@ ADD_REQUIRED_DEPENDENCY("assimp >= 2.0")
 if(ASSIMP_FOUND)
   if (NOT ${ASSIMP_VERSION} VERSION_LESS "2.0.1150")
     add_definitions(-DHPP_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES)
-    SET(HPP_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES TRUE)
     message(STATUS "Assimp version has unified headers")
   else()
-    SET(HPP_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES FALSE)
     message(STATUS "Assimp version does not have unified headers")
   endif()
 endif()
@@ -161,10 +159,6 @@ endif ()
 
 pkg_config_append_libs("hpp-fcl")
 PKG_CONFIG_APPEND_BOOST_LIBS(thread date_time filesystem system)
-IF(HPP_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES)
-  # FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES kept for backard compatibility reasons.
-  PKG_CONFIG_APPEND_CFLAGS("-DFCL_USE_ASSIMP_UNIFIED_HEADER_NAMES -DHPP_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES")
-ENDIF(HPP_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES)
 IF(HPP_FCL_HAVE_OCTOMAP)
   # FCL_HAVE_OCTOMAP kept for backward compatibility reasons.
   PKG_CONFIG_APPEND_CFLAGS(
diff --git a/include/hpp/fcl/BVH/BVH_model.h b/include/hpp/fcl/BVH/BVH_model.h
index 1f29a9bbbb8b18f3f5b34b3b605ad2c51758e386..c07cd8188ef01b4cff273fdba81ded028f61db8f 100644
--- a/include/hpp/fcl/BVH/BVH_model.h
+++ b/include/hpp/fcl/BVH/BVH_model.h
@@ -54,8 +54,7 @@ namespace fcl
 
 /// @brief A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as a degraded version of mesh)
 template<typename BV>
-class BVHModel : public CollisionGeometry,
-                 private boost::noncopyable
+class BVHModel : public CollisionGeometry
 {
 
 public:
diff --git a/include/hpp/fcl/fwd.hh b/include/hpp/fcl/fwd.hh
index 45fc60eceb5bc2e808476d4e72b2843cb045db57..7c5a301667330a84ee1eb7c9c195e2a57ee65b37 100644
--- a/include/hpp/fcl/fwd.hh
+++ b/include/hpp/fcl/fwd.hh
@@ -37,6 +37,8 @@
 #ifndef HPP_FCL_FWD_HH
 #define HPP_FCL_FWD_HH
 
+#include <boost/shared_ptr.hpp>
+
 namespace hpp {
 namespace fcl {
   class CollisionObject;
diff --git a/include/hpp/fcl/mesh_loader/assimp.h b/include/hpp/fcl/mesh_loader/assimp.h
index 2b3078d4574402f1cedd87995588e1f8887a042b..3849fc7dd782e4c1f9b4699f3086ded6b5c9edfc 100644
--- a/include/hpp/fcl/mesh_loader/assimp.h
+++ b/include/hpp/fcl/mesh_loader/assimp.h
@@ -37,30 +37,18 @@
 #ifndef HPP_FCL_MESH_LOADER_ASSIMP_H
 #define HPP_FCL_MESH_LOADER_ASSIMP_H
 
-#ifdef HPP_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES
-  #include <assimp/DefaultLogger.hpp>
-  #include <assimp/IOStream.hpp>
-  #include <assimp/IOSystem.hpp>
-  #include <assimp/scene.h>
-  #include <assimp/Importer.hpp>
-  #include <assimp/postprocess.h>
-#else
-  #include <assimp/DefaultLogger.h>
-  #include <assimp/assimp.hpp>
-  #include <assimp/IOStream.h>
-  #include <assimp/IOSystem.h>
-  #include <assimp/aiScene.h>
-  #include <assimp/aiPostProcess.h>
-#endif
-
 #include <hpp/fcl/BV/OBBRSS.h>
 #include <hpp/fcl/BVH/BVH_model.h>
 
+class aiScene;
+
 namespace hpp
 {
 namespace fcl
 {
   
+namespace internal
+{
 
 struct TriangleAndVertices
 {
@@ -68,6 +56,15 @@ struct TriangleAndVertices
   std::vector <fcl::Triangle> triangles_;
 };
 
+struct Loader {
+  Loader ();
+  ~Loader ();
+
+  void load (const std::string& resource_path);
+
+  aiScene* scene;
+};
+
 /**
  * @brief      Recursive procedure for building a mesh
  *
@@ -77,31 +74,26 @@ struct TriangleAndVertices
  * @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);
+void buildMesh (const fcl::Vec3f & scale,
+                const aiScene* scene,
+                unsigned vertices_offset,
+                TriangleAndVertices & tv);
 
 /**
  * @brief      Convert an assimp scene to a mesh
  *
- * @param[in]  name   File (ressource) transformed into an assimp scene in loa
  * @param[in]  scale  Scale to apply when reading the ressource
  * @param[in]  scene  Pointer to the assimp scene
  * @param[out] mesh  The mesh that must be built
  */
 template<class BoundingVolume>   
-inline void meshFromAssimpScene(const std::string & name,
+inline void meshFromAssimpScene(
                          const fcl::Vec3f & scale,
                          const aiScene* scene,
                          const boost::shared_ptr < BVHModel<BoundingVolume> > & mesh)
 {
   TriangleAndVertices tv;
   
-  if (!scene->HasMeshes())
-    throw std::invalid_argument (std::string ("No meshes found in file ")+name);
-  
   int res = mesh->beginModel ();
   
   if (res != fcl::BVH_OK)
@@ -111,13 +103,14 @@ inline void meshFromAssimpScene(const std::string & name,
     throw std::runtime_error (error.str ());
   }
     
-  buildMesh (scale, scene, scene->mRootNode, 
-      (unsigned) mesh->num_vertices, tv);
+  buildMesh (scale, scene, (unsigned) mesh->num_vertices, tv);
   mesh->addSubModel (tv.vertices_, tv.triangles_);
     
   mesh->endModel ();
 }
 
+} // namespace internal
+
 /**
  * @brief      Read a mesh file and convert it to a polyhedral mesh
  *
@@ -130,46 +123,13 @@ inline void loadPolyhedronFromResource (const std::string & resource_path,
                                  const fcl::Vec3f & scale,
                                  const boost::shared_ptr < BVHModel<BoundingVolume> > & polyhedron)
 {
-  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
-      );
-
-  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)
-  {
-    const std::string exception_message (std::string ("Could not load resource ") + resource_path + std::string("\n") +
-                                         importer.GetErrorString () + std::string("\n") +
-                                         "Hint: the mesh directory may be wrong.");
-    throw std::invalid_argument(exception_message);
-  }
-  
-  meshFromAssimpScene (resource_path, scale, scene, polyhedron);
-}
+  internal::Loader scene;
+  scene.load (resource_path);
 
+  internal::meshFromAssimpScene (scale, scene.scene, polyhedron);
 }
 
+} // namespace fcl
 } // namespace hpp
 
-#endif // FCL_MESH_LOADER_ASSIMP_H
+#endif // HPP_FCL_MESH_LOADER_ASSIMP_H
diff --git a/src/BVH/BVH_model.cpp b/src/BVH/BVH_model.cpp
index 58ab55200a01cdbc29b3fc03ff554a8264ca1316..7fabab7b61ed40161b12597878c6ff0b8cd7053f 100644
--- a/src/BVH/BVH_model.cpp
+++ b/src/BVH/BVH_model.cpp
@@ -47,7 +47,6 @@ namespace fcl
 
 template<typename BV>
 BVHModel<BV>::BVHModel(const BVHModel<BV>& other) : CollisionGeometry(other),
-                                                    boost::noncopyable(),
                                                     num_tris(other.num_tris),
                                                     num_vertices(other.num_vertices),
                                                     build_state(other.build_state),
diff --git a/src/mesh_loader/assimp.cpp b/src/mesh_loader/assimp.cpp
index 7e58853a73f8bdf86b1202e1e08b62cb933f3ca8..26d157d8c876bb309b131430209f47442a73f6c2 100644
--- a/src/mesh_loader/assimp.cpp
+++ b/src/mesh_loader/assimp.cpp
@@ -34,16 +34,94 @@
 
 #include <hpp/fcl/mesh_loader/assimp.h>
 
+#ifdef HPP_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES
+  #include <assimp/DefaultLogger.hpp>
+  #include <assimp/IOStream.hpp>
+  #include <assimp/IOSystem.hpp>
+  #include <assimp/Importer.hpp>
+  #include <assimp/postprocess.h>
+  #include <assimp/scene.h>
+#else
+  #include <assimp/DefaultLogger.h>
+  #include <assimp/assimp.hpp>
+  #include <assimp/IOStream.h>
+  #include <assimp/IOSystem.h>
+  #include <assimp/aiPostProcess.h>
+  #include <assimp/aiScene.h>
+#endif
+
 namespace hpp
 {
 namespace fcl
 {
   
-unsigned buildMesh (const fcl::Vec3f & scale,
-                    const aiScene* scene,
-                    const aiNode* node,
-                    unsigned vertices_offset,
-                    TriangleAndVertices & tv)
+namespace internal
+{
+
+Loader::Loader () : scene (NULL) {}
+
+Loader::~Loader ()
+{
+ if (scene) delete scene;
+}
+
+void Loader::load (const std::string & resource_path)
+{
+  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
+      );
+
+  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
+      );
+
+  scene = importer.GetOrphanedScene();
+  if (!scene)
+  {
+    const std::string exception_message (std::string ("Could not load resource ") + resource_path + std::string("\n") +
+                                         importer.GetErrorString () + std::string("\n") +
+                                         "Hint: the mesh directory may be wrong.");
+    throw std::invalid_argument(exception_message);
+  }
+
+  if (!scene->HasMeshes())
+    throw std::invalid_argument (std::string ("No meshes found in file ")+resource_path);
+}
+
+/**
+ * @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 recurseBuildMesh (
+    const fcl::Vec3f & scale,
+    const aiScene* scene,
+    const aiNode* node,
+    unsigned vertices_offset,
+    TriangleAndVertices & tv)
 {
   if (!node) return 0;
   
@@ -100,12 +178,20 @@ unsigned buildMesh (const fcl::Vec3f & scale,
   
   for (uint32_t i=0; i < node->mNumChildren; ++i)
   {
-    nbVertices += buildMesh(scale, scene, node->mChildren[i], nbVertices, tv);
+    nbVertices += recurseBuildMesh(scale, scene, node->mChildren[i], nbVertices, tv);
   }
 
   return nbVertices;
 }
 
+void buildMesh (const fcl::Vec3f & scale,
+                    const aiScene* scene,
+                    unsigned vertices_offset,
+                    TriangleAndVertices & tv)
+{
+  recurseBuildMesh (scale, scene, scene->mRootNode, vertices_offset, tv);
 }
 
+} // namespace internal
+} // namespace fcl
 } // namespace hpp
diff --git a/test/test_fcl_collision.cpp b/test/test_fcl_collision.cpp
index 2330248b60a98519ab5afbb4562c78d7aae75562..6b9f29c92501b3900f799dcd519bceb9de53e646 100644
--- a/test/test_fcl_collision.cpp
+++ b/test/test_fcl_collision.cpp
@@ -918,7 +918,7 @@ bool collide_Test(const Transform3f& tf,
   MeshCollisionTraversalNode<BV> node (request);
 
   bool success = initialize <BV> (node, m1, pose1, m2, pose2, local_result);
-  assert (success);
+  BOOST_REQUIRE (success);
 
   node.enable_statistics = verbose;