20 #include <boost/bind.hpp> 23 #include <hrpCorba/ViewSimulator.hh> 32 using namespace boost;
37 poa(PortableServer::POA::_duplicate(poa))
52 return PortableServer::POA::_duplicate(
poa);
76 string::size_type
n, nb = 0;
78 while ((n = str.find(sb,nb)) != string::npos){
79 str.replace(n,sb.size(),sa);
89 return new ShapeInfoSequence(
shapes_);
107 return new TextureInfoSequence(
textures_);
124 (
VrmlNode* node,
const Matrix44& T, TransformedShapeIndexSequence& io_shapeIndices, DblArray12Sequence& inlinedShapeM,
const SFString* url)
126 static int inline_count=0;
139 inlineNode =
dynamic_cast<VrmlInline*
>(groupNode);
143 int inlinedShapeMIndex = inlinedShapeM.length();
144 inlinedShapeM.length(inlinedShapeMIndex+1);
147 for(
int col=0; col < 4; ++col){
148 inlinedShapeM[inlinedShapeMIndex][p++] = T(
row, col);
151 url_ = inlineNode->
urls[0];
154 for( MFString::iterator ite = inlineNode->
urls.begin(); ite != inlineNode->
urls.end(); ++ite ){
156 struct stat statbuff;
158 if( stat( filename.c_str(), &statbuff ) == 0 ){
159 mtime = statbuff.st_mtime;
177 if( whichChoice >= 0 && whichChoice < switchNode->countChildren() )
191 short shapeInfoIndex;
195 shapeInfoIndex = p->second;
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;
207 for(
int col=0; col < 4; ++col){
208 tsi.transformMatrix[p++] = T(
row, col);
212 tsi.inlinedShapeTransformMatrixIndex=inlinedShapeM.length()-1;
214 tsi.inlinedShapeTransformMatrixIndex=-1;
224 int shapeInfoIndex = -1;
230 shapeInfoIndex =
shapes_.length();
231 shapes_.length(shapeInfoIndex + 1);
232 ShapeInfo& shapeInfo =
shapes_[shapeInfoIndex];
234 if ( url ) shapeInfo.url = CORBA::string_dup( url->c_str() );
241 return shapeInfoIndex;
248 size_t numVertices = vertices.size();
249 shapeInfo.vertices.length(numVertices * 3);
252 for(
size_t i=0;
i < numVertices; ++
i){
254 shapeInfo.vertices[pos++] = v[0];
255 shapeInfo.vertices[pos++] = v[1];
256 shapeInfo.vertices[pos++] = v[2];
260 const size_t numTriangles = indices.size() / 4;
261 shapeInfo.triangles.length(numTriangles * 3);
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++];
276 shapeInfo.primitiveType = SP_MESH;
277 FloatSequence& param = shapeInfo.primitiveParameters;
282 if(originalGeometry){
288 if(
VrmlBox*
box = dynamic_cast<VrmlBox*>(originalGeometry)){
289 shapeInfo.primitiveType = SP_BOX;
291 for(
int i=0;
i < 3; ++
i){
292 param[
i] =
box->size[
i];
295 }
else if(
VrmlCone* cone = dynamic_cast<VrmlCone*>(originalGeometry)){
296 shapeInfo.primitiveType = SP_CONE;
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;
303 }
else if(
VrmlCylinder* cylinder = dynamic_cast<VrmlCylinder*>(originalGeometry)){
304 shapeInfo.primitiveType = SP_CYLINDER;
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;
313 }
else if(
VrmlSphere* sphere = dynamic_cast<VrmlSphere*>(originalGeometry)){
314 shapeInfo.primitiveType = SP_SPHERE;
316 param[0] = sphere->radius;
322 if (protoInstance && protoInstance->
proto->protoName ==
"Plane"){
324 shapeInfo.primitiveType = SP_PLANE;
326 for (
int i=0;
i<3;
i++){
343 AppearanceInfo& appInfo =
appearances_[appearanceIndex];
347 appInfo.solid = faceSet->
solid;
349 appInfo.materialIndex = -1;
350 appInfo.textureIndex = -1;
365 if(appInfo.textureIndex != -1 ){
374 return appearanceIndex;
381 int numColors = colors.size();
382 appInfo.colors.length(numColors * 3);
385 for(
int i=0;
i < numColors; ++
i){
387 for(
int j=0; j < 3; ++j){
388 appInfo.colors[pos++] = color[j];
393 const int numOrgIndices = orgIndices.size();
394 if(numOrgIndices > 0){
396 const int numTriangles = numOrgIndices / 4;
397 appInfo.colorIndices.length(numTriangles * 3);
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++];
407 appInfo.colorIndices.length(numOrgIndices);
408 for(
int i=0;
i < numOrgIndices; ++
i){
409 appInfo.colorIndices[
i] = orgIndices[
i];
419 int numNormals = normals.size();
420 appInfo.normals.length(numNormals * 3);
423 for(
int i=0;
i < numNormals; ++
i){
425 for(
int j=0; j < 3; ++j){
426 appInfo.normals[pos++] = n[j];
431 const int numOrgIndices = orgIndices.size();
432 if(numOrgIndices > 0){
434 const int numTriangles = numOrgIndices / 4;
435 appInfo.normalIndices.length(numTriangles * 3);
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++];
445 appInfo.normalIndices.length(numOrgIndices);
446 for(
int i=0;
i < numOrgIndices; ++
i){
447 appInfo.normalIndices[
i] = orgIndices[
i];
455 int numCoords = triangleMesh->
texCoord->point.size();
456 appInfo.textureCoordinate.length(numCoords * 2);
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++];
463 for(
int i=0, pos=0;
i < numCoords;
i++ ){
465 Vector3 texCoordinate(m * point);
466 appInfo.textureCoordinate[pos++] = texCoordinate(0);
467 appInfo.textureCoordinate[pos++] = texCoordinate(1);
472 appInfo.textureCoordIndices.length(numIndex * 3 / 4);
473 for(
int i=0, j=0;
i < numIndex;
i++){
475 appInfo.textureCoordIndices[j++] = triangleMesh->
texCoordIndex[
i];
483 if(textureTransform){
485 matCT << 1, 0, textureTransform->translation[0]+textureTransform->center[0],
486 0, 1, textureTransform->translation[1]+textureTransform->center[1],
489 matR << cos(textureTransform->rotation), -sin(textureTransform->rotation), 0,
490 sin(textureTransform->rotation), cos(textureTransform->rotation), 0,
493 matCS << textureTransform->scale[0], 0, -textureTransform->center[0],
494 0, textureTransform->scale[1], -textureTransform->center[1],
497 m = matCS * matR * matCT;
499 m = Matrix33::Identity();
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);
517 int materialInfoIndex = -1;
520 MaterialInfo_var material(
new MaterialInfo());
522 material->ambientIntensity = materialNode->ambientIntensity;
523 material->shininess = materialNode->shininess;
524 material->transparency = materialNode->transparency;
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];
539 return materialInfoIndex;
554 int textureInfoIndex = -1;
558 TextureInfo_var texture(
new TextureInfo());
562 if(!pixelTextureNode){
564 if(imageTextureNode){
566 texture->url = CORBA::string_dup(url.c_str());
567 texture->repeatS = imageTextureNode->repeatS;
568 texture->repeatT = imageTextureNode->repeatT;
573 texture->width = image->
width;
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];
583 texture->numComponents = 0;
586 }
else if(pixelTextureNode){
587 texture->height = pixelTextureNode->image.height;
588 texture->width = pixelTextureNode->image.width;
589 texture->numComponents = pixelTextureNode->image.numComponents;
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];
596 texture->repeatS = pixelTextureNode->repeatS;
597 texture->repeatT = pixelTextureNode->repeatT;
605 return textureInfoIndex;
622 size_t pos = filepath.find_last_of(
"/\\");
627 if(pos != string::npos){
630 dirPath.resize(pos + 1);
637 for(
unsigned int i=0;
i < shapeIndices.length();
i++){
643 (
ColdetModelPtr& coldetModel,
const TransformedShapeIndex& tsi,
const Matrix44& Tparent,
int& vertexIndex,
int& triangleIndex)
645 short shapeIndex = tsi.shapeIndex;
646 const DblArray12& M = tsi.transformMatrix;;
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],
652 T = Tparent * Tlocal;
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]);
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);
684 box->
size[0] = boxSize[0]*2;
685 box->
size[1] = boxSize[1]*2;
686 box->
size[2] = boxSize[2]*2;
692 ShapeInfo& shapeInfo =
shapes_[shapeIndex];
695 shapeInfo.primitiveType = SP_BOX;
696 FloatSequence& param = shapeInfo.primitiveParameters;
698 for(
int i=0;
i < 3; ++
i)
700 shapeInfo.appearanceIndex = 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;
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;
741 struct stat statbuff;
743 if( stat( it->first.c_str(), &statbuff ) == 0 ){
744 mtime = statbuff.st_mtime;
746 if(it->second!=mtime){
boost::intrusive_ptr< VrmlTextureTransform > VrmlTextureTransformPtr
bool checkFileUpdateTime()
virtual MaterialInfoSequence * materials()
std::string getModelFileDirPath(const std::string &url)
std::vector< SFColor > MFColor
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)
Modifications controlling boost library behavior.
Abstract base class of all vrml nodes.
boost::intrusive_ptr< VrmlImageTexture > VrmlImageTexturePtr
virtual ~ShapeSetInfo_impl()
std::vector< unsigned char > pixels
boost::signal< void(const std::string &message)> sigMessage
int createTextureInfo(VrmlTexturePtr &textureNode, const SFString *url)
int createShapeInfo(VrmlShape *shapeNode, const SFString *url)
RTC::ReturnCode_t ret(RTC::Local::ReturnCode_t r)
void setNormalGenerationMode(bool on)
Base class of VRML geometry nodes.
boost::intrusive_ptr< VrmlNodeType > dynamic_node_cast(VrmlNodePtr node)
VRML IndexedFaseSet node.
HRP_UTIL_EXPORT void calcTransformMatrix(VrmlTransform *transform, Matrix44 &out_T)
void createAppearanceInfo()
virtual int countChildren()
virtual ShapeInfoSequence * shapes()
void setNormals(AppearanceInfo &appInfo, VrmlIndexedFaceSet *triangleMesh)
bool convertBox(VrmlBox *box, VrmlIndexedFaceSetPtr &triangleMesh)
png_bytep png_bytep png_size_t length
boost::intrusive_ptr< VrmlPixelTexture > VrmlPixelTexturePtr
AppearanceInfoSequence originAppearances_
void applyTriangleMeshShaper(VrmlNodePtr node)
virtual TextureInfoSequence * textures()
PortableServer::POA_var poa
bool isCategoryOf(VrmlNodeCategory category)
AppearanceInfoSequence appearances_
VrmlTextureCoordinatePtr texCoord
virtual VrmlNode * getChild(int index)
ShapeNodeToShapeInfoIndexMap shapeInfoIndexMap
std::vector< SFVec3f > MFVec3f
MaterialInfoSequence originMaterials_
boost::intrusive_ptr< VrmlTexture > VrmlTexturePtr
boost::intrusive_ptr< VrmlAppearance > VrmlAppearancePtr
TextureInfoSequence textures_
Header file of Image Converter class.
VRML node which is instance of VRML Prototype.
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
void setColdetModel(ColdetModelPtr &coldetModel, TransformedShapeIndexSequence shapeIndices, const Matrix44 &Tparent, int &vertexIndex, int &triangleIndex)
VrmlAppearancePtr appearance
virtual VrmlNode * getChild(int index)
void createTextureTransformMatrix(AppearanceInfo &appInfo, VrmlTextureTransformPtr &textureTransform)
HRP_UTIL_EXPORT string deleteURLScheme(string url)
boost::array< SFFloat, 3 > SFVec3f
ShapeInfoSequence shapes_
ShapeSetInfo_impl(PortableServer::POA_ptr poa)
boost::intrusive_ptr< VrmlIndexedFaceSet > VrmlIndexedFaceSetPtr
virtual PortableServer::POA_ptr _default_POA()
static void putMessage(const std::string &message)
MaterialInfoSequence materials_
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
void restoreOriginalData()
std::vector< SFInt32 > MFInt32
void setColdetModelTriangles(ColdetModelPtr &coldetModel, const TransformedShapeIndex &tsi, const Matrix44 &Tparent, int &vertexIndex, int &triangleIndex)
std::map< std::string, time_t > fileTimeMap
string setTexturefileUrl(string modelfileDir, MFString urls)
int createMaterialInfo(VrmlMaterialPtr &materialNode)
void setTexCoords(AppearanceInfo &appInfo, VrmlIndexedFaceSet *triangleMesh)
void setColors(AppearanceInfo &appInfo, VrmlIndexedFaceSet *triangleMesh)
boost::intrusive_ptr< VrmlMaterial > VrmlMaterialPtr
ShapeInfoSequence originShapes_