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> 
   64       AI_CONFIG_PP_RVC_FLAGS,
 
   65       aiComponent_TANGENTS_AND_BITANGENTS | aiComponent_COLORS |
 
   66           aiComponent_BONEWEIGHTS | aiComponent_ANIMATIONS |
 
   67           aiComponent_LIGHTS | aiComponent_CAMERAS | aiComponent_TEXTURES |
 
   68           aiComponent_TEXCOORDS | aiComponent_MATERIALS | aiComponent_NORMALS);
 
   71   importer->SetPropertyInteger(AI_CONFIG_PP_SBP_REMOVE,
 
   72                                aiPrimitiveType_LINE | aiPrimitiveType_POINT);
 
   81       resource_path.c_str(),
 
   82       aiProcess_SortByPType | aiProcess_Triangulate |
 
   83           aiProcess_RemoveComponent | aiProcess_ImproveCacheLocality |
 
   84           aiProcess_FindDegenerates | aiProcess_JoinIdenticalVertices);
 
   87     const std::string exception_message(
 
   88         std::string(
"Could not load resource ") + resource_path +
 
   89         std::string(
"\n") + 
importer->GetErrorString() + std::string(
"\n") +
 
   90         "Hint: the mesh directory may be wrong.");
 
   94   if (!
scene->HasMeshes())
 
   96         (std::string(
"No meshes found in file ") + resource_path).c_str(),
 
   97         std::invalid_argument);
 
  110                           const aiNode* node, 
unsigned vertices_offset,
 
  114   aiMatrix4x4 
transform = node->mTransformation;
 
  115   aiNode* pnode = node->mParent;
 
  119     if (pnode->mParent != NULL) {
 
  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           coal::Vec3s(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) {