24 using namespace boost;
28 const double PI = 3.14159265358979323846;
62 bool convertShapeNode(
VrmlShape* shapeNode);
65 template <
class TArray>
66 bool remapDirectMapObjectsPerFaces(TArray& objects,
const char* objectName);
68 bool checkAndRemapIndices(RemapType
type,
unsigned int numElements,
MFInt32& indices,
bool perVertex,
70 void putError1(
const char* valueName);
85 void putMessage(
const std::string& message);
90 TriangleMeshShaper::TriangleMeshShaper()
148 SFNode originalGeometryNode;
151 originalGeometryNode = p->second;
153 return originalGeometryNode;
189 for(
int i = 0;
i < numChildren;
i++){
198 putMessage(
"Node is inconvertible and removed from the scene graph");
226 triangleMesh = faceSet;
271 int numVertices = vertices.size();
274 const MFInt32 orgIndices = indices;
277 const int numOrgIndices = orgIndices.size();
279 int orgFaceIndex = 0;
280 int polygonTopIndexPosition = 0;
286 int triangleOrder[3];
288 triangleOrder[0] = 0; triangleOrder[1] = 1; triangleOrder[2] = 2;
290 triangleOrder[0] = 2; triangleOrder[1] = 1; triangleOrder[2] = 0;
295 for(
int i=0;
i < numOrgIndices; ++
i){
296 int index = orgIndices[
i];
297 if(index >= numVertices){
298 putMessage(
"The coordIndex field has an index over the size of the vertices in the coord field");
299 }
else if(index >= 0){
304 for(
int j=0; j < numTriangles; ++j){
305 for(
int k=0; k < 3; ++k){
306 int localIndex = triangles[j * 3 + triangleOrder[k]];
307 indices.push_back(
polygon[localIndex]);
310 indices.push_back(-1);
314 polygonTopIndexPosition =
i + 1;
322 int numColors = faceSet->
color ? faceSet->
color->color.size() : 0;
326 int numNormals = faceSet->
normal ? faceSet->
normal->vector.size() : 0;
330 if(numNormals > 0 && !faceSet->
ccw){
333 for(
unsigned int i=0;
i < normals.size(); ++
i){
344 return (result && !indices.empty());
348 template <
class TArray>
351 const TArray orgValues = values;
352 int numOrgValues = orgValues.size();
354 values.resize(numFaces);
355 for(
int i=0;
i < numFaces; ++
i){
357 if(faceIndex >= numOrgValues){
358 putMessage(
string(
"The number of ") + valueName +
" is less than the number of faces.");
361 values[
i] = orgValues[faceIndex];
370 const char* valueName = (
type==REMAP_COLOR) ?
"colors" :
"normals" ;
374 if(numElements == 0){
375 if(!indices.empty()){
376 putMessage(
string(
"An IndexedFaceSet has no ") + valueName +
377 ", but it has a non-empty index field of " + valueName +
".");
385 if(numElements < triangleMesh->coord->point.size()){
386 putMessage(
string(
"The number of ") + valueName +
387 " is less than the number of vertices.");
391 if(
type == REMAP_COLOR){
392 remapDirectMapObjectsPerFaces(triangleMesh->
color->color, valueName);
393 }
else if(
type == REMAP_NORMAL){
394 remapDirectMapObjectsPerFaces(triangleMesh->
normal->vector, valueName);
398 const MFInt32 orgIndices = indices;
401 int numNewIndices = indexPositionMap.size();
402 indices.resize(numNewIndices);
403 for(
int i=0;
i < numNewIndices; ++
i){
404 int orgPosition = indexPositionMap[
i];
408 int index = orgIndices[orgPosition];
409 if(index < (
int)numElements){
412 putError1(valueName);
418 int numNewIndices = faceIndexMap.size();
419 indices.resize(numNewIndices);
420 for(
int i=0;
i < numNewIndices; ++
i){
421 int orgFaceIndex = faceIndexMap[
i];
422 int index = orgIndices[orgFaceIndex];
423 if(index < (
int)numElements){
426 putError1(valueName);
442 MFInt32& texCoordIndex = faseSet->texCoordIndex;
443 MFInt32& coordIndex = faseSet->coordIndex;
446 if(texCoordIndex.empty()){
447 texCoordIndex.resize(coordIndex.size());
448 copy( coordIndex.begin(), coordIndex.end(), texCoordIndex.begin() );
450 const MFInt32 orgIndices = texCoordIndex;
452 texCoordIndex.resize(numNewIndices);
453 for(
int i=0;
i < numNewIndices; ++
i){
455 texCoordIndex[
i] = -1;
458 if(index < (
int)texCoord->point.size()){
459 texCoordIndex[
i] = index;
474 putMessage(
string(
"There is an index of ") + valueName +
475 " beyond the size of " + valueName +
".");
481 inline int addVertex(
MFVec3f& vertices,
const double x,
const double y,
const double z)
487 vertices.push_back(v);
488 return vertices.size() - 1;
491 inline void addTriangle(
MFInt32& indices,
int x,
int y,
int z)
493 indices.push_back(x);
494 indices.push_back(y);
495 indices.push_back(z);
496 indices.push_back(-1);
503 const double x =
box->size[0] / 2.0;
504 const double y =
box->size[1] / 2.0;
505 const double z =
box->size[2] / 2.0;
507 if(x < 0.0 || y < 0.0 || z < 0.0 ){
512 MFVec3f& vertices = triangleMesh->coord->point;
515 static const int numTriangles = 12;
517 static const double xsigns[] = { -1.0, -1.0, -1.0, -1.0, 1.0, 1.0, 1.0, 1.0 };
518 static const double ysigns[] = { -1.0, -1.0, 1.0, 1.0, -1.0, -1.0, 1.0, 1.0 };
519 static const double zsigns[] = { -1.0, 1.0, 1.0, -1.0, -1.0, 1.0, 1.0, -1.0 };
521 static const int triangles[] = {
536 for(
int i=0;
i < 8; ++
i){
537 addVertex(vertices, xsigns[
i] * x, ysigns[
i] * y, zsigns[
i] * z);
540 MFInt32& indices = triangleMesh->coordIndex;
541 indices.resize(numTriangles * 4);
545 for(
int i=0;
i < numTriangles;
i++){
546 indices[di++] = triangles[si++];
547 indices[di++] = triangles[si++];
548 indices[di++] = triangles[si++];
558 triangleMesh->coord = pointSet->
coord;
559 triangleMesh->color = pointSet->
color;
569 if(cone->
height < 0.0 || radius < 0.0 ){
574 MFVec3f& vertices = triangleMesh->coord->point;
579 addVertex(vertices, radius * cos(angle), -cone->
height/2.0, radius * sin(angle));
582 const int topIndex = addVertex(vertices, 0.0, cone->
height/2.0, 0.0);
583 const int bottomCenterIndex = addVertex(vertices, 0.0, -cone->
height/2.0, 0.0);
585 MFInt32& indices = triangleMesh->coordIndex;
597 triangleMesh->creaseAngle = 3.14 / 2.0;
610 MFVec3f& vertices = triangleMesh->coord->point;
614 const double y = cylinder->
height / 2.0;
620 vtop[0] = vbottom[0] = cylinder->
radius * cos(angle);
621 vtop[2] = vbottom[2] = cylinder->
radius * sin(angle);
626 const int topCenterIndex = addVertex(vertices, 0.0, y, 0.0);
627 const int bottomCenterIndex = addVertex(vertices, 0.0, -y, 0.0);
629 MFInt32& indices = triangleMesh->coordIndex;
647 triangleMesh->creaseAngle = 3.14 / 2.0;
655 const double r = sphere->
radius;
665 MFVec3f& vertices = triangleMesh->coord->point;
666 vertices.reserve((vdn - 1) * hdn + 2);
668 for(
int i=1;
i < vdn;
i++){
669 double tv =
i *
PI / vdn;
670 for(
int j=0; j < hdn; j++){
671 double th = j * 2.0 *
PI / hdn;
672 addVertex(vertices, r*sin(tv)*cos(th), r*cos(tv), r*sin(tv)*sin(th));
676 const int topIndex = addVertex(vertices, 0.0, r, 0.0);
677 const int bottomIndex = addVertex(vertices, 0.0, -r, 0.0);
679 MFInt32& indices = triangleMesh->coordIndex;
680 indices.reserve(vdn * hdn * 2 * 4);
683 for(
int i=0;
i < hdn; ++
i){
684 addTriangle(indices, topIndex, (
i+1) % hdn,
i);
688 for(
int i=0;
i < vdn - 2; ++
i){
689 const int upper =
i * hdn;
690 const int lower = (
i + 1) * hdn;
691 for(
int j=0; j < hdn; ++j) {
693 addTriangle(indices, j + upper, ((j + 1) % hdn) + lower, j + lower);
695 addTriangle(indices, j + upper, ((j + 1) % hdn) + upper, ((j + 1) % hdn) + lower);
700 const int offset = (vdn - 2) * hdn;
701 for(
int i=0;
i < hdn; ++
i){
702 addTriangle(indices, bottomIndex, (
i % hdn) + offset, ((
i+1) % hdn) + offset);
705 triangleMesh->creaseAngle =
PI;
721 MFVec3f& vertices = triangleMesh->coord->point;
730 MFInt32& indices = triangleMesh->coordIndex;
736 for(
int x=0; x < grid->xDimension - 1; ++x){
738 addTriangle(indices, x + current, x + next, (x + 1) + next);
739 addTriangle(indices, x + current, (x + 1) + next, (x + 1) + current);
741 addTriangle(indices, x + current, (x + 1) + next, x + next);
742 addTriangle(indices, x + current, (x + 1) + current, (x + 1) + next);
748 triangleMesh->ccw =
true;
750 triangleMesh->solid = grid->
solid;
753 triangleMesh->texCoord->point.resize(grid->
texCoord->point.size());
754 copy(grid->
texCoord->point.begin(), grid->
texCoord->point.end(), triangleMesh->texCoord->point.begin());
755 triangleMesh->texCoordIndex.resize(indices.size());
756 copy(indices.begin(), indices.end(), triangleMesh->texCoordIndex.begin());
765 bool isClosed =
false;
766 int numSpine = extrusion->
spine.size();
768 if( extrusion->
spine[0][0] == extrusion->
spine[numSpine-1][0] &&
769 extrusion->
spine[0][1] == extrusion->
spine[numSpine-1][1] &&
770 extrusion->
spine[0][2] == extrusion->
spine[numSpine-1][2] )
772 bool crossSectionisClosed =
false;
775 crossSectionisClosed =
true;
777 MFVec3f& vertices = triangleMesh->coord->point;
778 vertices.reserve(numSpine*numcross);
782 std::vector<Vector3> Yaxisarray;
783 std::vector<Vector3> Zaxisarray;
785 for(
int i=0;
i<numSpine;
i++){
786 Vector3 spine1, spine2, spine3;
793 Yaxis = spine3-spine1;
794 Zaxis = (spine3-spine2).
cross(spine1-spine2);
799 Yaxis = spine2-spine1;
800 Zaxis = (spine3-spine2).
cross(spine1-spine2);
802 }
else if(
i==numSpine-1){
807 Yaxis = spine3-spine1;
808 Zaxis = (spine3-spine2).
cross(spine1-spine2);
813 Yaxis = spine3-spine2;
814 Zaxis = (spine3-spine2).
cross(spine1-spine2);
820 Yaxis = spine3-spine1;
821 Zaxis = (spine3-spine2).
cross(spine1-spine2);
831 Yaxisarray.push_back(Yaxis);
832 Zaxisarray.push_back(Zaxis);
839 Yaxis = spine2-spine1;
840 Yaxisarray.push_back(Yaxis);
841 Yaxisarray.push_back(Yaxis);
843 for(
int i=0;
i<numSpine;
i++){
845 if(definedZaxis==-1){
846 Vector3 y(Yaxisarray[
i].normalized());
849 R[0] = y[2]; R[1] = 0.0; R[2] = -y[0]; R[3] = acos(y[1]);
853 Zaxisarray[
i] = Zaxisarray[definedZaxis];
854 if(
i && Zaxisarray[
i].
dot(Zaxisarray[
i-1])<0 )
856 Vector3 y(Yaxisarray[
i].normalized());
857 Vector3 z(Zaxisarray[
i].normalized());
867 if(extrusion->
scale.size()==1)
879 for(
int j=0; j<numcross; j++){
881 Vector3 v1(crossSection[0]*scale[0], 0, crossSection[2]*scale[2]);
882 Vector3 v2(Scp*orientation*v1+spine);
883 addVertex(vertices,v2[0], v2[1], v2[2]);
887 MFInt32& indices = triangleMesh->coordIndex;
888 for(
int i=0;
i < numSpine-1 ;
i++){
889 const int upper =
i * numcross;
890 const int lower = (
i + 1) * numcross;
891 for(
int j=0; j < numcross-1; ++j) {
894 addTriangle(indices, j + upper, (j + 1)+ lower, j + lower);
896 addTriangle(indices, j + upper, (j + 1)+ upper, j + 1 + lower);
898 addTriangle(indices, j + upper, j + lower, (j + 1) + lower);
899 addTriangle(indices, j + upper, (j + 1)+ lower, j + 1 + upper);
905 if(crossSectionisClosed)
907 if(extrusion->
beginCap && !isClosed){
910 for(
int i=0;
i<numcross-j;
i++)
914 for(
unsigned int i=0;
i<triangles.size();
i+=3 )
922 if(extrusion->
endCap && !isClosed){
925 for(
int i=0;
i<numcross-j;
i++)
926 polygon.push_back(numcross*(numSpine-1)+
i);
929 for(
unsigned int i=0;
i<triangles.size();
i+=3 )
937 triangleMesh->creaseAngle = extrusion->
creaseAngle;
938 triangleMesh->ccw =
true;
939 triangleMesh->convex =
true;
940 triangleMesh->solid = extrusion->
solid;
949 triangleMesh->normalPerVertex = (triangleMesh->creaseAngle > 0.0) ? true :
false;
953 if(triangleMesh->normalPerVertex){
963 const MFVec3f& vertices = triangleMesh->coord->point;
964 const int numVertices = vertices.size();
965 const MFInt32& triangles = triangleMesh->coordIndex;
966 const int numFaces = triangles.size() / 4;
970 if(triangleMesh->normalPerVertex){
975 for(
int faceIndex=0; faceIndex < numFaces; ++faceIndex){
981 if ( ! normal.isZero() ) {
986 if(triangleMesh->normalPerVertex){
987 for(
int i=0;
i < 3; ++
i){
988 int vertexIndex = triangles[faceIndex * 4 +
i];
990 bool isSameNormalFaceFound =
false;
991 for(
unsigned int j=0; j < facesOfVertex.size(); ++j){
993 const Vector3 d(otherNormal - normal);
995 if(d.dot(d) <= numeric_limits<double>::epsilon()){
996 isSameNormalFaceFound =
true;
1000 if(!isSameNormalFaceFound){
1001 facesOfVertex.push_back(faceIndex);
1011 const MFVec3f& vertices = triangleMesh->coord->point;
1012 const int numVertices = vertices.size();
1013 const MFInt32& triangles = triangleMesh->coordIndex;
1014 const int numFaces = triangles.size() / 4;
1016 MFVec3f& normals = triangleMesh->normal->vector;
1017 MFInt32& normalIndices = triangleMesh->normalIndex;
1018 normalIndices.clear();
1019 normalIndices.reserve(triangles.size());
1026 for(
int faceIndex=0; faceIndex < numFaces; ++faceIndex){
1028 for(
int i=0;
i < 3; ++
i){
1030 int vertexIndex = triangles[faceIndex * 4 +
i];
1033 Vector3 normal = currentFaceNormal;
1034 bool normalIsFaceNormal =
true;
1037 for(
unsigned int j=0; j < facesOfVertex.size(); ++j){
1038 int adjoiningFaceIndex = facesOfVertex[j];
1040 double currentFaceNormalLen = currentFaceNormal.norm();
1041 if (currentFaceNormalLen == 0)
continue;
1042 double adjoiningFaceNormalLen = adjoiningFaceNormal.norm();
1043 if (adjoiningFaceNormalLen == 0)
continue;
1044 double cosAngle = currentFaceNormal.dot(adjoiningFaceNormal)
1045 / (currentFaceNormalLen * adjoiningFaceNormalLen);
1046 if (cosAngle > 1.0) cosAngle = 1.0;
1047 if (cosAngle < -1.0) cosAngle = -1.0;
1048 double angle = acos(cosAngle);
1049 if(angle > 1.0e-6 && angle < triangleMesh->creaseAngle){
1050 normal += adjoiningFaceNormal;
1051 normalIsFaceNormal =
false;
1055 if(!normalIsFaceNormal){
1059 int normalIndex = -1;
1061 for(
int j=0; j < 3; ++j){
1062 int vertexIndex2 = triangles[faceIndex * 4 + j];
1064 for(
unsigned int k=0; k < normalIndicesOfVertex.size(); ++k){
1065 int index = normalIndicesOfVertex[k];
1066 const SFVec3f& norg = normals[index];
1068 if(d.dot(d) <= numeric_limits<double>::epsilon()){
1069 normalIndex = index;
1070 goto normalIndexFound;
1074 if(normalIndex < 0){
1076 n[0] = normal[0];
n[1] = normal[1];
n[2] = normal[2];
1077 normalIndex = normals.size();
1078 normals.push_back(
n);
1083 normalIndices.push_back(normalIndex);
1085 normalIndices.push_back(-1);
1092 const MFInt32& triangles = triangleMesh->coordIndex;
1093 const int numFaces = triangles.size() / 4;
1095 MFVec3f& normals = triangleMesh->normal->vector;
1096 MFInt32& normalIndices = triangleMesh->normalIndex;
1097 normalIndices.clear();
1098 normalIndices.reserve(numFaces);
1100 const int numVertices = triangleMesh->coord->point.size();
1104 for(
int faceIndex=0; faceIndex < numFaces; ++faceIndex){
1107 int normalIndex = -1;
1110 for(
int i=0;
i < 3; ++
i){
1111 int vertexIndex = triangles[faceIndex * 4 +
i];
1113 for(
unsigned int j=0; j < normalIndicesOfVertex.size(); ++j){
1114 int index = normalIndicesOfVertex[j];
1115 const SFVec3f& norg = normals[index];
1116 const Vector3 n(norg[0], norg[1], norg[2]);
1117 if((
n - normal).
norm() <= numeric_limits<double>::epsilon()){
1118 normalIndex = index;
1119 goto normalIndexFound2;
1123 if(normalIndex < 0){
1125 n[0] = normal[0];
n[1] = normal[1];
n[2] = normal[2];
1126 normalIndex = normals.size();
1127 normals.push_back(
n);
1128 for(
int i=0;
i < 3; ++
i){
1129 int vertexIndex = triangles[faceIndex * 4 +
i];
1134 normalIndices.push_back(normalIndex);
1142 self->sigMessage(message +
"\n" );
1154 if (!originalGeometry){
1160 if(originalGeometry){
1161 if(
dynamic_cast<VrmlBox*
>(originalGeometry)){
1163 }
else if(
dynamic_cast<VrmlCone*
>(originalGeometry)){
1165 }
else if(
dynamic_cast<VrmlCylinder*
>(originalGeometry)){
1183 float max[3]={
static_cast<float> (triangleMesh->
coord->point[0][0]),
1184 static_cast<float> (triangleMesh->
coord->point[0][1]),
1185 static_cast<float> (triangleMesh->
coord->point[0][2])};
1186 float min[3]={
static_cast<float> (triangleMesh->
coord->point[0][0]),
1187 static_cast<float> (triangleMesh->
coord->point[0][1]),
1188 static_cast<float> (triangleMesh->
coord->point[0][2])};
1189 int n = triangleMesh->
coord->point.size();
1190 for(
int i=1;
i<
n;
i++){
1191 for(
int j=0; j<3; j++){
1192 float w = triangleMesh->
coord->point[
i][j];
1197 float size[3]={0,0,0};
1198 for(
int j=0; j<3; j++)
1203 ( s=0 , t=
size[1] >=
size[2] ? 1 : 2 )
1206 ( s=1 , t=
size[0] >=
size[2] ? 0 : 2 )
1210 for(
int i=0;
i<
n;
i++){
1212 point[0] = (triangleMesh->
coord->point[
i][s]-
min[s])/
size[s];
1213 point[1] = (triangleMesh->
coord->point[
i][t]-
min[t])/
size[t]*ratio;
1214 triangleMesh->
texCoord->point.push_back(point);
1228 for(
unsigned int i=0;
i<triangleMesh->
coord->point.size();
i++){
1230 point[0] = (triangleMesh->
coord->point[
i][0])/xmax;
1231 point[1] = (triangleMesh->
coord->point[
i][2])/zmax;
1232 triangleMesh->
texCoord->point.push_back(point);
1242 if(point[0][0] <= 0 && point[1][0] <= 0 && point[2][0] <= 0 )
return LEFT;
1243 if(point[0][0] > 0 && point[1][0] > 0 && point[2][0] > 0 )
return RIGHT;
1244 if(point[0][1] <= 0 && point[1][1] <= 0 && point[2][1] <= 0 )
return BOTTOM;
1245 if(point[0][1] > 0 && point[1][1] > 0 && point[2][1] > 0 )
return TOP;
1246 if(point[0][2] <= 0 && point[1][2] <= 0 && point[2][2] <= 0 )
return BACK;
1247 if(point[0][2] > 0 && point[1][2] > 0 && point[2][2] > 0 )
return FRONT;
1254 for(
unsigned int i=0;
i<points.size();
i++){
1255 if((points[
i][0]-target[0])*(points[
i][0]-target[0]) +
1256 (points[
i][1]-target[1])*(points[
i][1]-target[1]) < 1.0e-9 )
1265 double angle = atan2( point[2], point[0] );
1266 if(angle>=0) angle=1.5*
PI-angle;
1267 else if(-0.5*
PI<angle) angle=-angle+1.5*
PI;
1268 else angle=-angle-0.5*
PI;
1277 point[0] = 0.0; point[1] = 0.0;
1278 triangleMesh->
texCoord->point.push_back(point);
1279 point[0] = 1.0; point[1] = 0.0;
1280 triangleMesh->
texCoord->point.push_back(point);
1281 point[0] = 0.0; point[1] = 1.0;
1282 triangleMesh->
texCoord->point.push_back(point);
1283 point[0] = 1.0; point[1] = 1.0;
1284 triangleMesh->
texCoord->point.push_back(point);
1286 for(
int i=0;
i<12;
i++){
1288 for(
int j=0; j<3; j++)
1292 for(
int j=0; j<3; j++){
1293 if(point[j][1] > 0 && point[j][2] > 0 ) triangleMesh->
texCoordIndex.push_back(3);
1294 else if(point[j][1] > 0 && point[j][2] <= 0 ) triangleMesh->
texCoordIndex.push_back(2);
1295 else if(point[j][1] <= 0 && point[j][2] > 0 ) triangleMesh->
texCoordIndex.push_back(1);
1296 else if(point[j][1] <= 0 && point[j][2] <= 0 ) triangleMesh->
texCoordIndex.push_back(0);
1300 for(
int j=0; j<3; j++){
1301 if(point[j][1] > 0 && point[j][2] > 0 ) triangleMesh->
texCoordIndex.push_back(2);
1302 else if(point[j][1] > 0 && point[j][2] <= 0 ) triangleMesh->
texCoordIndex.push_back(3);
1303 else if(point[j][1] <= 0 && point[j][2] > 0 ) triangleMesh->
texCoordIndex.push_back(0);
1304 else if(point[j][1] <= 0 && point[j][2] <= 0 ) triangleMesh->
texCoordIndex.push_back(1);
1308 for(
int j=0; j<3; j++){
1309 if(point[j][2] > 0 && point[j][0] > 0 ) triangleMesh->
texCoordIndex.push_back(3);
1310 else if(point[j][2] > 0 && point[j][0] <= 0 ) triangleMesh->
texCoordIndex.push_back(2);
1311 else if(point[j][2] <= 0 && point[j][0] > 0 ) triangleMesh->
texCoordIndex.push_back(1);
1312 else if(point[j][2] <= 0 && point[j][0] <= 0 ) triangleMesh->
texCoordIndex.push_back(0);
1316 for(
int j=0; j<3; j++){
1317 if(point[j][2] > 0 && point[j][0] > 0 ) triangleMesh->
texCoordIndex.push_back(1);
1318 else if(point[j][2] > 0 && point[j][0] <= 0 ) triangleMesh->
texCoordIndex.push_back(0);
1319 else if(point[j][2] <= 0 && point[j][0] > 0 ) triangleMesh->
texCoordIndex.push_back(3);
1320 else if(point[j][2] <= 0 && point[j][0] <= 0 ) triangleMesh->
texCoordIndex.push_back(2);
1324 for(
int j=0; j<3; j++){
1325 if(point[j][1] > 0 && point[j][0] > 0 ) triangleMesh->
texCoordIndex.push_back(2);
1326 else if(point[j][1] > 0 && point[j][0] <= 0 ) triangleMesh->
texCoordIndex.push_back(3);
1327 else if(point[j][1] <= 0 && point[j][0] > 0 ) triangleMesh->
texCoordIndex.push_back(0);
1328 else if(point[j][1] <= 0 && point[j][0] <= 0 ) triangleMesh->
texCoordIndex.push_back(1);
1332 for(
int j=0; j<3; j++){
1333 if(point[j][1] > 0 && point[j][0] > 0 ) triangleMesh->
texCoordIndex.push_back(3);
1334 else if(point[j][1] > 0 && point[j][0] <= 0 ) triangleMesh->
texCoordIndex.push_back(2);
1335 else if(point[j][1] <= 0 && point[j][0] > 0 ) triangleMesh->
texCoordIndex.push_back(1);
1336 else if(point[j][1] <= 0 && point[j][0] <= 0 ) triangleMesh->
texCoordIndex.push_back(0);
1351 texPoint[0] = 0.5; texPoint[1] = 0.5;
1352 triangleMesh->
texCoord->point.push_back(texPoint);
1354 for(
unsigned int i=0;
i<triangleMesh->
coordIndex.size();
i++){
1358 for(
int j=0; j<3; j++){
1360 if(point[j][1] > 0) top = j;
1361 if(point[j][0] == 0.0 && point[j][2] == 0.0) center = j;
1364 double s[3]={0,0,0};
1366 for(
int j=0; j<3; j++){
1371 if(s[pre] > 0.5 && s[j] < 1.0e-6)
1377 for(
int j=0; j<3; j++){
1382 texPoint[0] = (s[0]+s[1]+s[2])/2.0;
1389 triangleMesh->
texCoord->point.push_back(texPoint);
1395 for(
int j=0; j<3; j++){
1397 double angle = atan2( point[j][2], point[j][0] );
1398 texPoint[0] = 0.5 + 0.5*cos(angle);
1399 texPoint[1] = 0.5 + 0.5*sin(angle);
1404 triangleMesh->
texCoord->point.push_back(texPoint);
1421 texPoint[0] = 0.5; texPoint[1] = 0.5;
1422 triangleMesh->
texCoord->point.push_back(texPoint);
1424 for(
unsigned int i=0;
i<triangleMesh->
coordIndex.size();
i++){
1428 for(
int j=0; j<3; j++){
1431 if(point[0][1] == point[j][1] ) notside &=
true;
1432 else notside &=
false;
1434 if(point[j][0] == 0.0 && point[j][2] == 0.0) center = j;
1438 double s[3]={0,0,0};
1439 for(
int j=0; j<3; j++){
1445 for(
int j=0; j<3; j++){
1446 if(over && s[j]<1.0e-6)
1449 if(point[j][1] > 0) texPoint[1] = 1.0;
1450 else texPoint[1] = 0.0;
1455 triangleMesh->
texCoord->point.push_back(texPoint);
1461 for(
int j=0; j<3; j++){
1463 double angle = atan2( point[j][2], point[j][0] );
1464 texPoint[0] = 0.5 + 0.5*cos(angle);
1466 texPoint[1] = 0.5 - 0.5*sin(angle);
1468 texPoint[1] = 0.5 + 0.5*sin(angle);
1473 triangleMesh->
texCoord->point.push_back(texPoint);
1491 for(
unsigned int i=0;
i<triangleMesh->
coordIndex.size();
i++){
1494 double s[3]={0,0,0};
1495 for(
int j=0; j<3; j++){
1502 for(
int j=0; j<3; j++){
1503 if(over && s[j]<1.0e-6)
1506 double theta = acos(point[j][1]/radius);
1507 texPoint[1] = 1.0-theta/
PI;
1512 triangleMesh->
texCoord->point.push_back(texPoint);
1523 int numSpine = extrusion->
spine.size();
1527 std::vector<double> s;
1528 std::vector<double> t;
1534 slen += sqrt(x*x+z*z);
1539 for(
unsigned int i=1;
i<extrusion->
spine.size();
i++){
1540 double x=extrusion->
spine[
i][0]-extrusion->
spine[
i-1][0];
1541 double y=extrusion->
spine[
i][1]-extrusion->
spine[
i-1][1];
1542 double z=extrusion->
spine[
i][2]-extrusion->
spine[
i-1][2];
1543 tlen += sqrt(x*x+y*y+z*z);
1546 for(
unsigned int i=0;
i<extrusion->
spine.size();
i++){
1548 point[1] = t[
i]/tlen;
1549 for(
unsigned int j=0; j<extrusion->
crossSection.size(); j++){
1550 point[0] = s[j]/slen;
1551 triangleMesh->
texCoord->point.push_back(point);
1555 int endofspin = (numSpine-1)*(numcross-1)*2*4;
1559 int endofbegincap = endofspin;
1560 int endofpoint = triangleMesh->
texCoord->point.size();
1564 endofbegincap += (triangleMesh->
coordIndex.size()-endofspin)/2;
1566 endofbegincap = triangleMesh->
coordIndex.size();
1577 double xsize = xmax-xmin;
1578 double zsize = zmax-zmin;
1579 for(
int i=0;
i<numcross;
i++){
1583 triangleMesh->
texCoord->point.push_back(point);
1585 for(
int i=endofspin;
i<endofbegincap;
i++){
1605 double xsize = xmax-xmin;
1606 double zsize = zmax-zmin;
1611 triangleMesh->
texCoord->point.push_back(point);
1613 for(
unsigned int i=endofbegincap;
i<triangleMesh->
coordIndex.size();
i++){