35 #if !(__cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600)) 43 #include <assimp/defs.h> 44 #if !(__cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600)) && \ 50 #include <assimp/DefaultLogger.hpp> 51 #include <assimp/IOStream.hpp> 52 #include <assimp/IOSystem.hpp> 53 #include <assimp/Importer.hpp> 54 #include <assimp/postprocess.h> 55 #include <assimp/scene.h> 65 AI_CONFIG_PP_RVC_FLAGS,
66 aiComponent_TANGENTS_AND_BITANGENTS | aiComponent_COLORS |
67 aiComponent_BONEWEIGHTS | aiComponent_ANIMATIONS |
68 aiComponent_LIGHTS | aiComponent_CAMERAS | aiComponent_TEXTURES |
69 aiComponent_TEXCOORDS | aiComponent_MATERIALS | aiComponent_NORMALS);
72 importer->SetPropertyInteger(AI_CONFIG_PP_SBP_REMOVE,
73 aiPrimitiveType_LINE | aiPrimitiveType_POINT);
82 resource_path.c_str(),
83 aiProcess_SortByPType | aiProcess_Triangulate |
84 aiProcess_RemoveComponent | aiProcess_ImproveCacheLocality |
85 aiProcess_FindDegenerates | aiProcess_JoinIdenticalVertices);
88 const std::string exception_message(
89 std::string(
"Could not load resource ") + resource_path +
90 std::string(
"\n") +
importer->GetErrorString() + std::string(
"\n") +
91 "Hint: the mesh directory may be wrong.");
92 throw std::invalid_argument(exception_message);
95 if (!
scene->HasMeshes())
96 throw std::invalid_argument(std::string(
"No meshes found in file ") +
110 const aiNode* node,
unsigned vertices_offset,
114 aiMatrix4x4
transform = node->mTransformation;
115 aiNode* pnode = node->mParent;
119 if (pnode->mParent != NULL) {
120 transform = pnode->mTransformation *
transform;
122 pnode = pnode->mParent;
125 unsigned nbVertices = 0;
126 for (uint32_t i = 0; i < node->mNumMeshes; i++) {
127 aiMesh* input_mesh = scene->mMeshes[node->mMeshes[i]];
130 for (uint32_t j = 0; j < input_mesh->mNumVertices; j++) {
131 aiVector3D p = input_mesh->mVertices[j];
134 fcl::Vec3f(p.x * scale[0], p.y * scale[1], p.z * scale[2]));
138 for (uint32_t j = 0; j < input_mesh->mNumFaces; j++) {
139 aiFace& face = input_mesh->mFaces[j];
140 assert(face.mNumIndices == 3 &&
"The size of the face is not valid.");
143 vertices_offset + face.mIndices[1],
144 vertices_offset + face.mIndices[2]));
147 nbVertices += input_mesh->mNumVertices;
150 for (uint32_t i = 0; i < node->mNumChildren; ++i) {
HPP_FCL_DLLAPI void buildMesh(const fcl::Vec3f &scale, const aiScene *scene, unsigned vertices_offset, TriangleAndVertices &tv)
Recursive procedure for building a mesh.
std::vector< fcl::Triangle > triangles_
Triangle with 3 indices for points.
std::vector< fcl::Vec3f > vertices_
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
unsigned recurseBuildMesh(const fcl::Vec3f &scale, const aiScene *scene, const aiNode *node, unsigned vertices_offset, TriangleAndVertices &tv)
Recursive procedure for building a mesh.
HPP_FCL_DLLAPI Halfspace transform(const Halfspace &a, const Transform3f &tf)
void load(const std::string &resource_path)
Assimp::Importer * importer