Triangle.java
Go to the documentation of this file.
00001 /*******************************************************************************
00002  * Copyright (c) 2012 Stefan Profanter. All rights reserved. This program and the accompanying
00003  * materials are made available under the terms of the GNU Public License v3.0 which accompanies
00004  * this distribution, and is available at http://www.gnu.org/licenses/gpl.html
00005  * 
00006  * Contributors: Stefan Profanter - initial API and implementation, Year: 2012; Andrei Stoica -
00007  * refactored implementation during the Google Summer of Code 2014
00008  ******************************************************************************/
00009 package edu.tum.cs.vis.model.util;
00010 
00011 import java.util.ArrayList;
00012 import java.util.Arrays;
00013 import java.util.HashSet;
00014 import java.util.List;
00015 import java.util.Set;
00016 import java.util.concurrent.locks.Lock;
00017 
00018 import javax.vecmath.Point2f;
00019 import javax.vecmath.Point3f;
00020 import javax.vecmath.Tuple3f;
00021 import javax.vecmath.Vector3d;
00022 import javax.vecmath.Vector3f;
00023 
00024 import org.apache.log4j.Logger;
00025 
00026 import processing.core.PConstants;
00027 import processing.core.PGraphics;
00028 
00039 public class Triangle extends DrawObject {
00040 
00044         private static final long       serialVersionUID                        = -5164768039180386782L;
00045 
00049         private static Logger           logger                                          = Logger.getLogger(Triangle.class);
00050 
00054         protected Point2f                       texPosition[];
00055 
00059         protected Vector3f                      normalVector                            = null;
00060 
00064         protected Vector3f                      cornerarea                                      = null;
00065 
00069         protected Point3f                       centroid;
00070 
00074         protected Set<Triangle>         neighbors                                       = new HashSet<Triangle>(3);
00075 
00080         protected Edge[]                        edges                                           = new Edge[3];
00081 
00085         private boolean                         isSharpTriangle                         = false;
00086 
00095         private boolean                         isSeedTriangle                          = false;
00096 
00100         private int                                     regionLabel                                     = -1;
00101 
00115         private final float[]           curvatureMinMaxValue            = { 0.0f, 0.0f, 0.0f };
00116 
00120         private boolean                         isCurvatureMinMaxValueInit      = false;
00121 
00125         private boolean                         isVisited                                       = false;
00126 
00131         public Triangle() {
00132                 super(3);
00133         }
00134 
00145         public Triangle(Tuple3f p1, Tuple3f p2, Tuple3f p3) {
00146                 this(new Vertex(p1), new Vertex(p2), new Vertex(p3));
00147         }
00148 
00165         public Triangle(Tuple3f p1, Vector3f normP1, Tuple3f p2, Vector3f normP2, Tuple3f p3,
00166                         Vector3f normP3) {
00167                 super(3);
00168                 position[0] = new Vertex(p1, normP1);
00169                 position[1] = new Vertex(p2, normP2);
00170                 position[2] = new Vertex(p3, normP3);
00171         }
00172 
00183         public Triangle(Vertex p1, Vertex p2, Vertex p3) {
00184                 super(3);
00185                 position[0] = p1;
00186                 position[1] = p2;
00187                 position[2] = p3;
00188         }
00189 
00205         public boolean addNeighbor(Triangle neighbor, Lock lock) {
00206                 boolean add = false;
00207 
00208                 add = isDirectNeighbor(neighbor, Thresholds.FAST_NEIGHBOR_DETECTION);
00209 
00210                 if (add) {
00211                         if (lock != null)
00212                                 lock.lock();
00213                         // to make sure neighbors is not cached
00214                         synchronized (neighbors) {
00215                                 neighbors.add(neighbor);
00216                         }
00217                         synchronized (neighbor.neighbors) {
00218                                 neighbor.neighbors.add(this);
00219                         }
00220                         if (lock != null)
00221                                 lock.unlock();
00222                 }
00223                 return add;
00224         }
00225 
00236         public void addNeighbor(Triangle neighbor) {
00237                 synchronized (neighbors) {
00238                         neighbors.add(neighbor);
00239                 }
00240                 synchronized (neighbor.neighbors) {
00241                         neighbor.neighbors.add(this);
00242                 }
00243 
00244         }
00245 
00253         public void removeNeighbor(Triangle n) {
00254                 if (neighbors != null) {
00255                         synchronized (neighbors) {
00256                                 neighbors.remove(n);
00257                         }
00258                 }
00259                 if (n.neighbors != null) {
00260                         synchronized (n.neighbors) {
00261                                 n.neighbors.remove(this);
00262                         }
00263                 }
00264         }
00265 
00275         public void draw(PGraphics g, DrawSettings drawSettings) {
00276                 applyColor(g, drawSettings);
00277 
00278                 if (drawSettings != null && drawSettings.drawType == DrawType.POINTS) {
00279 
00280                         for (int i = 0; i < position.length; i++) {
00281                                 if (position[i].overrideColor != null) {
00282                                         g.stroke(position[i].overrideColor.getRed(),
00283                                                         position[i].overrideColor.getGreen(),
00284                                                         position[i].overrideColor.getBlue());
00285                                         g.noFill();
00286                                 } else if (drawSettings.getOverrideColor() == null && position[i].color != null) {
00287                                         g.stroke(position[i].color.getRed(), position[i].color.getGreen(),
00288                                                         position[i].color.getBlue());
00289                                         g.noFill();
00290                                 }
00291                                 g.point(position[i].x, position[i].y, position[i].z);
00292                         }
00293                 } else {
00294                         g.beginShape(PConstants.TRIANGLES);
00295                         if (appearance == null || appearance.getImageReference() == null /*no appearance*/
00296                                         || drawSettings.getOverrideColor() != null /*override*/
00297                                         || position[0].overrideColor != null /* points have colors */) {
00298                                 // no texture only color
00299 
00300                                 for (int i = 0; i < position.length; i++) {
00301 
00302                                         if (drawSettings != null && drawSettings.drawType == DrawType.LINES) {
00303                                                 if (position[i].overrideColor != null) {
00304                                                         g.stroke(position[i].overrideColor.getRed(),
00305                                                                         position[i].overrideColor.getGreen(),
00306                                                                         position[i].overrideColor.getBlue());
00307                                                         g.noFill();
00308                                                 } else if (drawSettings.getOverrideColor() == null
00309                                                                 && position[i].color != null) {
00310                                                         g.stroke(position[i].color.getRed(), position[i].color.getGreen(),
00311                                                                         position[i].color.getBlue());
00312                                                         g.noFill();
00313                                                 }
00314                                         } else {
00315                                                 if (position[i].overrideColor != null) {
00316                                                         g.fill(position[i].overrideColor.getRed(),
00317                                                                         position[i].overrideColor.getGreen(),
00318                                                                         position[i].overrideColor.getBlue());
00319                                                 } else if ((drawSettings == null || drawSettings.getOverrideColor() == null)
00320                                                                 && position[i].color != null) {
00321                                                         g.fill(position[i].color.getRed(), position[i].color.getGreen(),
00322                                                                         position[i].color.getBlue());
00323                                                 }
00324                                         }
00325 
00326                                         if (position[i].getNormalVector() != null)
00327                                                 g.normal(position[i].getNormalVector().x, position[i].getNormalVector().y,
00328                                                                 position[i].getNormalVector().z);
00329                                         g.vertex(position[i].x, position[i].y, position[i].z);
00330                                 }
00331 
00332                         } else {
00333                                 // has texture
00334                                 g.texture(appearance.getImageReference());
00335 
00336                                 for (int i = 0; i < position.length; i++) {
00337 
00338                                         g.vertex(position[i].x, position[i].y, position[i].z, texPosition[i].x,
00339                                                         texPosition[i].y);
00340 
00341                                 }
00342 
00343                         }
00344                         g.endShape();
00345                 }
00346         }
00347 
00353         public float getArea() {
00354                 if (position.length == 3) {
00355 
00356                         Point3f v = (Point3f) position[1].clone();
00357                         v.sub(position[0]);
00358                         Point3f w = (Point3f) position[2].clone();
00359                         w.sub(position[0]);
00360 
00361                         Vector3f v1 = new Vector3f(v);
00362                         Vector3f w1 = new Vector3f(w);
00363 
00364                         Vector3f cross = new Vector3f();
00365                         cross.cross(v1, w1);
00366                         return cross.length() / 2f;
00367                 }
00368 
00369                 logger.error("getArea not implemented for " + position.length + "-Triangle");
00370                 return 0;
00371         }
00372 
00378         public Point3f getCentroid() {
00379                 return centroid;
00380         }
00381 
00387         public Vector3f getCornerarea() {
00388                 return cornerarea;
00389         }
00390 
00396         public Set<Triangle> getNeighbors() {
00397                 return neighbors;
00398         }
00399 
00405         public List<Triangle> getNeighborsOfEdge(final Edge edge) {
00406                 List<Triangle> toAdd = new ArrayList<Triangle>();
00407                 for (Triangle t : neighbors) {
00408                         Edge[] tEdges = t.getEdges();
00409                         for (int i = 0; i < tEdges.length; ++i) {
00410                                 if (edge.isDirectNeighbor(tEdges[i])) {
00411                                         toAdd.add(t);
00412                                 }
00413                         }
00414                 }
00415                 return toAdd;
00416         }
00417 
00426         public Edge getCommonEdge(final Triangle triangle) {
00427                 if (neighbors.contains(triangle)) {
00428                         Edge[] triangleEdges = triangle.getEdges();
00429                         for (int i = 0; i < edges.length; ++i) {
00430                                 for (int j = 0; j < triangleEdges.length; ++j) {
00431                                         if (edges[i].isDirectNeighbor(triangleEdges[j])) {
00432                                                 return edges[i];
00433                                         }
00434                                 }
00435                         }
00436                 }
00437                 return null;
00438         }
00439 
00445         @Override
00446         public Edge[] getEdges() {
00447                 return edges;
00448         }
00449 
00456         public Edge[] getSharpEdges() {
00457                 int numSharpEdges = 0;
00458                 for (int i = 0; i < edges.length; ++i) {
00459                         if (edges[i].isSharpEdge()) {
00460                                 numSharpEdges++;
00461                         }
00462                 }
00463                 if (numSharpEdges == 3) {
00464                         return edges;
00465                 }
00466                 Edge[] sharpEdges = new Edge[numSharpEdges];
00467                 numSharpEdges = 0;
00468                 for (int i = 0; i < edges.length; ++i) {
00469                         if (edges[i].isSharpEdge()) {
00470                                 sharpEdges[numSharpEdges++] = edges[i];
00471                         }
00472                 }
00473                 return sharpEdges;
00474         }
00475 
00482         public Edge[] getNonSharpEdges() {
00483                 int numNonSharpEdges = 0;
00484                 for (int i = 0; i < edges.length; ++i) {
00485                         if (!edges[i].isSharpEdge()) {
00486                                 numNonSharpEdges++;
00487                         }
00488                 }
00489                 if (numNonSharpEdges == 3) {
00490                         return edges;
00491                 }
00492                 Edge[] nonSharpEdges = new Edge[numNonSharpEdges];
00493                 if (numNonSharpEdges == 0) {
00494                         return nonSharpEdges;
00495                 }
00496                 numNonSharpEdges = 0;
00497                 for (int i = 0; i < edges.length; ++i) {
00498                         if (!edges[i].isSharpEdge()) {
00499                                 nonSharpEdges[numNonSharpEdges++] = edges[i];
00500                         }
00501                 }
00502                 return nonSharpEdges;
00503         }
00504 
00513         public Vertex getOppositeVertexFromEdge(Edge edge) {
00514                 boolean flagNotDirectNeighbor = true;
00515                 boolean flagSharpEdgeBounded = false;
00516                 // first get the common edge section belonging to the triangle
00517                 for (int i = 0; i < edges.length; ++i) {
00518                         if (edges[i].isDirectNeighbor(edge)) {
00519                                 flagNotDirectNeighbor = false;
00520                                 if (edges[i].isSharpEdge()) {
00521                                         flagSharpEdgeBounded = true;
00522                                         break;
00523                                 }
00524                                 edge = edges[i];
00525                                 break;
00526                         }
00527                 }
00528 
00529                 if (flagNotDirectNeighbor) {
00530                         logger.warn(edge + " is not a direct neighbor of any edge of\n" + this.toString());
00531                         return null;
00532                 }
00533 
00534                 if (flagSharpEdgeBounded) {
00535                         return null;
00536                 }
00537                 // determine opposite vertex
00538                 for (int i = 0; i < position.length; ++i) {
00539                         if (!edge.hasVertex(position[i])) {
00540                                 return position[i];
00541                         }
00542                 }
00543                 // commented out the warning as returning null does not affect performance
00544                 // logger.warn("Could not identify opposite vertex of\n" + edge + "\nfor\n" +
00545                 // this.toString());
00546                 return null;
00547         }
00548 
00554         public float[] getCurvatureValues() {
00555                 return curvatureMinMaxValue;
00556         }
00557 
00563         public boolean getIsCurvatureMinMaxValueInit() {
00564                 return isCurvatureMinMaxValueInit;
00565         }
00566 
00574         public void addSharpEdge(Edge edge) {
00575                 for (int i = 0; i < edges.length; ++i) {
00576                         if (edges[i].isDirectNeighbor(edge)) {
00577                                 edges[i].isSharpEdge(true);
00578                                 return;
00579                         }
00580                 }
00581         }
00582 
00588         public int getRegionLabel() {
00589                 return regionLabel;
00590         }
00591 
00600         public double getDihedralAngle(Triangle t) {
00601                 return this.getNormalVector().angle(t.getNormalVector());
00602         }
00603 
00609         public Vector3f getNormalVector() {
00610                 return normalVector;
00611         }
00612 
00618         public Point2f[] getTexPosition() {
00619                 return texPosition;
00620         }
00621 
00627         public boolean isVisited() {
00628                 return isVisited;
00629         }
00630 
00634         public void setIsVisited(final boolean isVisited) {
00635                 this.isVisited = isVisited;
00636         }
00637 
00648         public boolean intersectsRay(Point3f rayStart, Point3f rayEnd) {
00649                 return intersectsRay(rayStart, rayEnd, null);
00650         }
00651 
00657         public boolean calculateNormalVector() {
00658                 // Calculate normal vector for triangle
00659                 Vector3f avgVertexNorm = new Vector3f();
00660                 for (int i = 0; i < 3; i++) {
00661                         if (position[i].getNormalVector() == null) {
00662                                 avgVertexNorm = null;
00663                                 break;
00664                         }
00665                         avgVertexNorm.add(position[i].getNormalVector());
00666                 }
00667                 if (avgVertexNorm != null) {
00668                         avgVertexNorm.scale(1f / 3f);
00669                 }
00670 
00671                 Vector3f a = new Vector3f(position[0]);
00672                 a.sub(position[1]);
00673                 Vector3f b = new Vector3f(position[1]);
00674                 b.sub(position[2]);
00675 
00676                 /*Vector3f a = new Vector3f(position[1]);
00677                 a.sub(position[0]);
00678                 Vector3f b = new Vector3f(position[2]);
00679                 b.sub(position[0]);*/
00680                 Vector3f norm = new Vector3f();
00681                 norm.cross(a, b);
00682                 if (norm.lengthSquared() == 0) {
00683                         return false;
00684                 }
00685                 norm.normalize();
00686 
00687                 if (avgVertexNorm != null && avgVertexNorm.dot(norm) < 0)
00688                         norm.scale(-1f);
00689 
00690                 this.normalVector = norm;
00691                 return true;
00692         }
00693 
00711         public boolean intersectsRay(Point3f p1, Point3f p2, Point3f intersectionPoint) {
00712 
00713                 if (position.length != 3) {
00714                         System.out.println("intersectRay not implemented for not triangles!!");
00715                         return false;
00716                 }
00717 
00718                 Vector3d u, v, n; // triangle vectors
00719                 Vector3d dir, w0, w; // ray vectors
00720                 double r, a, b; // params to calc ray-plane intersect
00721 
00722                 // get triangle edge vectors and plane normal
00723                 u = new Vector3d(position[1]);
00724                 u.sub(new Vector3d(position[0]));
00725                 v = new Vector3d(position[2]);
00726                 v.sub(new Vector3d(position[0]));
00727 
00728                 n = new Vector3d();
00729                 n.cross(u, v); // Normal vector
00730                 if (n.equals(new Vector3d(0, 0, 0))) // triangle is degenerate
00731                         return false; // do not deal with this case
00732 
00733                 dir = new Vector3d(p2);// ray direction vector
00734                 dir.sub(new Vector3d(p1));
00735 
00736                 w0 = new Vector3d(p1);
00737                 w0.sub(new Vector3d(position[0]));
00738 
00739                 a = -n.dot(w0);
00740                 b = n.dot(dir);
00741                 // SMALL_NUM 0.00000001 // anything that avoids division overflow
00742                 if (Math.abs(b) < 0.00000001) { // ray is parallel to triangle plane
00743                         if (a == 0) // ray lies in triangle plane
00744                                 return false;
00745 
00746                         return false; // ray disjoint from plane
00747                 }
00748 
00749                 // get intersect point of ray with triangle plane
00750                 r = a / b;
00751 
00752                 // if (r < 0.0) // ray goes away from triangle
00753                 // return false; // => no intersect
00754                 // for a segment, also test if (r > 1.0) => no intersect
00755 
00756                 Point3f intersect = intersectionPoint;
00757 
00758                 if (intersect == null)
00759                         intersect = new Point3f();
00760 
00761                 intersect.set(dir); // intersect point of ray and plane
00762                 intersect.scale((float) r);
00763                 intersect.add(p1);
00764 
00765                 // is I inside T?
00766                 double uu, uv, vv, wu, wv, D;
00767                 uu = new Vector3d(u).dot(u);
00768                 uv = new Vector3d(u).dot(v);
00769                 vv = new Vector3d(v).dot(v);
00770                 w = new Vector3d(intersect);
00771                 w.sub(new Vector3d(position[0]));
00772                 wu = new Vector3d(w).dot(u);
00773                 wv = new Vector3d(w).dot(v);
00774                 D = uv * uv - uu * vv;
00775 
00776                 // get and test parametric coords
00777                 double s, t;
00778                 s = (uv * wv - vv * wu) / D;
00779                 if (s < 0.0 || s > 1.0) // I is outside T
00780                         return false;
00781                 t = (uv * wu - uu * wv) / D;
00782                 if (t < 0.0 || (s + t) > 1.0) // I is outside T
00783                         return false;
00784 
00785                 return true; // I is in T
00786         }
00787 
00798         public boolean isDirectNeighbor(Triangle tr, final boolean fastDetection) {
00799                 int eqCnt = 0;
00800                 if (fastDetection == true) {
00801                         // fast detection based only on checking the vertices
00802                         boolean isNeighbor = false;
00803                         for (int i = 0; i < position.length; i++) {
00804                                 if (i == 2 && eqCnt == 0)
00805                                         break; // if 2 of 3 points aren't equal, it is no neighbor
00806                                 Vertex p1 = position[i];
00807                                 for (Vertex p2 : tr.position) {
00808                                         if (p1.x == p2.x && p1.y == p2.y && p1.z == p2.z) {
00809                                                 eqCnt++;
00810                                                 break;
00811                                         }
00812                                 }
00813                                 if (eqCnt == 2) {
00814                                         isNeighbor = true; // two common vertices, so neighbors
00815                                 } else if (eqCnt == 3) {
00816                                         return false; // similar triangles back to back
00817                                 }
00818                         }
00819                         return isNeighbor;
00820                 } else {
00821                         // slow detection based on edges
00822                         List<Edge> trEdges = new ArrayList<Edge>();
00823                         trEdges.addAll(Arrays.asList(tr.getEdges()));
00824                         for (int i = 0; i < edges.length; ++i) {
00825                                 for (int j = 0; j < trEdges.size(); ++j) {
00826                                         if (edges[i].isDirectNeighbor(trEdges.get(j))) {
00827                                                 eqCnt++;
00828                                                 trEdges.remove(trEdges.get(j));
00829                                                 break;
00830                                         }
00831                                 }
00832                                 if (eqCnt == 2) {
00833                                         return false;
00834                                 }
00835                         }
00836                         // if one hit only happened the triangles are neighbors
00837                         if (eqCnt == 1) {
00838                                 return true;
00839                         }
00840                         // otherwise they are not neighbors at all or just the same or back-faced
00841                         return false;
00842                 }
00843         }
00844 
00853         public boolean isAdjacentNeighbor(Triangle tr) {
00854 
00855                 int eqCnt = 0;
00856                 boolean isNeighbor = false;
00857 
00858                 for (int i = 0; i < 3; i++) {
00859                         if (i == 2 && eqCnt == 0)
00860                                 break; // if 2 of 3 points aren't equal, it is no neighbor
00861                         Point3f p1 = position[i];
00862                         for (Point3f p2 : tr.position) {
00863                                 if (p1 == p2) {
00864                                         eqCnt++;
00865                                         if (eqCnt == 2) {
00866                                                 isNeighbor = true;
00867                                         }
00868                                         if (eqCnt == 3) {
00869                                                 // if triangle has same position but is backface
00870                                                 isNeighbor = false;
00871                                         }
00872                                         break;
00873                                 }
00874 
00875                         }
00876                 }
00877                 return isNeighbor;
00878         }
00879 
00886         public void setCornerarea(Vector3f cornerarea) {
00887                 this.cornerarea = cornerarea;
00888         }
00889 
00896         public void setNeighbors(Set<Triangle> neighbors) {
00897                 this.neighbors = neighbors;
00898         }
00899 
00906         public void setNormalVector(Vector3f normalVector) {
00907                 this.normalVector = normalVector;
00908         }
00909 
00916         public void setTexPosition(Point2f[] texPosition) {
00917                 this.texPosition = texPosition;
00918         }
00919 
00926         public boolean containsEdge(Edge edge) {
00927                 for (int i = 0; i < edges.length; ++i) {
00928                         if (edges[i].isEqualTo(edge)) {
00929                                 return true;
00930                         }
00931                 }
00932                 return false;
00933         }
00934 
00943         public boolean isSharpTriangle() {
00944                 return isSharpTriangle;
00945         }
00946 
00956         public boolean checkIsSharpTriangle() {
00957                 if (position[0].isSharpVertex() && position[1].isSharpVertex()
00958                                 && position[2].isSharpVertex()) {
00959                         this.isSharpTriangle = true;
00960                         return true;
00961                 }
00962                 return false;
00963         }
00964 
00971         public void setRegionLabel(final int newLabel) {
00972                 this.regionLabel = newLabel;
00973         }
00974 
00981         public int numOfSharpVertices() {
00982                 int cont = 0;
00983                 for (int i = 0; i < position.length; ++i) {
00984                         if (position[i].isSharpVertex()) {
00985                                 cont++;
00986                         }
00987                 }
00988                 return cont;
00989         }
00990 
00995         public void updateEdges() {
00996                 for (int j = 0; j < position.length; j++) {
00997                         edges[j] = new Edge(position[(j + 2) % position.length], position[(j + 1)
00998                                         % position.length]);
00999                 }
01000         }
01001 
01008         public boolean updateIsSeedTriangle() {
01009                 int numOfSharpVertices = this.numOfSharpVertices();
01010                 if (numOfSharpVertices == 0) {
01011                         if (((position[0].getClusterCurvatureVal()[0] == position[1].getClusterCurvatureVal()[0]) && (position[1]
01012                                         .getClusterCurvatureVal()[0] == position[2].getClusterCurvatureVal()[0]))
01013                                         && ((position[0].getClusterCurvatureVal()[1] == position[1]
01014                                                         .getClusterCurvatureVal()[1]) && (position[1].getClusterCurvatureVal()[1] == position[2]
01015                                                         .getClusterCurvatureVal()[1]))
01016                                         && ((position[0].getClusterCurvatureVal()[2] == position[1]
01017                                                         .getClusterCurvatureVal()[2]) && (position[1].getClusterCurvatureVal()[2] == position[2]
01018                                                         .getClusterCurvatureVal()[2]))) {
01019                                 setCurvatureLevels(position[0].getClusterCurvatureVal()[0],
01020                                                 position[0].getClusterCurvatureVal()[1],
01021                                                 position[0].getClusterCurvatureVal()[2]);
01022                                 this.isSeedTriangle = true;
01023                                 return true;
01024                         }
01025                         this.isSeedTriangle = false;
01026                         return false;
01027                 } else if (numOfSharpVertices == 1) {
01028                         Vertex[] v = new Vertex[2];
01029                         int cont = 0;
01030                         if (!position[0].isSharpVertex()) {
01031                                 v[cont] = position[0];
01032                                 ++cont;
01033                         }
01034                         if (!position[1].isSharpVertex()) {
01035                                 v[cont] = position[1];
01036                                 ++cont;
01037                         }
01038                         if (!position[2].isSharpVertex() && cont < 2) {
01039                                 v[cont] = position[2];
01040                         }
01041                         if ((v[0].getClusterCurvatureVal()[0] == v[1].getClusterCurvatureVal()[0])
01042                                         && v[0].getClusterCurvatureVal()[1] == v[1].getClusterCurvatureVal()[1]
01043                                         && v[0].getClusterCurvatureVal()[2] == v[1].getClusterCurvatureVal()[2]) {
01044                                 setCurvatureLevels(v[0].getClusterCurvatureVal()[0],
01045                                                 v[0].getClusterCurvatureVal()[1], v[0].getClusterCurvatureVal()[2]);
01046                                 this.isSeedTriangle = true;
01047                                 return true;
01048                         }
01049                         this.isSeedTriangle = false;
01050                         return false;
01051                 } else if (numOfSharpVertices == 2) {
01052                         for (int i = 0; i < position.length; ++i) {
01053                                 if (position[i].isSharpVertex()) {
01054                                         setCurvatureLevels(position[i].getClusterCurvatureVal()[0],
01055                                                         position[i].getClusterCurvatureVal()[1],
01056                                                         position[i].getClusterCurvatureVal()[2]);
01057                                         this.isSeedTriangle = true;
01058                                         return true;
01059                                 }
01060                         }
01061                         this.isSeedTriangle = false;
01062                         return false;
01063                 }
01064                 this.isSeedTriangle = false;
01065                 return false;
01066         }
01067 
01072         public boolean isSeedTriangle() {
01073                 return isSeedTriangle;
01074         }
01075 
01080         public void setCurvatureLevels(final float minCurvatureLevel, final float maxCurvatureLevel,
01081                         final float minMaxCurvatureLevel) {
01082                 this.isCurvatureMinMaxValueInit = true;
01083                 this.curvatureMinMaxValue[0] = minCurvatureLevel;
01084                 this.curvatureMinMaxValue[1] = maxCurvatureLevel;
01085                 this.curvatureMinMaxValue[2] = minMaxCurvatureLevel;
01086         }
01087 
01088         /*
01089          * (non-Javadoc)
01090          * @see edu.tum.cs.vis.model.util.DrawObject#updateCentroid()
01091          */
01092         @Override
01093         public void updateCentroid() {
01094                 centroid = new Point3f(0, 0, 0);
01095 
01096                 for (int i = 0; i < position.length; i++) {
01097                         centroid.add(position[i]);
01098                 }
01099                 centroid.scale(1f / position.length);
01100         }
01101 
01102         /*
01103          * (non-Javadoc)
01104          * @see java.lang.Object#toString()
01105          */
01106         @Override
01107         public String toString() {
01108                 String print = "Triangle: " + System.identityHashCode(this) + "\n";
01109                 print = print + "V1: " + position[0] + " V2: " + position[1] + " V3: " + position[2] + "\n";
01110                 print = print + "isSeedTriangle: " + isSeedTriangle + "\n";
01111                 if (regionLabel != -1) {
01112                         print = print + "Region: " + regionLabel + "\n";
01113                         print = print + "KMin: " + curvatureMinMaxValue[0] + ", KMax: "
01114                                         + curvatureMinMaxValue[1] + ", KMinKMax : " + curvatureMinMaxValue[2] + "\n";
01115                 } else {
01116                         print = print + "Region: unset" + "\n";
01117                 }
01118                 return print;
01119         }
01120 }


knowrob_cad_parser
Author(s): Stefan Profanter
autogenerated on Mon Oct 6 2014 01:29:56