DoubleLinkedDAG.java
Go to the documentation of this file.
00001 /*
00002  * (c) copyright 2008, Technische Universitaet Graz and Technische Universitaet Wien
00003  *
00004  * This file is part of jdiagengine.
00005  *
00006  * jdiagengine is free software: you can redistribute it and/or modify
00007  * it under the terms of the GNU General Public License as published by
00008  * the Free Software Foundation, either version 3 of the License, or
00009  * (at your option) any later version.
00010  *
00011  * jdiagengine is distributed in the hope that it will be useful,
00012  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00013  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00014  * GNU General Public License for more details.
00015  * You should have received a copy of the GNU General Public License
00016  * along with jdiagengine. If not, see <http://www.gnu.org/licenses/>.
00017  *
00018  * Authors: Joerg Weber, Franz Wotawa
00019  * Contact: jweber@ist.tugraz.at (preferred), or fwotawa@ist.tugraz.at
00020  *
00021  */
00022 
00023 
00024 package utils;
00025 
00026 import java.util.*;
00027 
00028 public class DoubleLinkedDAG implements Cloneable {
00029 
00030     /*
00031      * Marks used for cycle detection (see method findCycle()).
00032      */
00033     protected static int MARK_NOT_VISITED = 0;
00034     protected static int MARK_BEING_VISITED = 1;
00035     protected static int MARK_DONE_VISITED = 2;
00036 
00037     protected ArrayList nodes = new ArrayList();
00038 
00039     protected int numEdges = 0;
00040 
00041     /*
00042      * Used by findCycle(); each entry is one of the MARK_X constants (e.g., MARK_VISITED).
00043      * Entry i is the visit-status of the node whose id is equal to i.
00044      */
00045     protected int[] nodeMarks;
00046 
00047     /*
00048      * Used by the methods implementing the Visitor-pattern: bit i denotes whether the node with id = i
00049      * has already been visited.
00050      */
00051     protected BitSet nodesVisited;
00052 
00053 
00054     /*
00055      * If a transitive closure is computed (method computeTransitiveClosure()) and
00056      * paramter \a computeMinMaxDist is \c true, then the closure (class GraphMatrix) contains
00057      * tags which are of type MinMaxDistance.
00058      */
00059     public class MinMaxDistance {
00060         public int minDist = -1;
00061         public int maxDist = -1;
00062 
00063         public MinMaxDistance(int minDist, int maxDist) {
00064             this.minDist = minDist;
00065             this.maxDist = maxDist;
00066         }
00067 
00068         public String toString() {
00069             return "min: " + minDist + "; max: " + maxDist;
00070         }
00071     }
00072 
00073     /*
00074      * Creates an empty DAG.
00075      */
00076     public DoubleLinkedDAG() {
00077     }
00078 
00079     /*
00080      * The new DAG is a (deep) clone of dag.
00081      */
00082     public DoubleLinkedDAG(DoubleLinkedDAG dag) {
00083         numEdges = dag.numEdges;
00084         nodes.ensureCapacity(dag.nodes.size());
00085 
00086         Iterator itNodes = dag.nodes.iterator();
00087         while (itNodes.hasNext()) {
00088             DoubleLinkedDAGNode n = (DoubleLinkedDAGNode)itNodes.next();
00089             DoubleLinkedDAGNode clonedN = (DoubleLinkedDAGNode)n.clone();
00090             clonedN.allNodes = nodes;
00091             nodes.add(clonedN);
00092         }
00093     }
00094 
00095     /*
00096      * Returns a (deep) clone of this DAG.
00097      */
00098     public Object clone() {
00099         DoubleLinkedDAG clonedDAG = new DoubleLinkedDAG(this);
00100         return clonedDAG;
00101     }
00102 
00108     public int addNode(DoubleLinkedDAGNode node) {
00109         assert(node != null);
00110 
00111         nodes.add(node);
00112         node.id = nodes.size() - 1;
00113         node.allNodes = nodes;
00114 
00115         return node.id;
00116     }
00117 
00118     public boolean hasNode(int id) {
00119         assert(id >= 0);
00120 
00121         return (id < nodes.size());
00122     }
00123 
00130     public boolean hasNode(DoubleLinkedDAGNode node) {
00131         Iterator itNodes = nodes.iterator();
00132         while (itNodes.hasNext()) {
00133             DoubleLinkedDAGNode n = (DoubleLinkedDAGNode)itNodes.next();
00134             if (node == n) return true;
00135         }
00136         return false;
00137     }
00138 
00145     public void addEdge(DoubleLinkedDAGNode from, DoubleLinkedDAGNode to) {
00146         
00147         // precondition
00148         assert(nodes.contains(from) && nodes.contains(to));
00149         assert(!from.getChildren().contains(to.id) && !to.getParents().contains(from.id));
00150         
00151         from.getChildren().addSorted(to.id);
00152         to.getParents().addSorted(from.id);
00153 
00154         ++numEdges;
00155     }
00156 
00157     public boolean hasEdge(DoubleLinkedDAGNode from, DoubleLinkedDAGNode to) {
00158         // precondition
00159         assert(nodes.contains(from) && nodes.contains(to));
00160 
00161         return (from.getChildren().contains(to.id));
00162     }
00163     
00164     public void removeEdge(DoubleLinkedDAGNode from, DoubleLinkedDAGNode to) {
00165         assert(hasEdge(from, to));
00166 
00167         from.getChildren().remove(to.id);
00168         to.getParents().remove(from.id);
00169 
00170         --numEdges;
00171     }
00172 
00173     public ArrayList getNodes() {
00174         return nodes;
00175     }
00176 
00177     public int getNumNodes() {
00178         return nodes.size();
00179     }
00180 
00181     public int getNumEdges() {
00182         return numEdges;
00183     }
00184 
00185     public String toString() {
00186         return toString(null);
00187     }
00188 
00189     /*
00190      * Similar to toString(), but the tags in graphMatrix
00191      * are also included (using the toString() method of the tags).
00192      * graphMatrix must conform to this DAG!
00193      *
00194      * graphMatrix may be null; in this case the result is equal to the
00195      * result returned by toString(). 
00196      */
00197     public String toString(GraphMatrix graphMatrix) {
00198         StringBuffer result = new StringBuffer();
00199 
00200         Iterator itNodes = iterator();
00201         while (itNodes.hasNext()) {
00202             DoubleLinkedDAGNode n = (DoubleLinkedDAGNode)itNodes.next();
00203             result.append("node: ");
00204             result.append(n.toString());
00205             result.append(";  PARENTS: ");
00206             
00207             Iterator itParents = n.getParentsIterator();
00208             while (itParents.hasNext()) {
00209                 DoubleLinkedDAGNode parent = (DoubleLinkedDAGNode)itParents.next();
00210                 result.append(parent.toString());
00211                 if (graphMatrix != null) {
00212                     Object tag = graphMatrix.getTag(parent.id, n.id);
00213                     if (tag != null) {
00214                         result.append("(");
00215                         result.append(tag.toString());
00216                         result.append(")");
00217                     }
00218                 }
00219                 result.append("; ");
00220             }
00221 
00222             result.append(";  CHILDREN: ");
00223             Iterator itChildren = n.getChildrenIterator();
00224             while (itChildren.hasNext()) {
00225                 DoubleLinkedDAGNode child = (DoubleLinkedDAGNode)itChildren.next();
00226                 result.append(child.toString());
00227                 if (graphMatrix != null) {
00228                     Object tag = graphMatrix.getTag(n.id, child.id);
00229                     if (tag != null) {
00230                         result.append("(");
00231                         result.append(tag.toString());
00232                         result.append(")");
00233                     }
00234                 }
00235                 result.append("; ");
00236             }
00237         
00238             result.append("\n");
00239         }
00240 
00241         return result.toString();
00242     }
00243 
00244     public String toStringShort() {
00245         
00246         StringBuffer result = new StringBuffer();
00247         AddNodeAsStringVisitor visitor = new AddNodeAsStringVisitor(result);
00248         visitRoots(visitor, false);
00249         return result.toString();        
00250     }
00251 
00252     /*
00253      * The iteration order is ascendent wrt the ID of the nodes.
00254      *
00255      * Thus, the iteration order has nothing to do with the structure of the
00256      * graph.
00257      */
00258     public Iterator iterator() {
00259         return nodes.iterator();
00260     }
00261 
00262     /*
00263      * \c index must be in the range 0..getNumNodes() - 1.
00264      */
00265     public final DoubleLinkedDAGNode getNode(int index) {
00266         return (DoubleLinkedDAGNode)nodes.get(index);
00267     }
00268 
00269     /*
00270      * The visitor recursively visits this node and all of its descendants in the DAG in the
00271      * following order: visit(this node) - visit(first child) - .. - visit(last child) 
00272      *
00273      * IMPORTANT: if the subgraph with "node" as root has diamond structures, then it 
00274      * could happen that nodes in this subgraph are visited multiple times. If 
00275      * visitOnlyOnce is true, then it is guaranteed that each child is visited only once.
00276      */
00277     public void visitChildrenPreOrder(DoubleLinkedDAGNode node,
00278                                       DoubleLinkedDAGVisitor visitor, boolean visitOnlyOnce) {
00279 
00280         if (visitOnlyOnce) nodesVisited = new BitSet(nodes.size());
00281         visitChildrenPreOrder_Recursive(node, visitor, visitOnlyOnce);
00282         nodesVisited = null;
00283     }
00284 
00285     public void visitChildrenPreOrder_Recursive(DoubleLinkedDAGNode node,
00286                                                 DoubleLinkedDAGVisitor visitor, boolean visitOnlyOnce) {
00287 
00288         if (!visitOnlyOnce || !nodesVisited.get(node.id)) {
00289 
00290             visitor.visit(node);
00291             if (visitOnlyOnce) {
00292                 nodesVisited.set(node.id, true);
00293             }
00294             boolean moreNodes = visitor.wantMoreNodes();
00295             
00296             if (moreNodes) {
00297                 
00298                 Iterator itChildren = node.getChildrenIterator();
00299                 while (moreNodes && itChildren.hasNext()) {
00300                     DoubleLinkedDAGNode child = (DoubleLinkedDAGNode)itChildren.next();
00301                     visitChildrenPreOrder_Recursive(child, visitor, visitOnlyOnce);
00302                     moreNodes = visitor.wantMoreNodes();
00303                 }
00304             }
00305         }
00306     }
00307 
00308     /*
00309      * Calls visitChildrenPreOrder() for all root nodes of this DAG.
00310      *
00311      * A "root" is a node without parents. Note that the roots are not explicitely stored,
00312      * i.e., in order to find the roots it is necessary to iterate through all nodes.
00313      *
00314      * If visitOnlyOnce is true, then it is guarenteed that each node is visited only once for each root, 
00315      * see alse visitChildrenPreOrder(). However, if a node is reachable from k different roots, then
00316      * this node is visited k times.
00317      */
00318     public void visitRoots(DoubleLinkedDAGVisitor visitor, boolean visitOnlyOnce) {
00319         Iterator itNodes = iterator();
00320         while (itNodes.hasNext()) {
00321             DoubleLinkedDAGNode node = (DoubleLinkedDAGNode)itNodes.next();
00322             if (!node.hasParents()) {
00323                 visitChildrenPreOrder(node, visitor, visitOnlyOnce);
00324             }
00325         }
00326     }
00327 
00328     /*
00329      * Util method for computeMaxPathLen(); recursive.
00330      *
00331      * Computes the longest path in those subgraph whose root passed as parameter.
00332      */
00333     protected int computeMaxPathLen_Recursive(DoubleLinkedDAGNode root) {
00334         int maxLen = 0;
00335      
00336         Iterator itChildren = root.getChildrenIterator();
00337         while (itChildren.hasNext()) {
00338             DoubleLinkedDAGNode child = (DoubleLinkedDAGNode)itChildren.next();
00339             int tmpMax = 1 + computeMaxPathLen_Recursive(child);
00340             if (tmpMax > maxLen) maxLen = tmpMax;
00341         }
00342 
00343         return maxLen;
00344     }
00345 
00346     /*
00347      * Returns the length of the longest path in the DAG.
00348      *
00349      * If there is no edge in the path, then it returns 0. If the longest path
00350      * has n edges, then it returns n.
00351      */
00352     public int computeMaxPathLen() {
00353         int maxLen = 0;
00354 
00355         Iterator itNodes = iterator();
00356         while (itNodes.hasNext()) {
00357             DoubleLinkedDAGNode n = (DoubleLinkedDAGNode)itNodes.next();
00358 
00359             if (!n.hasParents()) {   // perform recursive computation only for root nodes
00360                 int tmpMax = computeMaxPathLen_Recursive(n);
00361                 if (tmpMax > maxLen) maxLen = tmpMax;
00362             }
00363         }
00364 
00365         return maxLen;
00366     }
00367 
00368     /*
00369      * Util method for computeTransitiveClosure().
00370      * Adds an edge in closure from n to descendant and all descendants d of descendant.
00371      */
00372     protected void transClosureRecursion(GraphMatrix closure, DoubleLinkedDAGNode n,
00373                                          DoubleLinkedDAGNode descendant,
00374                                          boolean computeMinMaxDist, int distance) {
00375 
00376         boolean recursionRequired;  // is it necessary to perform recursive call for children?
00377         
00378         // set edge in closure, set tag in closure to length of min. path from n to desc.
00379         
00380         // NOTE: edge in closure already exists => edges to descendants of "descendant" exist as well!!
00381         // => recursion only necessary if computeMinMaxDistance=true and if new distances are smaller/greater
00382         // than old ones!
00383 
00384         if (closure.hasEdge(n.id, descendant.id)) {
00385             if (computeMinMaxDist) {
00386                 MinMaxDistance d = (MinMaxDistance)closure.getTag(n.id, descendant.id);
00387                 assert(d.minDist <= d.maxDist);
00388 
00389                 if (distance < d.minDist) {
00390                     System.out.println("distance < d.minDist: " + distance + " < " + d.minDist);
00391                     closure.setTag(n.id, descendant.id, new MinMaxDistance(distance, d.maxDist));
00392                     recursionRequired = true;
00393                 } else if (distance > d.maxDist) {
00394                     System.out.println("distance > d.maxDist: " + distance + " > " + d.maxDist);
00395                     closure.setTag(n.id, descendant.id, new MinMaxDistance(d.minDist, distance));
00396                     recursionRequired = true;
00397                 } else recursionRequired = false;
00398                 
00399             } else { 
00400                 recursionRequired = false;
00401             }
00402         } else {
00403             closure.addEdge(n.id, descendant.id);
00404             if (computeMinMaxDist) closure.setTag(n.id, descendant.id, new MinMaxDistance(distance, distance));
00405 
00406             recursionRequired = true;
00407         }
00408 
00409         // if required: recursive call for all children
00410 
00411         if (recursionRequired) {
00412             Iterator itChildren = descendant.getChildrenIterator();
00413             while (itChildren.hasNext()) {
00414                 DoubleLinkedDAGNode child = (DoubleLinkedDAGNode)itChildren.next();
00415                 transClosureRecursion(closure, n, child, computeMinMaxDist, distance + 1);
00416             }
00417         }
00418     }
00419 
00420     /*
00421      * Computes a graph which has an edge from n1 -> n2 iff 
00422      * there is a directed path from n1 to n2.
00423      *
00424      * If computeMinMaxDist is true, then tags are assigned to all edges in 
00425      * the closure. These tags are instances of MinMaxDistance (nested class of DoubleLinkedDAG).
00426      *
00427      * Complexity: O(n^2)
00428      */
00429     public GraphMatrix computeTransitiveClosure(boolean computeMinMaxDist) {
00430 
00431         final GraphMatrix result = new GraphMatrix(nodes.size());
00432 
00433         // iterate through all nodes n
00434 
00435         int progress = 0;
00436         Iterator itNodes = nodes.iterator();
00437         while (itNodes.hasNext()) {
00438             final DoubleLinkedDAGNode n = (DoubleLinkedDAGNode)itNodes.next();
00439 
00440             // iterate through children of n
00441 
00442             Iterator itChildren = n.getChildrenIterator();
00443             while (itChildren.hasNext()) {
00444                 DoubleLinkedDAGNode child = (DoubleLinkedDAGNode)itChildren.next();
00445                 
00446                 // perform recursive algorithm on all children
00447                 transClosureRecursion(result, n, child, computeMinMaxDist, 1);
00448             }
00449             
00450             ++progress;
00451         }
00452         
00453         // postcondition: deactivated, because often too time-consuming!
00454         //assert(correctTransitiveClosure(result, computeMinMaxDist));
00455 
00456         return result;
00457 
00458     }  // computeTransitiveClosure()
00459 
00460     /*
00461      * For test purposes only. Returns true iff transClosure is the 
00462      * transitive closure of this DAG.
00463      *
00464      * This method can be called in assert-statements. By default, no method in DoubleLinkedDAG 
00465      * performs this check, is it may be extremely time-consuming.
00466      *
00467      * This method is able to check if the min. and max. distances between nodes, which are supposed to
00468      * be stored as tags (instances of MinMaxDistance) are correct.
00469      */
00470     public boolean correctTransitiveClosure(GraphMatrix transClosure, boolean checkMinMaxDist) {
00471         
00472         // for all nodes n1 and n2: if n1 is an ancestor of n2, then there
00473         // must be an edge in transClosure from n1 to n2. And vice versa.
00474         // The minimal distances are also checked, if demanded.
00475 
00476         for (int i = 0; i < nodes.size(); ++i) {
00477             for (int j = i + 1; j < nodes.size(); ++j) {
00478                 
00479                 DoubleLinkedDAGNode ni = (DoubleLinkedDAGNode)nodes.get(i);
00480                 DoubleLinkedDAGNode nj = (DoubleLinkedDAGNode)nodes.get(j);
00481 
00482                 if (isAncestor(ni, nj)) {
00483                     if (!transClosure.hasEdge(ni.id, nj.id)) return false; 
00484                 } else if (isAncestor(nj, ni)) {
00485                     if (!transClosure.hasEdge(nj.id, ni.id)) return false; 
00486                 }
00487             }
00488         }
00489 
00490         // for all edges from ni to nj in transClosure: ni must be an ancestor of nj
00491         Iterator itEdges = transClosure.getEdgeIterator();
00492         while (itEdges.hasNext()) {
00493             GraphMatrix.Edge e = (GraphMatrix.Edge)itEdges.next();
00494             DoubleLinkedDAGNode ni = (DoubleLinkedDAGNode)nodes.get(e.from);
00495             DoubleLinkedDAGNode nj = (DoubleLinkedDAGNode)nodes.get(e.to);
00496 
00497             if (!isAncestor(ni, nj)) return false; 
00498             else if (checkMinMaxDist) {
00499                 Object tag = transClosure.getTag(ni.id, nj.id);
00500                 assert(tag != null);
00501                 MinMaxDistance minMaxDist = (MinMaxDistance)tag;
00502 
00503                 int computedMinDist = computeMinDistance(ni, nj);
00504                 if (minMaxDist.minDist != computedMinDist) return false; 
00505 
00506                 int computedMaxDist = computeMaxDistance(ni, nj);
00507                 if (minMaxDist.maxDist != computedMaxDist) return false;
00508             }
00509             
00510         }
00511 
00512         return true;
00513 
00514     }  //correctTransitiveClosure()
00515 
00516     /*
00517      * Returns the minimal distance between fromNode and toNode.
00518      *
00519      * Returns -1 if there is no path, and 0 if fromNode == toNode. The algorithm is recursive.
00520      */
00521     public int computeMinDistance(DoubleLinkedDAGNode fromNode, DoubleLinkedDAGNode toNode) {
00522         
00523         int minDist;
00524 
00525         if (fromNode == toNode) minDist = 0;
00526         else {
00527             Iterator itChildren = fromNode.getChildrenIterator();
00528             if (!itChildren.hasNext()) minDist = -1;  // there is no path from fromNode to toNode
00529             else {
00530                 minDist = -1;
00531 
00532                 while (itChildren.hasNext()) {
00533                     DoubleLinkedDAGNode child = (DoubleLinkedDAGNode)itChildren.next();
00534                     int childDist = computeMinDistance(child, toNode);
00535                     if (childDist == 0) {
00536                         minDist = 1;
00537                         break;
00538                     } else {
00539                         if (childDist > 0) {
00540                             if (minDist == -1) minDist = childDist + 1;
00541                             else if (childDist + 1 < minDist) minDist = childDist + 1;
00542                         }
00543                     }
00544                 }
00545             }
00546         }
00547 
00548         return minDist;
00549     }
00550 
00551     
00552     /*
00553      * Returns the maximal distance between fromNode and toNode.
00554      *
00555      * Returns -1 if there is no path, and 0 if fromNode == toNode. The algorithm is recursive.
00556      */
00557     public int computeMaxDistance(DoubleLinkedDAGNode fromNode, DoubleLinkedDAGNode toNode) {
00558         
00559         int maxDist;
00560 
00561         if (fromNode == toNode) maxDist = 0;
00562         else {
00563             Iterator itChildren = fromNode.getChildrenIterator();
00564             if (!itChildren.hasNext()) maxDist = -1;  // there is no path from fromNode to toNode
00565             else {
00566                 maxDist = -1;
00567 
00568                 while (itChildren.hasNext()) {
00569                     DoubleLinkedDAGNode child = (DoubleLinkedDAGNode)itChildren.next();
00570                     int childDist = computeMaxDistance(child, toNode);
00571                     
00572                     if (childDist == 0) {
00573                         if (maxDist == -1) maxDist = 1;
00574                         else assert(maxDist >= 1);
00575                     } else if (childDist > 0) {
00576                         if (maxDist == -1) maxDist = childDist + 1;
00577                         else if (childDist + 1 > maxDist) maxDist = childDist + 1;
00578                     }
00579 
00580                 }
00581             }
00582         }
00583 
00584         return maxDist;
00585     }
00586     /*
00587      * When a new edge from "from" to "to" was created, then this method updates "transClosure".
00588      *
00589      * See also computeTransitiveClosure().
00590      */
00591     public void updateTransClosureForNewEdge(GraphMatrix transClosure, 
00592                                              DoubleLinkedDAGNode fromNode, DoubleLinkedDAGNode toNode, 
00593                                              boolean computeMinDistance) {
00594 
00595         // iterate through all nodes n; if either n is fromNode or fromNode is reachable from n:
00596         //     add an edge in transClosure from n to toNode and all descendants of toNode
00597 
00598         Iterator itNodes = nodes.iterator();
00599         while (itNodes.hasNext()) 
00600         {
00601             DoubleLinkedDAGNode n = (DoubleLinkedDAGNode)itNodes.next();
00602             if ((n == fromNode) || (transClosure.hasEdge(n.id, fromNode.id))) {
00603                 transClosureRecursion(transClosure, n, toNode, computeMinDistance, 1);
00604             }
00605         }
00606 
00607      }
00608 
00609 
00610     /*
00611      * Returns true iff possAnc is an ancestor of node.
00612      *
00613      * This method performes a recursive search. If the transitive closure of this DAG
00614      * has already been computed, then use the overloaded method below.
00615      *
00616      * Complexity: O(n)  [n..#nodes]
00617      */
00618     public boolean isAncestor(DoubleLinkedDAGNode possAnc, DoubleLinkedDAGNode possDesc) {
00619         
00620         // precondition
00621         assert(nodes.contains(possAnc) && nodes.contains(possDesc));
00622 
00623         SearchNodeVisitor visitor = new SearchNodeVisitor(possDesc);
00624         
00625         Iterator itChildren = possAnc.getChildrenIterator();
00626         while (itChildren.hasNext() && !visitor.foundNode()) {
00627             DoubleLinkedDAGNode child = (DoubleLinkedDAGNode)itChildren.next();            
00628             visitChildrenPreOrder(child, visitor, true);
00629         }
00630 
00631         return visitor.foundNode();
00632     }
00633 
00634     /*
00635      * Returns true iff possAnc is an ancestor of node.
00636      *
00637      * If the transitive closure is not known, then use the overloaded method above.
00638      * Complexity: O(const)
00639      */
00640     public boolean isAncestor(DoubleLinkedDAGNode possAnc, DoubleLinkedDAGNode possDesc,
00641                               GraphMatrix transitiveClosure) {
00642         
00643         // precondition
00644         assert(nodes.contains(possAnc) && nodes.contains(possDesc));
00645 
00646         boolean result = transitiveClosure.hasEdge(possAnc.id, possDesc.id);
00647 
00648         // postcondition
00649         assert(result == isAncestor(possAnc, possDesc));
00650         
00651         return result;
00652     }
00653 
00654     /*
00655      * Implements depth-first search: a cycle is detected if n is already marked as MARK_BEING_VISITED.
00656      * If this happens, then n is returned. If the recursive call for a child returns a node n1, then
00657      * n1 is the first node encountered by the search which occurs a second time on one path.
00658      *
00659      * If a cycle is found, then all of its elements are returned in foundCycle.
00660      */
00661     protected DoubleLinkedDAGNode findCycle_Recursive(DoubleLinkedDAGNode n, ArrayList foundCycle) {
00662         
00663         int nodeStatus = nodeMarks[n.id];
00664 
00665         if (nodeStatus == MARK_BEING_VISITED) {  // cycle detected!
00666             foundCycle.add(n);
00667             return n;
00668         
00669         } else {
00670 
00671             if (nodeStatus == MARK_DONE_VISITED) {  // if there are "diamond" structures: n is visited again
00672                 return null;
00673             
00674             } else {
00675                 nodeMarks[n.id] = MARK_BEING_VISITED;
00676 
00677                 // iterate through children, recursive calls
00678 
00679                 Iterator itChildren = n.getChildrenIterator();
00680                 while (itChildren.hasNext()) {
00681                     DoubleLinkedDAGNode child = (DoubleLinkedDAGNode)itChildren.next();
00682                     DoubleLinkedDAGNode cycleNode = findCycle_Recursive(child, foundCycle);
00683                     
00684                     if (cycleNode != null) {   // child is part of a cycle
00685 
00686                         if (cycleNode == n) {  // n is the "first" node of the cycle
00687                             foundCycle.add(n);
00688                             return null;
00689 
00690                         } else {  // n is not the first node of the cycle
00691                             foundCycle.add(n);
00692                             return n;
00693                         }
00694                     }
00695                 }
00696             }
00697 
00698             nodeMarks[n.id] = MARK_DONE_VISITED;
00699             return null;
00700         }
00701         
00702     }  // findCycle_Recursive()
00703 
00704     /*
00705      * Searches for a cycle and, if one is found, returns a list of nodes on this cycle.
00706      *
00707      * If a cycle is found which starts with node n then n will be the first AND the last 
00708      * element of the returned list, i.e., this list contains n twice!
00709      */
00710     public List findCycle() {
00711 
00712         ArrayList foundCycle = new ArrayList();
00713         nodeMarks = new int[nodes.size()];
00714 
00715         // iterate through all nodes, if n is a root node: start depth search on n
00716 
00717         Iterator itNodes = nodes.iterator();
00718         while (itNodes.hasNext()) {
00719             DoubleLinkedDAGNode n = (DoubleLinkedDAGNode)itNodes.next();
00720             
00721             if (!n.hasParents()) {  // n is a root node
00722                 
00723                 // mark all nodes as MARK_NOT_VISITED
00724 
00725                 for (int i = 0; i < nodeMarks.length; ++i) {
00726                     nodeMarks[i] = MARK_NOT_VISITED;
00727                 }
00728 
00729                 // start recursive search
00730 
00731                 findCycle_Recursive(n, foundCycle);
00732                 if (foundCycle.size() > 0) break;  // if cycle found: interrupt search
00733             }
00734         }
00735 
00736         if (foundCycle.size() == 0) return null;
00737         else return foundCycle;
00738     
00739     }  // findCyle()
00740     
00741     /*
00742      * Iterates through all ancestors of node. The transitive closure of this DAG
00743      * must be provided.
00744      *
00745      * The iterator returns objects of type DoubleLinkedDAGNode.
00746      *
00747      * UNTESTED!
00748      */
00749     public Iterator getAncestorIterator(DoubleLinkedDAGNode node, GraphMatrix transitiveClosure) {
00750         return new IntegerIterator(transitiveClosure.getAncestorIterator(node.id));
00751     }
00752     
00753     /*
00754      * Analogous to getAncestorIterator().
00755      *
00756      * UNTESTED!
00757      */
00758     public Iterator getDescendantIterator(DoubleLinkedDAGNode node, GraphMatrix transitiveClosure) {
00759         return new IntegerIterator(transitiveClosure.getDescendantIterator(node.id));
00760     }
00761 
00762 
00763     /*
00764      * Iterates through those nodes of the DAG whose integer indexes are passed to
00765      * the constructor of IntegerIterator.
00766      */
00767     protected class IntegerIterator implements Iterator {
00768 
00769         Iterator itNodes;
00770 
00771         /*
00772          * The argument is an iterator of Integer objects.
00773          */
00774         public IntegerIterator(Iterator itNodes) {
00775             this.itNodes = itNodes;
00776         }
00777 
00778         public boolean hasNext() {
00779             return itNodes.hasNext();
00780         }
00781 
00782         public Object next() {
00783             assert(hasNext());
00784 
00785             Integer index = (Integer)itNodes.next();
00786             return nodes.get(index.intValue());
00787         }
00788 
00789         public void remove() {
00790             throw new UnsupportedOperationException();
00791         }
00792     }
00793 
00794 }
00795 
00796 class SearchNodeVisitor extends DoubleLinkedDAGVisitor {
00797 
00798     private DoubleLinkedDAGNode searchNode;
00799 
00800     private boolean foundNode = false;
00801 
00802 
00803     public SearchNodeVisitor(DoubleLinkedDAGNode searchNode) {
00804         this.searchNode = searchNode;
00805     }
00806 
00807     public boolean wantMoreNodes() {
00808         return (!foundNode);
00809     }
00810 
00811     public void visit(DoubleLinkedDAGNode node) {
00812         if (node == searchNode) foundNode = true;
00813     }
00814 
00815     public boolean foundNode() {
00816         return foundNode;
00817     }
00818 
00819 }
00820 
00821 /*
00822  * For each visited node n: iterate through parents n_p and
00823  * add strings of format "n_p.toString() => n.toString; " to the StringBuffer which is passed
00824  * to the constructor.
00825  */
00826 class AddNodeAsStringVisitor extends DoubleLinkedDAGVisitor {
00827 
00828     StringBuffer str;
00829 
00830     public AddNodeAsStringVisitor(StringBuffer str) {
00831         this.str = str;
00832     }
00833 
00834     public boolean wantMoreNodes() {
00835         return true;
00836     }
00837 
00838     public void visit(DoubleLinkedDAGNode node) {
00839         Iterator itParents = node.getParentsIterator();
00840         if (!itParents.hasNext()) {
00841             str.append(node.toString() + "; ");
00842         }
00843         while (itParents.hasNext()) {
00844             DoubleLinkedDAGNode parentNode = (DoubleLinkedDAGNode)itParents.next();
00845             str.append(parentNode.toString() + " => " + node.toString() + "; ");
00846         }
00847     }
00848 
00849     public String getStr() {
00850         return str.toString();
00851     }
00852 
00853 }
00854 


tug_ist_diagnosis_engine
Author(s): Safdar Zaman, Gerald Steinbauer
autogenerated on Mon Jan 6 2014 11:51:16