eus_assimp.cpp
Go to the documentation of this file.
00001 #if 0
00002 // assimp 2
00003 #include <assimp/assimp.hpp>
00004 #include <assimp/aiScene.h>
00005 #include <assimp/aiPostProcess.h>
00006 #endif
00007 
00008 // assimp 3
00009 #include <assimp3/Importer.hpp>
00010 #include <assimp3/Exporter.hpp>
00011 #include <assimp3/postprocess.h>
00012 #include <assimp3/scene.h>
00013 
00014 // convex decomposition
00015 //#include "NvConvexDecomposition.h"
00016 
00017 #include <stdio.h>
00018 #include <stdlib.h>
00019 #include <unistd.h>
00020 #include <string.h>
00021 #include <signal.h>
00022 #include <math.h>
00023 #include <time.h>
00024 #include <pthread.h>
00025 #include <setjmp.h>
00026 #include <errno.h>
00027 
00028 #include <list>
00029 #include <vector>
00030 #include <set>
00031 #include <string>
00032 #include <map>
00033 #include <sstream>
00034 #include <cstdio>
00035 #include <iostream>
00036 
00037 // for eus.h
00038 #define class   eus_class
00039 #define throw   eus_throw
00040 #define export  eus_export
00041 #define vector  eus_vector
00042 #define string  eus_string
00043 #define iostream eus_iostream
00044 #define complex  eus_complex
00045 
00046 #include "eus.h"
00047 extern "C" {
00048   pointer ___eus_assimp(register context *ctx, int n, pointer *argv, pointer env);
00049   void register_eus_assimp(){
00050     char modname[] = "___eus_assimp";
00051     return add_module_initializer(modname, (pointer (*)())___eus_assimp);}
00052 }
00053 
00054 #undef class
00055 #undef throw
00056 #undef export
00057 #undef vector
00058 #undef string
00059 #undef iostream
00060 #undef complex
00061 
00062 #define SIZE_T_MAX (std::numeric_limits<size_t>::max())
00063 
00064 static pointer K_VERTICES, K_NORMALS, K_INDICES, K_TYPE, K_MATERIAL;
00065 static pointer K_LINES, K_TRIANGLES, K_QUADS, K_POLYGON, K_NAME;
00066 static pointer K_AMBIENT, K_DIFFUSE, K_SPECULAR, K_EMISSION, K_SHININESS, K_TRANSPARENCY;
00067 
00068 static std::string primitiveType (unsigned int tp) {
00069  switch (tp) {
00070  case aiPrimitiveType_POINT:
00071    return "POINT";
00072    break;
00073  case aiPrimitiveType_LINE:
00074    return "LINE";
00075    break;
00076  case aiPrimitiveType_TRIANGLE:
00077    return "TRIANGLE";
00078    break;
00079  case aiPrimitiveType_POLYGON:
00080    return "POLYGON";
00081    break;
00082  }
00083  return "NO_TYPE";
00084 }
00085 
00086 static void printMesh(aiMesh *mesh, std::string prefix)
00087 {
00088   std::string name;
00089   name.assign(  mesh->mName.data, mesh->mName.length );
00090 
00091   std::cerr << ";;" << prefix << " Mesh name: " << name << std::endl;
00092 
00093   std::cerr << ";;" << prefix << "   Bones: " << mesh->mNumBones << std::endl;
00094   std::cerr << ";;" << prefix << "   Faces: " << mesh->mNumFaces << std::endl;
00095   std::cerr << ";;" << prefix << "   Vertices: " << mesh->mNumVertices << std::endl;
00096   std::cerr << ";;" << prefix << "   PType: " << primitiveType( mesh->mPrimitiveTypes ) << std::endl;
00097   std::cerr << ";;" << prefix << "   MaterialIndex: " << mesh->mMaterialIndex << std::endl;
00098 }
00099 
00100 static void printTransform(aiMatrix4x4 &transform, std::string prefix) {
00101   std::cerr << prefix << "  trans: " << transform.a1 << " " << transform.a2 << " " << transform.a3 << " " << transform.a4 << std::endl;
00102   std::cerr << prefix << "         " << transform.b1 << " " << transform.b2 << " " << transform.b3 << " " << transform.b4 << std::endl;
00103   std::cerr << prefix << "         " << transform.c1 << " " << transform.c2 << " " << transform.c3 << " " << transform.c4 << std::endl;
00104   std::cerr << prefix << "         " << transform.d1 << " " << transform.d2 << " " << transform.d3 << " " << transform.d4 << std::endl;
00105 }
00106 
00107 static void printNode(aiNode *node, std::string prefix)
00108 {
00109   std::string name;
00110   name.assign (node->mName.C_Str());
00111 
00112   fprintf (stderr,"%s Node name(%lX): %s", prefix.c_str(), (void *)node, name.c_str());
00113   std::cerr << std::endl;
00114   std::cerr << prefix << "    Meshes: " << node->mNumMeshes << " / ";
00115   for (unsigned int i = 0; i < node->mNumMeshes; i++ ) {
00116     std::cerr << " " << node->mMeshes[i];
00117   }
00118   std::cerr << std::endl;
00119   printTransform(node->mTransformation, prefix);
00120 
00121   std::cerr << prefix << "   Children: " << node->mNumChildren << std::endl;
00122   for (unsigned int i = 0; i < node->mNumChildren; i++ ) {
00123     printNode(node->mChildren[i], prefix + "  ");
00124   }
00125 }
00126 
00127 static void printMaterial(aiMaterial *material, unsigned int idx)
00128 {
00129   std::cerr << ";;  material: " << idx << std::endl;
00130 
00131   //float col[4];
00132   //aiReturn ret = material->Get(AI_MATKEY_COLOR_DIFFUSE, col, NULL);
00133   //std::cerr << "color : " << ret << " " << col[0] << " " << col[1] << " " << col[2] << " " << col[3];
00134 
00135   for ( unsigned int i = 0; i < material->mNumProperties; i++ ) {
00136     aiMaterialProperty *mp = material->mProperties[i];
00137     std::string kname;
00138     kname.assign(  mp->mKey.data, mp->mKey.length );
00139     std::cerr << ";;    " << kname << std::endl;
00140   }
00141 }
00142 
00143 static pointer store_mesh_info (register context *ctx, eusfloat_t base_scl,
00144                                 const aiScene *scene, const aiNode *node, const aiMesh *amesh,
00145                                 const aiMatrix4x4 &trans) {
00146   static int mesh_cntr = -1;
00147   pointer ver_mat, nom_mat, indices;
00148   eusfloat_t *ver_vec=NULL, *nom_vec=NULL;
00149   numunion nu;
00150   pointer ret = NIL;
00151   int npc = 0;
00152 
00153   mesh_cntr++;
00154   // name
00155   {
00156     std::string nname, mname;
00157     nname.assign (node->mName.C_Str());
00158     mname.assign (amesh->mName.C_Str());
00159 
00160     if (nname.empty() && mname.empty()) {
00161       nname = "eusglvertices_" + mesh_cntr;
00162     } else {
00163       nname = nname + "_" + mname;
00164     }
00165     pointer lname = makestring ((char *)nname.c_str(), nname.length());
00166     vpush (lname);
00167     lname = rawcons (ctx, lname , NIL);
00168     vpop (); vpush (lname);
00169     lname = rawcons (ctx, K_NAME, lname);
00170     vpop (); vpush (lname);
00171     ret = rawcons (ctx, lname, ret);
00172     vpop ();
00173     vpush (ret); npc++;
00174   }
00175 
00176   // type
00177   {
00178     pointer ltype = NIL;
00179     switch (amesh->mPrimitiveTypes) {
00180     case aiPrimitiveType_LINE:
00181       ltype = K_LINES;
00182       break;
00183     case aiPrimitiveType_TRIANGLE:
00184       ltype = K_TRIANGLES;
00185       break;
00186     case aiPrimitiveType_POLYGON:
00187       ltype = K_POLYGON;
00188       break;
00189     }
00190     ltype = rawcons (ctx, ltype , NIL);
00191     vpush (ltype);
00192     ltype = rawcons (ctx, K_TYPE, ltype);
00193     vpop(); vpush (ltype);
00194     ret = rawcons (ctx, ltype, ret);
00195     vpop();
00196     vpush (ret); npc++;
00197   }
00198 
00199   // material
00200   {
00201     pointer lmaterial = NIL;
00202     aiMaterial *am = scene->mMaterials[amesh->mMaterialIndex];
00203 #if DEBUG
00204     std::cerr << ";; material properties: " << am->mNumProperties << std::endl;
00205 #endif
00206     aiReturn ar;
00207     aiString s;
00208     aiColor4D clr4d( 0.0, 0.0, 0.0, 0.0);
00209     float val;
00210     int lpc = 0;
00211     ar = am->Get (AI_MATKEY_NAME, s);
00212     if (ar == aiReturn_SUCCESS) {
00213       std::string str; str.assign(s.C_Str());
00214 #if DEBUG
00215       std::cerr << ";; material properties: name: " << str << std::endl;
00216 #endif
00217       pointer pelem;
00218       pointer eusstr = makestring (s.data, strlen(s.data));
00219       vpush (eusstr);//
00220       pelem = rawcons (ctx, eusstr, NIL);
00221       vpush (pelem);//
00222       pelem = rawcons (ctx, K_NAME, pelem);
00223       vpush (pelem);//
00224       lmaterial = rawcons (ctx, pelem, lmaterial);
00225       vpop(); vpop(); vpop();
00226       vpush (lmaterial); lpc++;
00227     }
00228     ar = am->Get (AI_MATKEY_COLOR_AMBIENT, clr4d);
00229     if (ar == aiReturn_SUCCESS) {
00230 #if DEBUG
00231       std::cerr << ";; material properties: AMBIENT: ";
00232       std::cerr << clr4d[0] << " " << clr4d[1] << " " << clr4d[2] << " " << clr4d[3] << std::endl;
00233 #endif
00234       pointer pelem = makefvector (4);
00235       pelem->c.fvec.fv[0] = clr4d[0]; pelem->c.fvec.fv[1] = clr4d[1];
00236       pelem->c.fvec.fv[2] = clr4d[2]; pelem->c.fvec.fv[3] = clr4d[3];
00237       vpush (pelem);//
00238       pelem = rawcons (ctx, pelem, NIL);
00239       vpush (pelem);//
00240       pelem = rawcons (ctx, K_AMBIENT, pelem);
00241       vpush (pelem);//
00242       lmaterial = rawcons (ctx, pelem, lmaterial);
00243       vpop(); vpop(); vpop();
00244       vpush (lmaterial); lpc++;
00245     }
00246     ar = am->Get (AI_MATKEY_COLOR_DIFFUSE, clr4d);
00247     if (ar == aiReturn_SUCCESS) {
00248 #if DEBUG
00249       std::cerr << ";; material properties: DIFFUSE: ";
00250       std::cerr << clr4d[0] << " " << clr4d[1] << " " << clr4d[2] << " " << clr4d[3] << std::endl;
00251 #endif
00252       pointer pelem = makefvector (4);
00253       pelem->c.fvec.fv[0] = clr4d[0]; pelem->c.fvec.fv[1] = clr4d[1];
00254       pelem->c.fvec.fv[2] = clr4d[2]; pelem->c.fvec.fv[3] = clr4d[3];
00255       vpush (pelem);//
00256       pelem = rawcons (ctx, pelem, NIL);
00257       vpush (pelem);//
00258       pelem = rawcons (ctx, K_DIFFUSE, pelem);
00259       vpush (pelem);//
00260       lmaterial = rawcons (ctx, pelem, lmaterial);
00261       vpop(); vpop(); vpop();
00262       vpush (lmaterial); lpc++;
00263     }
00264     ar = am->Get (AI_MATKEY_COLOR_SPECULAR, clr4d);
00265     if (ar == aiReturn_SUCCESS) {
00266 #if DEBUG
00267       std::cerr << ";; material properties: SPECULAR: ";
00268       std::cerr << clr4d[0] << " " << clr4d[1] << " " << clr4d[2] << " " << clr4d[3] << std::endl;
00269 #endif
00270       pointer pelem = makefvector (4);
00271       pelem->c.fvec.fv[0] = clr4d[0]; pelem->c.fvec.fv[1] = clr4d[1];
00272       pelem->c.fvec.fv[2] = clr4d[2]; pelem->c.fvec.fv[3] = clr4d[3];
00273       vpush (pelem);//
00274       pelem = rawcons (ctx, pelem, NIL);
00275       vpush (pelem);//
00276       pelem = rawcons (ctx, K_SPECULAR, pelem);
00277       vpush (pelem);//
00278       lmaterial = rawcons (ctx, pelem, lmaterial);
00279       vpop(); vpop(); vpop();
00280       vpush (lmaterial); lpc++;
00281     }
00282     ar = am->Get (AI_MATKEY_COLOR_EMISSIVE, clr4d);
00283     if (ar == aiReturn_SUCCESS) {
00284 #if DEBUG
00285       std::cerr << ";; material properties: EMISSIVE: ";
00286       std::cerr << clr4d[0] << " " << clr4d[1] << " " << clr4d[2] << " " << clr4d[3] << std::endl;
00287 #endif
00288       pointer pelem = makefvector (4);
00289       pelem->c.fvec.fv[0] = clr4d[0]; pelem->c.fvec.fv[1] = clr4d[1];
00290       pelem->c.fvec.fv[2] = clr4d[2]; pelem->c.fvec.fv[3] = clr4d[3];
00291       vpush (pelem);//
00292       pelem = rawcons (ctx, pelem, NIL);
00293       vpush (pelem);//
00294       pelem = rawcons (ctx, K_EMISSION, pelem);
00295       vpush (pelem);//
00296       lmaterial = rawcons (ctx, pelem, lmaterial);
00297       vpop(); vpop(); vpop();
00298       vpush (lmaterial); lpc++;
00299     }
00300     ar = am->Get (AI_MATKEY_SHININESS, val);
00301     if (ar == aiReturn_SUCCESS) {
00302 #if DEBUG
00303       std::cerr << ";; material properties: SHININESS: " << val << std::endl;
00304 #endif
00305       pointer pelem;
00306       pelem = rawcons (ctx, makeflt(val), NIL);
00307       vpush (pelem);//
00308       pelem = rawcons (ctx, K_SHININESS, pelem);
00309       vpush (pelem);//
00310       lmaterial = rawcons (ctx, pelem, lmaterial);
00311       vpop(); vpop();
00312       vpush (lmaterial); lpc++;
00313     }
00314 #if 0 // Do not use transparent??
00315     ar = am->Get (AI_MATKEY_COLOR_TRANSPARENT, clr4d);
00316     if (ar == aiReturn_SUCCESS) {
00317       std::cerr << ";; material properties: TRANSPARENT: ";
00318       std::cerr << clr4d[0] << " " << clr4d[1] << " " << clr4d[2] << " " << clr4d[3] << std::endl;
00319       pointer pelem = makefvector (4);
00320       pelem->c.fvec.fv[0] = clr4d[0]; pelem->c.fvec.fv[1] = clr4d[1];
00321       pelem->c.fvec.fv[2] = clr4d[2]; pelem->c.fvec.fv[3] = clr4d[3];
00322       vpush (pelem);//
00323       pelem = rawcons (ctx, pelem, NIL);
00324       vpush (pelem);//
00325       pelem = rawcons (ctx, K_TRANSPARENT, pelem);
00326       vpush (pelem);//
00327       lmaterial = rawcons (ctx, pelem, lmaterial);
00328       vpop(); vpop(); vpop();
00329       vpush (lmaterial); lpc++;
00330     }
00331 #endif
00332     pointer tmp = rawcons (ctx, lmaterial, NIL);
00333     vpush (tmp); lpc++;
00334     tmp = rawcons (ctx, K_MATERIAL, tmp);
00335     vpush (tmp); lpc++;
00336     ret = rawcons (ctx, tmp, ret);
00337     while(lpc-- > 0) vpop();
00338 
00339     vpush (ret); npc++;
00340   }
00341 
00342   if (!!amesh->mNormals) {
00343     nom_mat = makematrix (ctx, amesh->mNumVertices, 3); vpush (nom_mat); npc++;
00344     nom_vec = nom_mat->c.ary.entity->c.fvec.fv;
00345   }
00346   ver_mat = makematrix (ctx, amesh->mNumVertices, 3); vpush (ver_mat); npc++;
00347   ver_vec = ver_mat->c.ary.entity->c.fvec.fv;
00348 
00349   // count indices
00350   {
00351     int icount = 0;
00352     for (unsigned int f = 0; f < amesh->mNumFaces; f++) {
00353       icount += amesh->mFaces[f].mNumIndices;
00354     }
00355     indices = makevector (C_INTVECTOR, icount);
00356     vpush (indices); npc++;
00357   }
00358   // fill indices
00359   {
00360     eusinteger_t *vec = indices->c.ivec.iv;
00361     int icount = 0;
00362     for (unsigned int f = 0; f < amesh->mNumFaces; f++) {
00363       for(unsigned int p = 0; p < amesh->mFaces[f].mNumIndices; p++) {
00364         vec[icount++] = amesh->mFaces[f].mIndices[p];
00365       }
00366     }
00367   }
00368   // add indices to return list
00369   {
00370     pointer tmp;
00371     tmp = rawcons (ctx, indices, NIL);
00372     vpush (tmp);
00373     tmp = rawcons (ctx, K_INDICES, tmp);
00374     ret = rawcons (ctx, tmp, ret);
00375     vpop();
00376     vpush (ret); npc++;
00377   }
00378   // make vetices and normal matrix
00379   int vcount=0, ncount=0;
00380   for (unsigned int i = 0; i < amesh->mNumVertices; ++i) {
00381     aiQuaternion rot;
00382     aiVector3D   pos;
00383     trans.DecomposeNoScaling(rot, pos);
00384     aiVector3D tvec (amesh->mVertices[i]);
00385     tvec *= trans;
00386     tvec *= base_scl;
00387     ver_vec[vcount++] = tvec.x;
00388     ver_vec[vcount++] = tvec.y;
00389     ver_vec[vcount++] = tvec.z;
00390     if ( !!nom_vec ) {
00391       aiVector3D tnom = rot.Rotate (amesh->mNormals[i]);
00392       nom_vec[ncount++] = tnom.x;
00393       nom_vec[ncount++] = tnom.y;
00394       nom_vec[ncount++] = tnom.z;
00395     }
00396   }
00397   //
00398   if ( !!nom_vec ) {
00399     pointer tmp;
00400     tmp = rawcons (ctx, nom_mat , NIL);
00401     vpush (tmp);
00402     tmp = rawcons (ctx, K_NORMALS , tmp);
00403     ret = rawcons (ctx, tmp, ret);
00404     vpop();
00405     vpush (ret); npc++;
00406   }
00407   //
00408   {
00409     pointer tmp;
00410     tmp = rawcons (ctx, ver_mat , NIL);
00411     vpush (tmp);
00412     tmp = rawcons (ctx, K_VERTICES , tmp);
00413     ret = rawcons (ctx, tmp, ret);
00414     vpop();
00415     vpush (ret); npc++;
00416   }
00417 
00418   for (;npc > 0; npc--) vpop();
00419 
00420   return ret;
00421 }
00422 
00423 static void register_all_nodes (register context *ctx, eusfloat_t base_scl,
00424                                 const aiScene *scene, const aiNode *node,
00425                                 const aiMatrix4x4 &parent_world_trans,
00426                                 std::vector<pointer> &mesh_info) {
00427   aiMatrix4x4 node_world_trans = parent_world_trans * node->mTransformation;
00428 #if DEBUG
00429   fprintf (stderr, "node : %lX\n", (void *)node);
00430   printTransform (node_world_trans, "");
00431 #endif
00432   if (node->mNumMeshes > 0 && node->mMeshes != NULL) {
00433     for (unsigned int n = 0; n < node->mNumMeshes; n++) {
00434 #if DEBUG
00435       fprintf (stderr, " mesh: %d", node->mMeshes[n]);
00436 #endif
00437       aiMesh *am = scene->mMeshes[node->mMeshes[n]];
00438       std::cerr << ";; mesh = " << (void *)am << std::endl;
00439       pointer ret = store_mesh_info (ctx, base_scl, scene, node, am, node_world_trans);
00440       vpush (ret);
00441       mesh_info.push_back (ret);
00442     }
00443   }
00444 #if DEBUG
00445   fprintf(stderr, "\n");
00446   std::cerr << " children: " <<  node->mNumChildren << std::endl;
00447 #endif
00448   for (unsigned int c = 0; c < node->mNumChildren; c++) {
00449     register_all_nodes (ctx, base_scl,
00450                         scene, node->mChildren[c],
00451                         node_world_trans, mesh_info);
00452   }
00453 }
00454 
00455 pointer GET_MESHES(register context *ctx,int n,pointer *argv)
00456 {
00457   /* filename &optional scale (gen_normal nil) (smooth_normal nil) (split_large_mesh nil) (optimize_mesh nil) (identical_vert nil) (fix_normal nil) (dumpfilename) */
00458   eusfloat_t base_scl = 1.0;
00459   numunion nu;
00460 
00461   ckarg2(1, 9);
00462   if (!isstring(argv[0])) error (E_NOSTRING);
00463   if (n > 1) {
00464     base_scl = ckfltval (argv[1]);
00465   }
00466 
00467   Assimp::Importer importer;
00468   unsigned int post_proc = (aiProcess_Triangulate | aiProcess_SortByPType);
00469   bool recalc_normal = false;
00470   char *dumpfile = NULL;
00471 
00472   if (n > 2) {
00473     if (argv[2] != NIL) {
00474       post_proc |= (aiProcess_GenNormals | aiProcess_FindInvalidData);
00475       recalc_normal = true;
00476     }
00477   }
00478   if (n > 3) {
00479     if (argv[3] != NIL) {
00480       post_proc |= (aiProcess_GenSmoothNormals | aiProcess_FindInvalidData);
00481       recalc_normal = true;
00482     }
00483   }
00484   if (n > 4) {
00485     if (argv[4] != NIL) { post_proc |= aiProcess_SplitLargeMeshes; }
00486   }
00487   if (n > 5) {
00488     if (argv[5] != NIL) { post_proc |= aiProcess_OptimizeMeshes; }
00489   }
00490   if (n > 6) {
00491     if (argv[6] != NIL) { post_proc |= aiProcess_JoinIdenticalVertices; }
00492   }
00493   if (n > 7) {
00494     if (argv[7] != NIL) { post_proc |= aiProcess_FixInfacingNormals; }
00495   }
00496   if (n > 8) {
00497     if (argv[8] != NIL) {
00498       if (!isstring(argv[8])) error(E_NOSTRING);
00499       dumpfile = (char *)get_string(argv[8]);
00500     }
00501   }
00502   const aiScene* raw_scene = importer.ReadFile ((char *)get_string(argv[0]), 0);
00503 
00504   if (!raw_scene) {
00505     std::string str (importer.GetErrorString());
00506     std::cerr << ";; " << str << std::endl;
00507     return NIL;
00508   }
00509 #if DEBUG
00510   std::cerr << ";; Num meshes(raw): " << raw_scene->mNumMeshes << std::endl;
00511 #endif
00512   if (recalc_normal) {
00513 #if DEBUG
00514     std::cerr << ";; Recalc_normal" << std::endl;
00515 #endif
00516     for (unsigned int m = 0; m < raw_scene->mNumMeshes; m++) {
00517       aiMesh *a = raw_scene->mMeshes[m];
00518       if (!!a->mNormals) { a->mNormals = NULL; }
00519     }
00520   }
00521 
00522   const aiScene* scene = importer.ApplyPostProcessing (post_proc);
00523   if (!scene) {
00524     std::string str (importer.GetErrorString());
00525     std::cerr << ";; " << str << std::endl;
00526     return NIL;
00527   }
00528 #if DEBUG
00529   std::cerr << ";; Num meshes: " << scene->mNumMeshes << std::endl;
00530   // travarse nodes and store
00531   printNode (scene->mRootNode, ";;");
00532 #endif
00533 
00534   pointer lst = NIL;
00535   {
00536     aiMatrix4x4 world_trans;
00537     std::vector<pointer> mesh_info;
00538     register_all_nodes (ctx, base_scl, scene,
00539                         scene->mRootNode, world_trans, mesh_info);
00540 #if DEBUG
00541     std::cerr << ";; mesh size: " << mesh_info.size() << std::endl;
00542 #endif
00543     for (std::vector<pointer>::reverse_iterator rit = mesh_info.rbegin();
00544          rit != mesh_info.rend(); rit++) {
00545       vpush(lst);
00546       lst = rawcons (ctx, *rit, lst);
00547       vpop(); // vpop(); // pop for mesh_info
00548     }
00549     vpush (lst);
00550   }
00551 
00552   if (!!dumpfile) {
00553     std::string outf, outext;
00554     outf.assign (dumpfile);
00555     {
00556       const std::string::size_type s = outf.find_last_of('.');
00557       if (s != std::string::npos) {
00558         outext = outf.substr (s+1);
00559       } else {
00560         std::cerr << ";; Can not find extention: " << outf << std::endl;
00561       }
00562     }
00563     Assimp::Exporter exporter;
00564     size_t outfi = SIZE_T_MAX;
00565     for(size_t i = 0, end = exporter.GetExportFormatCount(); i < end; ++i) {
00566       const aiExportFormatDesc* const e = exporter.GetExportFormatDescription(i);
00567       if (outext == e->fileExtension) {
00568         outfi = i; break;
00569       }
00570     }
00571     if (outfi == SIZE_T_MAX) {
00572       outext = "stl";
00573       for(size_t i = 0, end = exporter.GetExportFormatCount(); i < end; ++i) {
00574         const aiExportFormatDesc* const e = exporter.GetExportFormatDescription(i);
00575         if (outext == e->fileExtension) {
00576           outfi = i; break;
00577         }
00578       }
00579     }
00580     if (outfi == SIZE_T_MAX) outfi = 0;
00581 
00582     const aiExportFormatDesc* const e = exporter.GetExportFormatDescription(outfi);
00583 #if DEBUG
00584     fprintf (stderr, ";; use file format: %s\n", e->id);
00585 #endif
00586     aiReturn ret = exporter.Export (scene, e->id, outf);
00587   }
00588 
00589   vpop(); // vpush (lst);
00590   return lst;
00591 }
00592 
00593 pointer DUMP_GL_VERTICES(register context *ctx,int n,pointer *argv)
00594 {
00595   /* filename type-list material-list vertices-list normals-list indices-list
00596      (scale) (gen_normal nil) (smooth_normal nil) (split_large_mesh nil)
00597      (optimize_mesh nil) (identical_vert nil) (fix_normal)
00598   */
00599   // FIXME: name_list
00600   ckarg2(6, 12);
00601   numunion nu;
00602 
00603   char *dumpfile = NULL;
00604   if (!isstring(argv[0])) error(E_NOSTRING);
00605   dumpfile = (char *)get_string(argv[0]);
00606 
00607   int list_len = 0;
00608   {
00609     pointer a = argv[1];
00610     while (islist(a)) {list_len++; a=ccdr(a);}
00611   }
00612   if (list_len <= 0) return NIL;
00613   bool has_materials = false;
00614   pointer ltype, linfo, lvertices, lnormals, lindices;
00615   pointer mtype, minfo, mvertices, mnormals, mindices;
00616   ltype = argv[1];
00617   linfo = argv[2];
00618   lvertices = argv[3];
00619   lnormals = argv[4];
00620   lindices = argv[5];
00621 
00622   // assimp loader
00623   aiScene *pScene = (aiScene *) malloc(sizeof (aiScene));
00624   memset((void *)pScene, 0, sizeof (aiScene));
00625   pScene->mPrivate = malloc(sizeof (void *) * 2);
00626   //printf("scene = %lX\n", (void *)pScene);
00627 
00628   pScene->mNumMeshes = list_len;
00629   pScene->mMeshes = new aiMesh*[list_len];
00630 
00631   // allocate a single node
00632   pScene->mRootNode = new aiNode();
00633   pScene->mRootNode->mNumMeshes = list_len;
00634   pScene->mRootNode->mMeshes = new unsigned int[list_len];
00635   pScene->mRootNode->mName.Set("eus_glvertices");
00636 
00637   if (linfo != NIL) {
00638     pScene->mNumMaterials = list_len;
00639     pScene->mMaterials = new aiMaterial*[list_len];
00640     has_materials = true;
00641   } else {
00642     pScene->mNumMaterials = 1;
00643     pScene->mMaterials = new aiMaterial*[1];
00644     has_materials = false;
00645     // make default material
00646     aiMaterial* pcMat = new aiMaterial();
00647     aiString s; s.Set (AI_DEFAULT_MATERIAL_NAME);
00648     pcMat->AddProperty (&s, AI_MATKEY_NAME);
00649     aiColor4D clrDiffuse(0.8f, 0.8f, 0.8f, 1.0f);
00650     pcMat->AddProperty (&clrDiffuse, 1, AI_MATKEY_COLOR_DIFFUSE);
00651     pcMat->AddProperty (&clrDiffuse, 1, AI_MATKEY_COLOR_SPECULAR);
00652     clrDiffuse = aiColor4D (0.2f, 0.2f, 0.2f, 1.0f);
00653     pcMat->AddProperty (&clrDiffuse, 1, AI_MATKEY_COLOR_AMBIENT);
00654 
00655     pScene->mMaterials[0] = pcMat;
00656   }
00657 
00658   for (int i = 0; i < list_len; i++) {
00659     mtype = ccar (ltype);
00660     minfo = ccar (linfo);
00661     mvertices = ccar (lvertices);
00662     mnormals = ccar (lnormals);
00663     mindices = ccar (lindices);
00664 
00665     ltype = ccdr (ltype);
00666     linfo = ccdr (linfo);
00667     lvertices = ccdr (lvertices);
00668     lnormals = ccdr (lnormals);
00669     lindices = ccdr (lindices);
00670 
00671     pScene->mRootNode->mMeshes[i] = i;
00672     aiMesh* pMesh = pScene->mMeshes[i] = new aiMesh();
00673     std::cerr << ";; mesh = " << (void *)pMesh << std::endl;
00674     if (!has_materials) {
00675       pMesh->mMaterialIndex = 0;
00676     } else {
00677       pMesh->mMaterialIndex = i;
00678       // material
00679       aiMaterial* pcMat = new aiMaterial();
00680       std::ostringstream oss;
00681       oss << "eusassimp_mat_" << i;
00682       aiString s; s.Set (oss.str());
00683       pcMat->AddProperty(&s, AI_MATKEY_NAME);
00684 
00685       for (int el = 0; el < 6; el++) {
00686         // (list :ambient :diffuse :specular :emission :shininess :transparency)
00687         pointer melem = ccar (minfo);
00688         minfo = ccdr (minfo);
00689         aiColor4D clr4d (0.0f, 0.0f, 0.0f, 1.0f);
00690         switch (el) {
00691         case 0:
00692           if (melem != NIL) {
00693             for(int j = 0; j < intval(melem->c.fvec.length); j++) {
00694               clr4d[j] = melem->c.fvec.fv[j];
00695             }
00696             //printf("%d: %f %f %f %f\n", el, clr4d[0], clr4d[1], clr4d[2], clr4d[3]);
00697             pcMat->AddProperty(&clr4d, 1, AI_MATKEY_COLOR_AMBIENT);
00698           }
00699           break;
00700         case 1:
00701           if (melem != NIL) {
00702             for(int j = 0; j < intval(melem->c.fvec.length); j++) {
00703               clr4d[j] = melem->c.fvec.fv[j];
00704             }
00705             //printf("%d: %f %f %f %f\n", el, clr4d[0], clr4d[1], clr4d[2], clr4d[3]);
00706             pcMat->AddProperty(&clr4d, 1, AI_MATKEY_COLOR_DIFFUSE);
00707           }
00708           break;
00709         case 2:
00710           if (melem != NIL) {
00711             for(int j = 0; j < intval(melem->c.fvec.length); j++) {
00712               clr4d[j] = melem->c.fvec.fv[j];
00713             }
00714             //printf("%d: %f %f %f %f\n", el, clr4d[0], clr4d[1], clr4d[2], clr4d[3]);
00715             pcMat->AddProperty(&clr4d, 1, AI_MATKEY_COLOR_SPECULAR);
00716           }
00717           break;
00718         case 3:
00719           if (melem != NIL) {
00720             for(int j = 0; j < intval(melem->c.fvec.length); j++) {
00721               clr4d[j] = melem->c.fvec.fv[j];
00722             }
00723             //printf("%d: %f %f %f %f\n", el, clr4d[0], clr4d[1], clr4d[2], clr4d[3]);
00724             pcMat->AddProperty(&clr4d, 1, AI_MATKEY_COLOR_EMISSIVE);
00725           }
00726           break;
00727         case 4:
00728           if (melem != NIL) {
00729             float val = fltval (melem);
00730             pcMat->AddProperty(&val, 1, AI_MATKEY_SHININESS);
00731           }
00732           break;
00733         case 5:
00734           if (melem != NIL) {
00735             if (isnum (melem)) {
00736               float val = isflt (melem) ? fltval (melem) : (float)intval (melem);
00737               //printf("trans: %f\n", val);
00738               for(int j = 0; j < 4; j++) {
00739                 clr4d[j] = val;
00740               }
00741             } else {
00742               for(int j = 0; j < intval(melem->c.fvec.length); j++) {
00743                 clr4d[j] = melem->c.fvec.fv[j];
00744               }
00745             }
00746             //printf("%d: %f %f %f %f\n", el, clr4d[0], clr4d[1], clr4d[2], clr4d[3]);
00747             pcMat->AddProperty(&clr4d, 1, AI_MATKEY_COLOR_TRANSPARENT);
00748           }
00749           break;
00750         }
00751       }
00752       pScene->mMaterials[i] = pcMat;
00753     }
00754     // vertices
00755     if (mvertices == NIL) { /* error */ }
00756     eusinteger_t size = intval (mvertices->c.ary.entity->c.fvec.length);
00757     eusfloat_t *fv = mvertices->c.ary.entity->c.fvec.fv;
00758     pMesh->mNumVertices = size / 3;
00759     pMesh->mVertices = new aiVector3D [pMesh->mNumVertices];
00760     for (unsigned int k = 0; k < pMesh->mNumVertices; k++) {
00761       pMesh->mVertices[k].x = *fv++;
00762       pMesh->mVertices[k].y = *fv++;
00763       pMesh->mVertices[k].z = *fv++;
00764     }
00765     // normals
00766     if (mnormals != NIL) {
00767       eusinteger_t size = intval (mnormals->c.ary.entity->c.fvec.length);
00768       eusfloat_t *fv = mnormals->c.ary.entity->c.fvec.fv;
00769       if (size / 3 != pMesh->mNumVertices) { /* error */ }
00770       pMesh->mNormals  = new aiVector3D [pMesh->mNumVertices];
00771       for (unsigned int k = 0; k < pMesh->mNumVertices; k++) {
00772         pMesh->mNormals[k].x = *fv++;
00773         pMesh->mNormals[k].y = *fv++;
00774         pMesh->mNormals[k].z = *fv++;
00775       }
00776     }
00777     unsigned int verts_per_face = intval(mtype);
00778     if (mindices != NIL) {
00779       if (verts_per_face != 4 && verts_per_face != 3) {
00780         /* variable face size */
00781         // not implemented yet
00782       } else {
00783         eusinteger_t *iv = mindices->c.ivec.iv;
00784         eusinteger_t idlen = intval (mindices->c.ivec.length);
00785         pMesh->mNumFaces = idlen / verts_per_face;//
00786 
00787         pMesh->mFaces = new aiFace[pMesh->mNumFaces];
00788         for (unsigned int f = 0; f < pMesh->mNumFaces; f++) {
00789           aiFace& face = pMesh->mFaces[f];
00790           face.mNumIndices = verts_per_face;
00791           face.mIndices = new unsigned int[verts_per_face];
00792           for (unsigned int o = 0; o < verts_per_face; o++) {
00793             face.mIndices[o] = *iv++;
00794           }
00795         }
00796       }
00797     } else {
00798       // add indices
00799       if (verts_per_face != 4 && verts_per_face != 3) { /* error */ }
00800       pMesh->mNumFaces = pMesh->mNumVertices / verts_per_face;
00801       pMesh->mFaces = new aiFace[pMesh->mNumFaces];
00802       for (unsigned int f = 0, p = 0; f < pMesh->mNumFaces; f++) {
00803         aiFace& face = pMesh->mFaces[f];
00804         face.mNumIndices = verts_per_face;
00805         face.mIndices = new unsigned int[verts_per_face];
00806         for (unsigned int o = 0; o < verts_per_face; o++, p++) {
00807           face.mIndices[o] = p;
00808         }
00809       }
00810     }
00811   }
00812 
00813   if (!!dumpfile) {
00814     std::string outf, outext;
00815     outf.assign (dumpfile);
00816     {
00817       const std::string::size_type s = outf.find_last_of('.');
00818       if (s != std::string::npos) {
00819         outext = outf.substr (s+1);
00820       } else {
00821         std::cerr << ";; Can not find extention: " << outf << std::endl;
00822       }
00823     }
00824 
00825     Assimp::Exporter exporter;
00826     size_t outfi = SIZE_T_MAX;
00827     for(size_t i = 0, end = exporter.GetExportFormatCount(); i < end; ++i) {
00828       const aiExportFormatDesc* const e = exporter.GetExportFormatDescription(i);
00829       if (outext == e->fileExtension) {
00830         outfi = i; break;
00831       }
00832     }
00833     if (outfi == SIZE_T_MAX) {
00834       outext = "stl";
00835       for(size_t i = 0, end = exporter.GetExportFormatCount(); i < end; ++i) {
00836         const aiExportFormatDesc* const e = exporter.GetExportFormatDescription(i);
00837         if (outext == e->fileExtension) {
00838           outfi = i; break;
00839         }
00840       }
00841     }
00842     if (outfi == SIZE_T_MAX) outfi = 0;
00843     const aiExportFormatDesc* const e = exporter.GetExportFormatDescription(outfi);
00844     aiReturn ret = exporter.Export (pScene, e->id, outf);
00845   }
00846 
00847   return NIL;
00848 }
00849 
00850 pointer CONVEX_DECOMP_GL_VERTICES(register context *ctx,int n,pointer *argv)
00851 {
00852   /* vertices-list indices-list (params) */
00853   numunion nu;
00854   int verts_per_face = 3;
00855   pointer lvertices = argv[0];
00856   pointer lindices = argv[1];
00857   pointer ret = NIL;
00858 
00859 #if 0
00860   int list_len = 0;
00861   {
00862     pointer a = lvertices;
00863     while (islist(a)) {list_len++; a=ccdr(a);}
00864   }
00865 
00866   CONVEX_DECOMPOSITION::iConvexDecomposition *ic = CONVEX_DECOMPOSITION::createConvexDecomposition();
00867   // store all vertices
00868   for (int i = 0; i < list_len; i++) {
00869     pointer mvertices = ccar (lvertices);
00870     pointer mindices = ccar (lindices);
00871 
00872     lvertices = ccdr (lvertices);
00873     lindices = ccdr (lindices);
00874 
00875     if (mvertices == NIL) { /* error */ }
00876     eusinteger_t size = intval (mvertices->c.ary.entity->c.fvec.length);
00877     eusfloat_t *fv = mvertices->c.ary.entity->c.fvec.fv;
00878     NxF32 p1[3];
00879     NxF32 p2[3];
00880     NxF32 p3[3];
00881 
00882     if (mindices != NIL) {
00883       eusinteger_t *iv = mindices->c.ivec.iv;
00884       eusinteger_t idlen = intval (mindices->c.ivec.length);
00885       for (unsigned int f = 0; f < idlen / verts_per_face; f++) {
00886         eusinteger_t i1 = *iv++;
00887         eusinteger_t i2 = *iv++;
00888         eusinteger_t i3 = *iv++;
00889 
00890         p1[0] = fv[3*i1];
00891         p1[1] = fv[3*i1+1];
00892         p1[2] = fv[3*i1+2];
00893 
00894         p2[0] = fv[3*i2];
00895         p2[1] = fv[3*i2+1];
00896         p2[2] = fv[3*i2+2];
00897 
00898         p3[0] = fv[3*i3];
00899         p3[1] = fv[3*i3+1];
00900         p3[2] = fv[3*i3+2];
00901 
00902         ic->addTriangle(p1, p2, p3);
00903       }
00904     } else {
00905       for (unsigned int f = 0; f < size / (3 * verts_per_face); f++) {
00906         p1[0] = fv[(3 * verts_per_face) + 0];
00907         p1[1] = fv[(3 * verts_per_face) + 1];
00908         p1[2] = fv[(3 * verts_per_face) + 2];
00909 
00910         p2[0] = fv[(3 * verts_per_face) + 3];
00911         p2[1] = fv[(3 * verts_per_face) + 4];
00912         p2[2] = fv[(3 * verts_per_face) + 5];
00913 
00914         p3[0] = fv[(3 * verts_per_face) + 6];
00915         p3[1] = fv[(3 * verts_per_face) + 7];
00916         p3[2] = fv[(3 * verts_per_face) + 8];
00917 
00918         ic->addTriangle(p1, p2, p3);
00919       }
00920     }
00921   }
00922 
00923   NxF32 skinWidth = 0;
00924   NxU32 decompositionDepth = 4;
00925   NxU32 maxHullVertices    = 64;
00926   NxF32 concavityThresholdPercent = 0.1f;
00927   NxF32 mergeThresholdPercent = 20;
00928   NxF32 volumeSplitThresholdPercent = 2;
00929   bool useInitialIslandGeneration = true;
00930   bool useIslandGeneration = false;
00931   bool useBackgroundThreads = true;
00932   ic->computeConvexDecomposition(skinWidth,
00933                                  decompositionDepth,
00934                                  maxHullVertices,
00935                                  concavityThresholdPercent,
00936                                  mergeThresholdPercent,
00937                                  volumeSplitThresholdPercent,
00938                                  useInitialIslandGeneration,
00939                                  useIslandGeneration,
00940                                  useBackgroundThreads);
00941 
00942   while ( !ic->isComputeComplete() ) {
00943     printf("Computing the convex decomposition in a background thread.\r\n");
00944     sleep(1);
00945     // Sleep(1000);
00946   }
00947   // finish process
00948 
00949   NxU32 hullCount = ic->getHullCount();
00950   printf("Convex Decomposition produced %d hulls.\r\n", hullCount );
00951 
00952   for (NxU32 i = 0; i < hullCount; i++) {
00953     //
00954     pointer tmpret = NIL;
00955     int npc = 0;
00956     // name
00957     {
00958       std::string nname = "convex_" + i;
00959       pointer lname = makestring ((char *)nname.c_str(), nname.length());
00960       vpush (lname);
00961       lname = rawcons (ctx, lname , NIL);
00962       vpop (); vpush (lname);
00963       lname = rawcons (ctx, K_NAME, lname);
00964       vpop (); vpush (lname);
00965       tmpret = rawcons (ctx, lname, tmpret);
00966       vpop ();
00967       vpush (tmpret); npc++;
00968     }
00969     // type
00970     {
00971       pointer ltype = K_TRIANGLES;
00972       ltype = rawcons (ctx, ltype , NIL);
00973       vpush (ltype);
00974       ltype = rawcons (ctx, K_TYPE, ltype);
00975       vpop(); vpush (ltype);
00976       tmpret = rawcons (ctx, ltype, tmpret);
00977       vpop();
00978       vpush (tmpret); npc++;
00979     }
00980 
00981     CONVEX_DECOMPOSITION::ConvexHullResult result;
00982     ic->getConvexHullResult(i, result);
00983 
00984     pointer ver_mat = makematrix (ctx, result.mVcount, 3); vpush (ver_mat); npc++;
00985     eusfloat_t *ver_vec = ver_mat->c.ary.entity->c.fvec.fv;
00986 
00987     pointer indices = makevector (C_INTVECTOR, result.mTcount * 3);
00988     eusinteger_t *vec = indices->c.ivec.iv;
00989     vpush (indices); npc++;
00990 
00991     for (NxU32 i = 0; i < result.mVcount * 3; i++) {
00992       //const NxF32 *pos = &result.mVertices[i*3];
00993       //fprintf(fph,"v %0.9f %0.9f %0.9f\r\n", pos[0], pos[1], pos[2] );
00994       ver_vec[i] = result.mVertices[i];
00995     }
00996     for (NxU32 i = 0; i < result.mTcount * 3; i++) {
00997       //NxU32 i1 = result.mIndices[i*3+0];
00998       //NxU32 i2 = result.mIndices[i*3+1];
00999       //NxU32 i3 = result.mIndices[i*3+2];
01000       //fprintf(fph,"f %d %d %d\r\n", i1 + vcount_base, i2 + vcount_base, i3 + vcount_base );
01001       vec[i] = result.mIndices[i];
01002     }
01003     //vcount_base += result.mVcount;
01004     // add indices to return list
01005     {
01006       pointer tmp;
01007       tmp = rawcons (ctx, indices, NIL);
01008       vpush (tmp);
01009       tmp = rawcons (ctx, K_INDICES, tmp);
01010       tmpret = rawcons (ctx, tmp, tmpret);
01011       vpop();
01012       vpush (tmpret); npc++;
01013     }
01014     //
01015     {
01016       pointer tmp;
01017       tmp = rawcons (ctx, ver_mat , NIL);
01018       vpush (tmp);
01019       tmp = rawcons (ctx, K_VERTICES , tmp);
01020       tmpret = rawcons (ctx, tmp, tmpret);
01021       vpop();
01022       vpush (tmpret); npc++;
01023     }
01024 
01025     vpush(ret); npc++;
01026     ret = rawcons (ctx, tmpret, ret);
01027     for (;npc > 0; npc--) vpop();
01028     vpush(ret);
01029   }
01030 
01031   CONVEX_DECOMPOSITION::releaseConvexDecomposition(ic);
01032   vpop(); // pop ret
01033 #endif
01034   return ret;
01035 }
01036 
01037 pointer ASSIMP_DESCRIBE(register context *ctx,int n,pointer *argv)
01038 {
01039   /* */
01040   ckarg(1);
01041   if (!isstring(argv[0])) error(E_NOSTRING);
01042 
01043   Assimp::Importer importer;
01044   const aiScene* scene = importer.ReadFile((char *)get_string(argv[0]),
01045                                            aiProcess_Triangulate            |
01046                                            aiProcess_JoinIdenticalVertices  |
01047                                            aiProcess_SortByPType);
01048 
01049   if (!scene) {
01050     std::string str( importer.GetErrorString() );
01051     std::cerr << ";; " << str << std::endl;
01052     //std::cerr << ";; file: " << get_string(argv[0]) << " not found" << std::endl;
01053     return NIL;
01054   }
01055 
01056   std::cerr << ";; scene->NumAnimations " <<  scene->mNumAnimations << std::endl;
01057   //aiAnimation ** mAnimations;
01058 
01059   std::cerr << ";; scene->mNumCameras " << scene->mNumCameras << std::endl;
01060   //aiCamera ** mCameras;
01061 
01062   std::cerr << ";; scene->mNumLights " << scene->mNumLights << std::endl;
01063   //aiLight ** mLights;
01064 
01065   std::cerr << ";; scene->mNumMaterials " << scene->mNumMaterials << std::endl;
01066   for (unsigned int i = 0; i < scene->mNumMaterials; i++) {
01067     printMaterial(scene->mMaterials[i], i);
01068   }
01069   //aiMaterial ** mMaterials;
01070 
01071   std::cerr << ";; scene->mNumTextures " << scene->mNumTextures << std::endl;
01072   //aiTexture ** mTextures;
01073 
01074   std::cerr << ";; scene->mFlags " << scene->mFlags << std::endl;
01075 
01076   std::cerr << ";; scene->mNumMeshes " << scene->mNumMeshes << std::endl;
01077 
01078   //aiMesh ** scene->mMeshes;
01079   for ( unsigned int i = 0; i < scene->mNumMeshes; i++ ) {
01080     printMesh( scene->mMeshes[i] , "");
01081   }
01082 
01083   printNode( scene->mRootNode , "");
01084 
01085   return NIL;
01086 }
01087 
01088 pointer ___eus_assimp(register context *ctx, int n, pointer *argv, pointer env)
01089 {
01090   defun(ctx,"ASSIMP-GET-GLVERTICES", argv[0], (pointer (*)())GET_MESHES);
01091   defun(ctx,"ASSIMP-DUMP-GLVERTICES", argv[0], (pointer (*)())DUMP_GL_VERTICES);
01092   defun(ctx,"CONVEX-DECOMPOSITION-GLVERTICES", argv[0], (pointer (*)())CONVEX_DECOMP_GL_VERTICES);
01093 
01094   defun(ctx,"ASSIMP-DESCRIBE", argv[0], (pointer (*)())ASSIMP_DESCRIBE);
01095 
01096   K_VERTICES  = defkeyword(ctx, "VERTICES");
01097   K_NORMALS   = defkeyword(ctx, "NORMALS");
01098   K_INDICES   = defkeyword(ctx, "INDICES");
01099   K_MATERIAL  = defkeyword(ctx, "MATERIAL");
01100   K_TYPE      = defkeyword(ctx, "TYPE");
01101   K_LINES     = defkeyword(ctx, "LINES");
01102   K_TRIANGLES = defkeyword(ctx, "TRIANGLES");
01103   K_QUADS     = defkeyword(ctx, "QUADS");
01104   K_POLYGON   = defkeyword(ctx, "POLYGON");
01105   K_NAME      = defkeyword(ctx, "NAME");
01106   // for material
01107   K_AMBIENT      = defkeyword(ctx, "AMBIENT");
01108   K_DIFFUSE      = defkeyword(ctx, "DIFFUSE");
01109   K_SPECULAR     = defkeyword(ctx, "SPECULAR");
01110   K_EMISSION     = defkeyword(ctx, "EMISSION");
01111   K_SHININESS    = defkeyword(ctx, "SHININESS");
01112   K_TRANSPARENCY = defkeyword(ctx, "TRANSPARENCY");
01113 
01114   return 0;
01115 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


eus_assimp
Author(s): Yohei Kakiuchi (youhei@jsk.t.u-tokyo.ac.jp)
autogenerated on Sat Mar 23 2013 19:19:01