Commit 8391132f authored by Joseph Mirabel's avatar Joseph Mirabel
Browse files

Hide Assimp configuration + code cleaning.

parent 12e5357c
...@@ -97,10 +97,8 @@ ADD_REQUIRED_DEPENDENCY("assimp >= 2.0") ...@@ -97,10 +97,8 @@ ADD_REQUIRED_DEPENDENCY("assimp >= 2.0")
if(ASSIMP_FOUND) if(ASSIMP_FOUND)
if (NOT ${ASSIMP_VERSION} VERSION_LESS "2.0.1150") if (NOT ${ASSIMP_VERSION} VERSION_LESS "2.0.1150")
add_definitions(-DHPP_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES) 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") message(STATUS "Assimp version has unified headers")
else() else()
SET(HPP_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES FALSE)
message(STATUS "Assimp version does not have unified headers") message(STATUS "Assimp version does not have unified headers")
endif() endif()
endif() endif()
...@@ -161,10 +159,6 @@ endif () ...@@ -161,10 +159,6 @@ endif ()
pkg_config_append_libs("hpp-fcl") pkg_config_append_libs("hpp-fcl")
PKG_CONFIG_APPEND_BOOST_LIBS(thread date_time filesystem system) 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) IF(HPP_FCL_HAVE_OCTOMAP)
# FCL_HAVE_OCTOMAP kept for backward compatibility reasons. # FCL_HAVE_OCTOMAP kept for backward compatibility reasons.
PKG_CONFIG_APPEND_CFLAGS( PKG_CONFIG_APPEND_CFLAGS(
......
...@@ -54,8 +54,7 @@ namespace fcl ...@@ -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) /// @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> template<typename BV>
class BVHModel : public CollisionGeometry, class BVHModel : public CollisionGeometry
private boost::noncopyable
{ {
public: public:
......
...@@ -37,6 +37,8 @@ ...@@ -37,6 +37,8 @@
#ifndef HPP_FCL_FWD_HH #ifndef HPP_FCL_FWD_HH
#define HPP_FCL_FWD_HH #define HPP_FCL_FWD_HH
#include <boost/shared_ptr.hpp>
namespace hpp { namespace hpp {
namespace fcl { namespace fcl {
class CollisionObject; class CollisionObject;
......
...@@ -37,30 +37,18 @@ ...@@ -37,30 +37,18 @@
#ifndef HPP_FCL_MESH_LOADER_ASSIMP_H #ifndef HPP_FCL_MESH_LOADER_ASSIMP_H
#define 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/BV/OBBRSS.h>
#include <hpp/fcl/BVH/BVH_model.h> #include <hpp/fcl/BVH/BVH_model.h>
class aiScene;
namespace hpp namespace hpp
{ {
namespace fcl namespace fcl
{ {
namespace internal
{
struct TriangleAndVertices struct TriangleAndVertices
{ {
...@@ -68,6 +56,15 @@ struct TriangleAndVertices ...@@ -68,6 +56,15 @@ struct TriangleAndVertices
std::vector <fcl::Triangle> triangles_; 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 * @brief Recursive procedure for building a mesh
* *
...@@ -77,31 +74,26 @@ struct TriangleAndVertices ...@@ -77,31 +74,26 @@ struct TriangleAndVertices
* @param[in] vertices_offset Current number of vertices in the model * @param[in] vertices_offset Current number of vertices in the model
* @param tv Triangles and Vertices of the mesh submodels * @param tv Triangles and Vertices of the mesh submodels
*/ */
unsigned buildMesh (const fcl::Vec3f & scale, void buildMesh (const fcl::Vec3f & scale,
const aiScene* scene, const aiScene* scene,
const aiNode* node, unsigned vertices_offset,
unsigned vertices_offset, TriangleAndVertices & tv);
TriangleAndVertices & tv);
/** /**
* @brief Convert an assimp scene to a mesh * @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] scale Scale to apply when reading the ressource
* @param[in] scene Pointer to the assimp scene * @param[in] scene Pointer to the assimp scene
* @param[out] mesh The mesh that must be built * @param[out] mesh The mesh that must be built
*/ */
template<class BoundingVolume> template<class BoundingVolume>
inline void meshFromAssimpScene(const std::string & name, inline void meshFromAssimpScene(
const fcl::Vec3f & scale, const fcl::Vec3f & scale,
const aiScene* scene, const aiScene* scene,
const boost::shared_ptr < BVHModel<BoundingVolume> > & mesh) const boost::shared_ptr < BVHModel<BoundingVolume> > & mesh)
{ {
TriangleAndVertices tv; TriangleAndVertices tv;
if (!scene->HasMeshes())
throw std::invalid_argument (std::string ("No meshes found in file ")+name);
int res = mesh->beginModel (); int res = mesh->beginModel ();
if (res != fcl::BVH_OK) if (res != fcl::BVH_OK)
...@@ -111,13 +103,14 @@ inline void meshFromAssimpScene(const std::string & name, ...@@ -111,13 +103,14 @@ inline void meshFromAssimpScene(const std::string & name,
throw std::runtime_error (error.str ()); throw std::runtime_error (error.str ());
} }
buildMesh (scale, scene, scene->mRootNode, buildMesh (scale, scene, (unsigned) mesh->num_vertices, tv);
(unsigned) mesh->num_vertices, tv);
mesh->addSubModel (tv.vertices_, tv.triangles_); mesh->addSubModel (tv.vertices_, tv.triangles_);
mesh->endModel (); mesh->endModel ();
} }
} // namespace internal
/** /**
* @brief Read a mesh file and convert it to a polyhedral mesh * @brief Read a mesh file and convert it to a polyhedral mesh
* *
...@@ -130,46 +123,13 @@ inline void loadPolyhedronFromResource (const std::string & resource_path, ...@@ -130,46 +123,13 @@ inline void loadPolyhedronFromResource (const std::string & resource_path,
const fcl::Vec3f & scale, const fcl::Vec3f & scale,
const boost::shared_ptr < BVHModel<BoundingVolume> > & polyhedron) const boost::shared_ptr < BVHModel<BoundingVolume> > & polyhedron)
{ {
Assimp::Importer importer; internal::Loader scene;
// set list of ignored parameters (parameters used for rendering) scene.load (resource_path);
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::meshFromAssimpScene (scale, scene.scene, polyhedron);
} }
} // namespace fcl
} // namespace hpp } // namespace hpp
#endif // FCL_MESH_LOADER_ASSIMP_H #endif // HPP_FCL_MESH_LOADER_ASSIMP_H
...@@ -47,7 +47,6 @@ namespace fcl ...@@ -47,7 +47,6 @@ namespace fcl
template<typename BV> template<typename BV>
BVHModel<BV>::BVHModel(const BVHModel<BV>& other) : CollisionGeometry(other), BVHModel<BV>::BVHModel(const BVHModel<BV>& other) : CollisionGeometry(other),
boost::noncopyable(),
num_tris(other.num_tris), num_tris(other.num_tris),
num_vertices(other.num_vertices), num_vertices(other.num_vertices),
build_state(other.build_state), build_state(other.build_state),
......
...@@ -34,16 +34,94 @@ ...@@ -34,16 +34,94 @@
#include <hpp/fcl/mesh_loader/assimp.h> #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 hpp
{ {
namespace fcl namespace fcl
{ {
unsigned buildMesh (const fcl::Vec3f & scale, namespace internal
const aiScene* scene, {
const aiNode* node,
unsigned vertices_offset, Loader::Loader () : scene (NULL) {}
TriangleAndVertices & tv)
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; if (!node) return 0;
...@@ -100,12 +178,20 @@ unsigned buildMesh (const fcl::Vec3f & scale, ...@@ -100,12 +178,20 @@ unsigned buildMesh (const fcl::Vec3f & scale,
for (uint32_t i=0; i < node->mNumChildren; ++i) 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; 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 } // namespace hpp
...@@ -918,7 +918,7 @@ bool collide_Test(const Transform3f& tf, ...@@ -918,7 +918,7 @@ bool collide_Test(const Transform3f& tf,
MeshCollisionTraversalNode<BV> node (request); MeshCollisionTraversalNode<BV> node (request);
bool success = initialize <BV> (node, m1, pose1, m2, pose2, local_result); bool success = initialize <BV> (node, m1, pose1, m2, pose2, local_result);
assert (success); BOOST_REQUIRE (success);
node.enable_statistics = verbose; node.enable_statistics = verbose;
......
Supports Markdown
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment