ShapeSetInfo_impl.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, AIST, the University of Tokyo and General Robotix Inc.
3  * All rights reserved. This program is made available under the terms of the
4  * Eclipse Public License v1.0 which accompanies this distribution, and is
5  * available at http://www.eclipse.org/legal/epl-v10.html
6  * Contributors:
7  * National Institute of Advanced Industrial Science and Technology (AIST)
8  */
9 
15 #include "ShapeSetInfo_impl.h"
16 
17 #include <map>
18 #include <vector>
19 #include <iostream>
20 #include <boost/bind.hpp>
21 #include <sys/stat.h>
22 
23 #include <hrpCorba/ViewSimulator.hh>
24 #include <hrpUtil/VrmlNodes.h>
25 #include <hrpUtil/ImageConverter.h>
26 
27 #include "VrmlUtil.h"
28 
29 
30 
31 using namespace std;
32 using namespace boost;
33 
34 
35 
36 ShapeSetInfo_impl::ShapeSetInfo_impl(PortableServer::POA_ptr poa) :
37  poa(PortableServer::POA::_duplicate(poa))
38 {
40  triangleMeshShaper.sigMessage.connect(boost::bind(&putMessage, _1));
41 }
42 
43 
45 {
46 
47 }
48 
49 
50 PortableServer::POA_ptr ShapeSetInfo_impl::_default_POA()
51 {
52  return PortableServer::POA::_duplicate(poa);
53 }
54 
55 
57 {
59 }
60 
61 
62 void ShapeSetInfo_impl::putMessage(const std::string& message)
63 {
64  cout << message;
65 }
66 
67 
74 string& ShapeSetInfo_impl::replace(string& str, const string& sb, const string& sa)
75 {
76  string::size_type n, nb = 0;
77 
78  while ((n = str.find(sb,nb)) != string::npos){
79  str.replace(n,sb.size(),sa);
80  nb = n + sa.size();
81  }
82 
83  return str;
84 }
85 
86 
87 ShapeInfoSequence* ShapeSetInfo_impl::shapes()
88 {
89  return new ShapeInfoSequence(shapes_);
90 }
91 
92 
93 AppearanceInfoSequence* ShapeSetInfo_impl::appearances()
94 {
95  return new AppearanceInfoSequence(appearances_);
96 }
97 
98 
99 MaterialInfoSequence* ShapeSetInfo_impl::materials()
100 {
101  return new MaterialInfoSequence(materials_);
102 }
103 
104 
105 TextureInfoSequence* ShapeSetInfo_impl::textures()
106 {
107  return new TextureInfoSequence(textures_);
108 }
109 
110 
124 (VrmlNode* node, const Matrix44& T, TransformedShapeIndexSequence& io_shapeIndices, DblArray12Sequence& inlinedShapeM, const SFString* url)
125 {
126  static int inline_count=0;
127  SFString url_ = *url;
129  VrmlProtoInstance* protoInstance = static_cast<VrmlProtoInstance*>(node);
130  if(protoInstance->actualNode){
131  traverseShapeNodes(protoInstance->actualNode.get(), T, io_shapeIndices, inlinedShapeM, url);
132  }
133 
134  } else if(node->isCategoryOf(GROUPING_NODE)) {
135  VrmlGroup* groupNode = static_cast<VrmlGroup*>(node);
136  VrmlTransform* transformNode = dynamic_cast<VrmlTransform*>(groupNode);
137  VrmlInline* inlineNode = NULL;
138 
139  inlineNode = dynamic_cast<VrmlInline*>(groupNode);
140  const Matrix44* pT;
141  if(inlineNode){
142  if(!inline_count){
143  int inlinedShapeMIndex = inlinedShapeM.length();
144  inlinedShapeM.length(inlinedShapeMIndex+1);
145  int p = 0;
146  for(int row=0; row < 3; ++row){
147  for(int col=0; col < 4; ++col){
148  inlinedShapeM[inlinedShapeMIndex][p++] = T(row, col);
149  }
150  }
151  url_ = inlineNode->urls[0];
152  }
153  inline_count++;
154  for( MFString::iterator ite = inlineNode->urls.begin(); ite != inlineNode->urls.end(); ++ite ){
155  string filename(deleteURLScheme(*ite));
156  struct stat statbuff;
157  time_t mtime = 0;
158  if( stat( filename.c_str(), &statbuff ) == 0 ){
159  mtime = statbuff.st_mtime;
160  }
161  fileTimeMap.insert(make_pair(filename, mtime));
162  }
163  }
164  Matrix44 T2;
165  if( transformNode ){
166  Matrix44 Tlocal;
167  calcTransformMatrix(transformNode, Tlocal);
168  T2 = T * Tlocal;
169  pT = &T2;
170  } else {
171  pT = &T;
172  }
173 
174  VrmlSwitch* switchNode = dynamic_cast<VrmlSwitch*>(node);
175  if(switchNode){
176  int whichChoice = switchNode->whichChoice;
177  if( whichChoice >= 0 && whichChoice < switchNode->countChildren() )
178  traverseShapeNodes(switchNode->getChild(whichChoice), *pT, io_shapeIndices, inlinedShapeM, &url_);
179  }else{
180  for(int i=0; i < groupNode->countChildren(); ++i){
181  traverseShapeNodes(groupNode->getChild(i), *pT, io_shapeIndices, inlinedShapeM, &url_);
182  }
183  }
184  if(inlineNode)
185  inline_count--;
186 
187 
188  } else if(node->isCategoryOf(SHAPE_NODE)) {
189 
190  VrmlShape* shapeNode = static_cast<VrmlShape*>(node);
191  short shapeInfoIndex;
192 
193  ShapeNodeToShapeInfoIndexMap::iterator p = shapeInfoIndexMap.find(shapeNode);
194  if(p != shapeInfoIndexMap.end()){
195  shapeInfoIndex = p->second;
196  } else {
197  shapeInfoIndex = createShapeInfo(shapeNode, url);
198  }
199 
200  if(shapeInfoIndex >= 0){
201  long length = io_shapeIndices.length();
202  io_shapeIndices.length(length + 1);
203  TransformedShapeIndex& tsi = io_shapeIndices[length];
204  tsi.shapeIndex = shapeInfoIndex;
205  int p = 0;
206  for(int row=0; row < 3; ++row){
207  for(int col=0; col < 4; ++col){
208  tsi.transformMatrix[p++] = T(row, col);
209  }
210  }
211  if(inline_count)
212  tsi.inlinedShapeTransformMatrixIndex=inlinedShapeM.length()-1;
213  else
214  tsi.inlinedShapeTransformMatrixIndex=-1;
215  }
216  }
217 }
218 
223 {
224  int shapeInfoIndex = -1;
225 
226  VrmlIndexedFaceSet* triangleMesh = dynamic_node_cast<VrmlIndexedFaceSet>(shapeNode->geometry).get();
227 
228  if(triangleMesh){
229 
230  shapeInfoIndex = shapes_.length();
231  shapes_.length(shapeInfoIndex + 1);
232  ShapeInfo& shapeInfo = shapes_[shapeInfoIndex];
233 
234  if ( url ) shapeInfo.url = CORBA::string_dup( url->c_str() );
235  setTriangleMesh(shapeInfo, triangleMesh);
236  setPrimitiveProperties(shapeInfo, shapeNode);
237  shapeInfo.appearanceIndex = createAppearanceInfo(shapeInfo, shapeNode, triangleMesh, url);
238  shapeInfoIndexMap.insert(make_pair(shapeNode, shapeInfoIndex));
239  }
240 
241  return shapeInfoIndex;
242 }
243 
244 
245 void ShapeSetInfo_impl::setTriangleMesh(ShapeInfo& shapeInfo, VrmlIndexedFaceSet* triangleMesh)
246 {
247  const MFVec3f& vertices = triangleMesh->coord->point;
248  size_t numVertices = vertices.size();
249  shapeInfo.vertices.length(numVertices * 3);
250 
251  size_t pos = 0;
252  for(size_t i=0; i < numVertices; ++i){
253  const SFVec3f& v = vertices[i];
254  shapeInfo.vertices[pos++] = v[0];
255  shapeInfo.vertices[pos++] = v[1];
256  shapeInfo.vertices[pos++] = v[2];
257  }
258 
259  const MFInt32& indices = triangleMesh->coordIndex;
260  const size_t numTriangles = indices.size() / 4;
261  shapeInfo.triangles.length(numTriangles * 3);
262 
263  int dpos = 0;
264  int spos = 0;
265  for(size_t i=0; i < numTriangles; ++i){
266  shapeInfo.triangles[dpos++] = indices[spos++];
267  shapeInfo.triangles[dpos++] = indices[spos++];
268  shapeInfo.triangles[dpos++] = indices[spos++];
269  spos++; // skip a terminater '-1'
270  }
271 }
272 
273 
274 void ShapeSetInfo_impl::setPrimitiveProperties(ShapeInfo& shapeInfo, VrmlShape* shapeNode)
275 {
276  shapeInfo.primitiveType = SP_MESH;
277  FloatSequence& param = shapeInfo.primitiveParameters;
278 
279  VrmlNode *node = triangleMeshShaper.getOriginalGeometry(shapeNode).get();
280  VrmlGeometry* originalGeometry = dynamic_cast<VrmlGeometry *>(node);
281 
282  if(originalGeometry){
283 
284  VrmlIndexedFaceSet* faceSet = dynamic_cast<VrmlIndexedFaceSet*>(originalGeometry);
285 
286  if(!faceSet){
287 
288  if(VrmlBox* box = dynamic_cast<VrmlBox*>(originalGeometry)){
289  shapeInfo.primitiveType = SP_BOX;
290  param.length(3);
291  for(int i=0; i < 3; ++i){
292  param[i] = box->size[i];
293  }
294 
295  } else if(VrmlCone* cone = dynamic_cast<VrmlCone*>(originalGeometry)){
296  shapeInfo.primitiveType = SP_CONE;
297  param.length(4);
298  param[0] = cone->bottomRadius;
299  param[1] = cone->height;
300  param[2] = cone->bottom ? 1.0 : 0.0;
301  param[3] = cone->side ? 1.0 : 0.0;
302 
303  } else if(VrmlCylinder* cylinder = dynamic_cast<VrmlCylinder*>(originalGeometry)){
304  shapeInfo.primitiveType = SP_CYLINDER;
305  param.length(5);
306  param[0] = cylinder->radius;
307  param[1] = cylinder->height;
308  param[2] = cylinder->top ? 1.0 : 0.0;
309  param[3] = cylinder->bottom ? 1.0 : 0.0;
310  param[4] = cylinder->side ? 1.0 : 0.0;
311 
312 
313  } else if(VrmlSphere* sphere = dynamic_cast<VrmlSphere*>(originalGeometry)){
314  shapeInfo.primitiveType = SP_SPHERE;
315  param.length(1);
316  param[0] = sphere->radius;
317  }
318  }
319  }else{
320 
321  VrmlProtoInstance *protoInstance = dynamic_cast<VrmlProtoInstance *>(node);
322  if (protoInstance && protoInstance->proto->protoName == "Plane"){
323  VrmlBox *box = dynamic_cast<VrmlBox *>(protoInstance->actualNode.get());
324  shapeInfo.primitiveType = SP_PLANE;
325  param.length(3);
326  for (int i=0; i<3; i++){
327  param[i] = box->size[i];
328  }
329  }
330  }
331 }
332 
333 
338 (ShapeInfo& shapeInfo, VrmlShape* shapeNode, VrmlIndexedFaceSet* faceSet,
339  const SFString *url)
340 {
341  int appearanceIndex = appearances_.length();
342  appearances_.length(appearanceIndex + 1);
343  AppearanceInfo& appInfo = appearances_[appearanceIndex];
344 
345  appInfo.normalPerVertex = faceSet->normalPerVertex;
346  appInfo.colorPerVertex = faceSet->colorPerVertex;
347  appInfo.solid = faceSet->solid;
348  appInfo.creaseAngle = faceSet->creaseAngle;
349  appInfo.materialIndex = -1;
350  appInfo.textureIndex = -1;
351 
352  if(faceSet->color){
353  setColors(appInfo, faceSet);
354  }
355 
356  if(faceSet->normal){
357  setNormals(appInfo, faceSet);
358  }
359 
360  VrmlAppearancePtr& appNode = shapeNode->appearance;
361 
362  if(appNode) {
363  appInfo.materialIndex = createMaterialInfo(appNode->material);
364  appInfo.textureIndex = createTextureInfo (appNode->texture, url);
365  if(appInfo.textureIndex != -1 ){
366  createTextureTransformMatrix(appInfo, appNode->textureTransform);
367  if(!faceSet->texCoord){ // default Texture Mapping
369  }
370  setTexCoords(appInfo, faceSet);
371  }
372  }
373 
374  return appearanceIndex;
375 }
376 
377 
378 void ShapeSetInfo_impl::setColors(AppearanceInfo& appInfo, VrmlIndexedFaceSet* triangleMesh)
379 {
380  const MFColor& colors = triangleMesh->color->color;
381  int numColors = colors.size();
382  appInfo.colors.length(numColors * 3);
383 
384  int pos = 0;
385  for(int i=0; i < numColors; ++i){
386  const SFColor& color = colors[i];
387  for(int j=0; j < 3; ++j){
388  appInfo.colors[pos++] = color[j];
389  }
390  }
391 
392  const MFInt32& orgIndices = triangleMesh->colorIndex;
393  const int numOrgIndices = orgIndices.size();
394  if(numOrgIndices > 0){
395  if(triangleMesh->colorPerVertex){
396  const int numTriangles = numOrgIndices / 4; // considering delimiter element '-1'
397  appInfo.colorIndices.length(numTriangles * 3);
398  int dpos = 0;
399  int spos = 0;
400  for(int i=0; i < numTriangles; ++i){
401  appInfo.colorIndices[dpos++] = orgIndices[spos++];
402  appInfo.colorIndices[dpos++] = orgIndices[spos++];
403  appInfo.colorIndices[dpos++] = orgIndices[spos++];
404  spos++; // skip delimiter '-1'
405  }
406  } else { // color per face
407  appInfo.colorIndices.length(numOrgIndices);
408  for(int i=0; i < numOrgIndices; ++i){
409  appInfo.colorIndices[i] = orgIndices[i];
410  }
411  }
412  }
413 }
414 
415 
416 void ShapeSetInfo_impl::setNormals(AppearanceInfo& appInfo, VrmlIndexedFaceSet* triangleMesh)
417 {
418  const MFVec3f& normals = triangleMesh->normal->vector;
419  int numNormals = normals.size();
420  appInfo.normals.length(numNormals * 3);
421 
422  int pos = 0;
423  for(int i=0; i < numNormals; ++i){
424  const SFVec3f& n = normals[i];
425  for(int j=0; j < 3; ++j){
426  appInfo.normals[pos++] = n[j];
427  }
428  }
429 
430  const MFInt32& orgIndices = triangleMesh->normalIndex;
431  const int numOrgIndices = orgIndices.size();
432  if(numOrgIndices > 0){
433  if(triangleMesh->normalPerVertex){
434  const int numTriangles = numOrgIndices / 4; // considering delimiter element '-1'
435  appInfo.normalIndices.length(numTriangles * 3);
436  int dpos = 0;
437  int spos = 0;
438  for(int i=0; i < numTriangles; ++i){
439  appInfo.normalIndices[dpos++] = orgIndices[spos++];
440  appInfo.normalIndices[dpos++] = orgIndices[spos++];
441  appInfo.normalIndices[dpos++] = orgIndices[spos++];
442  spos++; // skip delimiter '-1'
443  }
444  } else { // normal per face
445  appInfo.normalIndices.length(numOrgIndices);
446  for(int i=0; i < numOrgIndices; ++i){
447  appInfo.normalIndices[i] = orgIndices[i];
448  }
449  }
450  }
451 }
452 
453 void ShapeSetInfo_impl::setTexCoords(AppearanceInfo& appInfo, VrmlIndexedFaceSet* triangleMesh )
454 {
455  int numCoords = triangleMesh->texCoord->point.size();
456  appInfo.textureCoordinate.length(numCoords * 2);
457 
458  Matrix33 m;
459  for(int i=0,k=0; i<3; i++)
460  for(int j=0; j<3; j++)
461  m(i,j) = appInfo.textransformMatrix[k++];
462 
463  for(int i=0, pos=0; i < numCoords; i++ ){
464  Vector3 point(triangleMesh->texCoord->point[i][0], triangleMesh->texCoord->point[i][1], 1);
465  Vector3 texCoordinate(m * point);
466  appInfo.textureCoordinate[pos++] = texCoordinate(0);
467  appInfo.textureCoordinate[pos++] = texCoordinate(1);
468  }
469 
470  int numIndex = triangleMesh->texCoordIndex.size();
471  if(numIndex > 0){
472  appInfo.textureCoordIndices.length(numIndex * 3 / 4);
473  for(int i=0, j=0; i < numIndex; i++){
474  if(triangleMesh->texCoordIndex[i] != -1)
475  appInfo.textureCoordIndices[j++] = triangleMesh->texCoordIndex[i];
476  }
477  }
478 }
479 
480 void ShapeSetInfo_impl::createTextureTransformMatrix(AppearanceInfo& appInfo, VrmlTextureTransformPtr& textureTransform ){
481 
482  Matrix33 m;
483  if(textureTransform){
484  Matrix33 matCT;
485  matCT << 1, 0, textureTransform->translation[0]+textureTransform->center[0],
486  0, 1, textureTransform->translation[1]+textureTransform->center[1],
487  0,0,1 ;
488  Matrix33 matR;
489  matR << cos(textureTransform->rotation), -sin(textureTransform->rotation), 0,
490  sin(textureTransform->rotation), cos(textureTransform->rotation), 0,
491  0,0,1;
492  Matrix33 matCS;
493  matCS << textureTransform->scale[0], 0, -textureTransform->center[0],
494  0, textureTransform->scale[1], -textureTransform->center[1],
495  0,0,1 ;
496 
497  m = matCS * matR * matCT;
498  }else{
499  m = Matrix33::Identity();
500  }
501 
502  for(int i=0,k=0; i<3; i++)
503  for(int j=0; j<3; j++)
504  appInfo.textransformMatrix[k++] = m(i,j);
505 }
506 
516 {
517  int materialInfoIndex = -1;
518 
519  if(materialNode){
520  MaterialInfo_var material(new MaterialInfo());
521 
522  material->ambientIntensity = materialNode->ambientIntensity;
523  material->shininess = materialNode->shininess;
524  material->transparency = materialNode->transparency;
525 
526  for(int j = 0 ; j < 3 ; j++){
527  material->diffuseColor[j] = materialNode->diffuseColor[j];
528  material->emissiveColor[j] = materialNode->emissiveColor[j];
529  material->specularColor[j] = materialNode->specularColor[j];
530  }
531 
532  // materials_に追加する //
533  materialInfoIndex = materials_.length();
534  materials_.length(materialInfoIndex + 1 );
535  materials_[materialInfoIndex] = material;
536 
537  }
538 
539  return materialInfoIndex;
540 }
541 
542 
553 {
554  int textureInfoIndex = -1;
555 
556  if(textureNode){
557 
558  TextureInfo_var texture(new TextureInfo());
559 
560  VrmlPixelTexturePtr pixelTextureNode = dynamic_pointer_cast<VrmlPixelTexture>(textureNode);
561 
562  if(!pixelTextureNode){
563  VrmlImageTexturePtr imageTextureNode = dynamic_pointer_cast<VrmlImageTexture>(textureNode);
564  if(imageTextureNode){
565  string url = setTexturefileUrl(getModelFileDirPath(*currentUrl), imageTextureNode->url);
566  texture->url = CORBA::string_dup(url.c_str());
567  texture->repeatS = imageTextureNode->repeatS;
568  texture->repeatT = imageTextureNode->repeatT;
569  if(readImage && !url.empty()){
570  ImageConverter converter;
571  SFImage* image = converter.convert(url);
572  texture->height = image->height;
573  texture->width = image->width;
574  texture->numComponents = image->numComponents;
575  unsigned long pixelsLength = image->pixels.size();
576  texture->image.length( pixelsLength );
577  for(unsigned long j = 0 ; j < pixelsLength ; j++ ){
578  texture->image[j] = image->pixels[j];
579  }
580  }else{
581  texture->height = 0;
582  texture->width = 0;
583  texture->numComponents = 0;
584  }
585  }
586  }else if(pixelTextureNode){
587  texture->height = pixelTextureNode->image.height;
588  texture->width = pixelTextureNode->image.width;
589  texture->numComponents = pixelTextureNode->image.numComponents;
590 
591  size_t pixelsLength = pixelTextureNode->image.pixels.size();
592  texture->image.length( pixelsLength );
593  for(size_t j = 0 ; j < pixelsLength ; j++ ){
594  texture->image[j] = pixelTextureNode->image.pixels[j];
595  }
596  texture->repeatS = pixelTextureNode->repeatS;
597  texture->repeatT = pixelTextureNode->repeatT;
598  }
599 
600  textureInfoIndex = textures_.length();
601  textures_.length(textureInfoIndex + 1);
602  textures_[textureInfoIndex] = texture;
603  }
604 
605  return textureInfoIndex;
606 }
607 
608 
616 std::string ShapeSetInfo_impl::getModelFileDirPath(const std::string& url)
617 {
618  // BodyInfo::url_ から URLスキームを削除する //
619  string filepath = deleteURLScheme(url);
620 
621  // '/' または '\' の最後の位置を取得する //
622  size_t pos = filepath.find_last_of("/\\");
623 
624  string dirPath = "";
625 
626  // 存在すれば, //
627  if(pos != string::npos){
628  // ディレクトリパス文字列 //
629  dirPath = filepath;
630  dirPath.resize(pos + 1);
631  }
632 
633  return dirPath;
634 }
635 
636 void ShapeSetInfo_impl::setColdetModel(ColdetModelPtr& coldetModel, TransformedShapeIndexSequence shapeIndices, const Matrix44& Tparent, int& vertexIndex, int& triangleIndex){
637  for(unsigned int i=0; i < shapeIndices.length(); i++){
638  setColdetModelTriangles(coldetModel, shapeIndices[i], Tparent, vertexIndex, triangleIndex);
639  }
640 }
641 
643 (ColdetModelPtr& coldetModel, const TransformedShapeIndex& tsi, const Matrix44& Tparent, int& vertexIndex, int& triangleIndex)
644 {
645  short shapeIndex = tsi.shapeIndex;
646  const DblArray12& M = tsi.transformMatrix;;
647  Matrix44 T, Tlocal;
648  Tlocal << M[0], M[1], M[2], M[3],
649  M[4], M[5], M[6], M[7],
650  M[8], M[9], M[10], M[11],
651  0.0, 0.0, 0.0, 1.0;
652  T = Tparent * Tlocal;
653 
654  const ShapeInfo& shapeInfo = shapes_[shapeIndex];
655  int vertexIndexBase = coldetModel->getNumVertices();
656  const FloatSequence& vertices = shapeInfo.vertices;
657  const int numVertices = vertices.length() / 3;
658  coldetModel->setNumVertices(coldetModel->getNumVertices()+numVertices);
659  for(int j=0; j < numVertices; ++j){
660  Vector4 v(T * Vector4(vertices[j*3], vertices[j*3+1], vertices[j*3+2], 1.0));
661  coldetModel->setVertex(vertexIndex++, v[0], v[1], v[2]);
662  }
663  const LongSequence& triangles = shapeInfo.triangles;
664  const int numTriangles = triangles.length() / 3;
665  coldetModel->setNumTriangles(coldetModel->getNumTriangles()+numTriangles);
666  for(int j=0; j < numTriangles; ++j){
667  int t0 = triangles[j*3] + vertexIndexBase;
668  int t1 = triangles[j*3+1] + vertexIndexBase;
669  int t2 = triangles[j*3+2] + vertexIndexBase;
670  coldetModel->setTriangle( triangleIndex++, t0, t1, t2);
671  }
672 
673 }
674 
679 }
680 
681 void ShapeSetInfo_impl::setBoundingBoxData(const Vector3& boxSize, int shapeIndex){
682  VrmlBox* box = new VrmlBox();
683  VrmlIndexedFaceSetPtr triangleMesh;
684  box->size[0] = boxSize[0]*2;
685  box->size[1] = boxSize[1]*2;
686  box->size[2] = boxSize[2]*2;
687  triangleMesh = new VrmlIndexedFaceSet();
688  triangleMesh->coord = new VrmlCoordinate();
689  triangleMeshShaper.convertBox(box, triangleMesh);
690 
691  shapes_.length(shapeIndex+1);
692  ShapeInfo& shapeInfo = shapes_[shapeIndex];
693  VrmlIndexedFaceSet* faceSet = triangleMesh.get();
694  setTriangleMesh(shapeInfo, faceSet);
695  shapeInfo.primitiveType = SP_BOX;
696  FloatSequence& param = shapeInfo.primitiveParameters;
697  param.length(3);
698  for(int i=0; i < 3; ++i)
699  param[i] = box->size[i];
700  shapeInfo.appearanceIndex = 0;
701 
702  delete box;
703 }
704 
706  appearances_.length(1);
707  AppearanceInfo& appInfo = appearances_[0];
708  appInfo.normalPerVertex = false;
709  appInfo.colorPerVertex = false;
710  appInfo.solid = false;
711  appInfo.creaseAngle = 0.0;
712  appInfo.textureIndex = -1;
713  appInfo.normals.length(0);
714  appInfo.normalIndices.length(0);
715  appInfo.colors.length(0);
716  appInfo.colorIndices.length(0);
717  appInfo.materialIndex = 0;
718  appInfo.textureIndex = -1;
719 
720  materials_.length(1);
721  MaterialInfo& material = materials_[0];
722  material.ambientIntensity = 0.2;
723  material.shininess = 0.2;
724  material.transparency = 0.0;
725  for(int j = 0 ; j < 3 ; j++){
726  material.diffuseColor[j] = 0.8;
727  material.emissiveColor[j] = 0.0;
728  material.specularColor[j] = 0.0;
729  }
730 }
731 
736 }
737 
739  bool ret=true;
740  for( map<std::string, time_t>::iterator it=fileTimeMap.begin(); it != fileTimeMap.end(); ++it){
741  struct stat statbuff;
742  time_t mtime = 0;
743  if( stat( it->first.c_str(), &statbuff ) == 0 ){
744  mtime = statbuff.st_mtime;
745  }
746  if(it->second!=mtime){
747  ret=false;
748  break;
749  }
750  }
751  return ret;
752 }
boost::intrusive_ptr< VrmlTextureTransform > VrmlTextureTransformPtr
Definition: VrmlNodes.h:301
virtual MaterialInfoSequence * materials()
std::string getModelFileDirPath(const std::string &url)
VrmlCoordinatePtr coord
Definition: VrmlNodes.h:467
std::vector< SFColor > MFColor
Definition: VrmlNodes.h:76
virtual AppearanceInfoSequence * appearances()
std::string & replace(std::string &str, const std::string &sb, const std::string &sa)
void setBoundingBoxData(const Vector3 &boxSize, int shapeIndex)
void defaultTextureMapping(VrmlShape *shapeNode)
VRML ImageTexture node.
Definition: VrmlNodes.h:341
Modifications controlling boost library behavior.
Definition: ColladaUtil.h:306
char * filename
Definition: cdjpeg.h:133
Abstract base class of all vrml nodes.
Definition: VrmlNodes.h:121
boost::intrusive_ptr< VrmlImageTexture > VrmlImageTexturePtr
Definition: VrmlNodes.h:350
std::vector< unsigned char > pixels
Definition: VrmlNodes.h:65
VrmlProtoPtr proto
Definition: VrmlNodes.h:886
SFVec3f size
Definition: VrmlNodes.h:377
boost::signal< void(const std::string &message)> sigMessage
VRML Shape node.
Definition: VrmlNodes.h:285
int createTextureInfo(VrmlTexturePtr &textureNode, const SFString *url)
int createShapeInfo(VrmlShape *shapeNode, const SFString *url)
VRML Cone node.
Definition: VrmlNodes.h:383
RTC::ReturnCode_t ret(RTC::Local::ReturnCode_t r)
Base class of VRML geometry nodes.
Definition: VrmlNodes.h:366
boost::intrusive_ptr< VrmlNodeType > dynamic_node_cast(VrmlNodePtr node)
Definition: VrmlNodes.h:907
VRML Coordinate node.
Definition: VrmlNodes.h:512
VRML Group node.
Definition: VrmlNodes.h:236
VRML IndexedFaseSet node.
Definition: VrmlNodes.h:483
HRP_UTIL_EXPORT void calcTransformMatrix(VrmlTransform *transform, Matrix44 &out_T)
Definition: Eigen4d.cpp:49
virtual int countChildren()
Definition: VrmlNodes.cpp:144
virtual ShapeInfoSequence * shapes()
void setNormals(AppearanceInfo &appInfo, VrmlIndexedFaceSet *triangleMesh)
bool convertBox(VrmlBox *box, VrmlIndexedFaceSetPtr &triangleMesh)
png_bytep png_bytep png_size_t length
Definition: png.h:1541
boost::intrusive_ptr< VrmlPixelTexture > VrmlPixelTexturePtr
Definition: VrmlNodes.h:582
png_uint_32 i
Definition: png.h:2735
Eigen::Matrix4d Matrix44
Definition: Eigen4d.h:18
AppearanceInfoSequence originAppearances_
png_bytepp image
Definition: png.h:1772
void applyTriangleMeshShaper(VrmlNodePtr node)
virtual TextureInfoSequence * textures()
PortableServer::POA_var poa
Eigen::Vector3d Vector3
Definition: EigenTypes.h:11
VRML Inline node.
Definition: VrmlNodes.h:268
bool isCategoryOf(VrmlNodeCategory category)
Definition: VrmlNodes.cpp:60
Eigen::Matrix3d Matrix33
Definition: EigenTypes.h:12
std::string SFString
Definition: VrmlNodes.h:52
AppearanceInfoSequence appearances_
VrmlTextureCoordinatePtr texCoord
Definition: VrmlNodes.h:489
virtual VrmlNode * getChild(int index)
Definition: VrmlNodes.cpp:150
ShapeNodeToShapeInfoIndexMap shapeInfoIndexMap
def j(str, encoding="cp932")
VRML Box node.
Definition: VrmlNodes.h:373
std::vector< SFVec3f > MFVec3f
Definition: VrmlNodes.h:72
VRML Sphere node.
Definition: VrmlNodes.h:412
SFInt32 whichChoice
Definition: VrmlNodes.h:666
MaterialInfoSequence originMaterials_
boost::intrusive_ptr< VrmlTexture > VrmlTexturePtr
Definition: VrmlNodes.h:298
boost::intrusive_ptr< VrmlAppearance > VrmlAppearancePtr
Definition: VrmlNodes.h:277
VrmlNormalPtr normal
Definition: VrmlNodes.h:488
TextureInfoSequence textures_
png_bytepp row
Definition: png.h:1759
Header file of Image Converter class.
VrmlNodePtr actualNode
Definition: VrmlNodes.h:888
Eigen::Vector4d Vector4
Definition: Eigen4d.h:21
SFVec3f SFColor
Definition: VrmlNodes.h:58
int numComponents
Definition: VrmlNodes.h:64
VRML node which is instance of VRML Prototype.
Definition: VrmlNodes.h:883
VrmlNodePtr apply(VrmlNodePtr topNode)
HRP_UTIL_EXPORT SFImage * convert(string url)
convert ImageTexture node to PixelTexture node
void setPrimitiveProperties(ShapeInfo &shapeInfo, VrmlShape *shapeNode)
boost::intrusive_ptr< VrmlNode > VrmlNodePtr
Definition: VrmlNodes.h:155
void setColdetModel(ColdetModelPtr &coldetModel, TransformedShapeIndexSequence shapeIndices, const Matrix44 &Tparent, int &vertexIndex, int &triangleIndex)
VrmlAppearancePtr appearance
Definition: VrmlNodes.h:289
VRML Cylinder node.
Definition: VrmlNodes.h:397
virtual VrmlNode * getChild(int index)
Definition: VrmlNodes.cpp:439
void createTextureTransformMatrix(AppearanceInfo &appInfo, VrmlTextureTransformPtr &textureTransform)
HRP_UTIL_EXPORT string deleteURLScheme(string url)
Definition: UrlUtil.cpp:25
boost::array< SFFloat, 3 > SFVec3f
Definition: VrmlNodes.h:55
ShapeInfoSequence shapes_
ShapeSetInfo_impl(PortableServer::POA_ptr poa)
boost::intrusive_ptr< VrmlIndexedFaceSet > VrmlIndexedFaceSetPtr
Definition: VrmlNodes.h:498
virtual PortableServer::POA_ptr _default_POA()
static void putMessage(const std::string &message)
VrmlColorPtr color
Definition: VrmlNodes.h:466
SFNode geometry
Definition: VrmlNodes.h:290
MaterialInfoSequence materials_
VRML Transform node.
Definition: VrmlNodes.h:254
void setTriangleMesh(ShapeInfo &shapeInfo, VrmlIndexedFaceSet *triangleMesh)
SFNode getOriginalGeometry(VrmlShapePtr shapeNode)
TriangleMeshShaper triangleMeshShaper
void traverseShapeNodes(VrmlNode *node, const Matrix44 &T, TransformedShapeIndexSequence &io_shapeIndices, DblArray12Sequence &inlinedShapeM, const SFString *url=NULL)
boost::intrusive_ptr< ColdetModel > ColdetModelPtr
Definition: ColdetModel.h:268
VRML PixelTexture node.
Definition: VrmlNodes.h:572
std::vector< SFInt32 > MFInt32
Definition: VrmlNodes.h:69
void setColdetModelTriangles(ColdetModelPtr &coldetModel, const TransformedShapeIndex &tsi, const Matrix44 &Tparent, int &vertexIndex, int &triangleIndex)
std::map< std::string, time_t > fileTimeMap
MFString urls
Definition: VrmlNodes.h:272
string setTexturefileUrl(string modelfileDir, MFString urls)
Definition: VrmlUtil.cpp:210
int createMaterialInfo(VrmlMaterialPtr &materialNode)
void setTexCoords(AppearanceInfo &appInfo, VrmlIndexedFaceSet *triangleMesh)
void setColors(AppearanceInfo &appInfo, VrmlIndexedFaceSet *triangleMesh)
boost::intrusive_ptr< VrmlMaterial > VrmlMaterialPtr
Definition: VrmlNodes.h:295
Definition: jquant2.c:258
ShapeInfoSequence originShapes_


openhrp3
Author(s): AIST, General Robotix Inc., Nakamura Lab of Dept. of Mechano Informatics at University of Tokyo
autogenerated on Sat May 8 2021 02:42:41