aggregates.hh

Go to the documentation of this file.
00001 // $Id: aggregates.hh 1153 2010-01-22 17:47:59Z mblatt $ 
00002 #ifndef DUNE_AMG_AGGREGATES_HH
00003 #define DUNE_AMG_AGGREGATES_HH
00004 
00005 #include"graph.hh"
00006 #include"properties.hh"
00007 #include"combinedfunctor.hh"
00008 
00009 #include<dune/common/timer.hh>
00010 #include<dune/common/tuples.hh>
00011 #include<dune/common/stdstreams.hh>
00012 #include<dune/common/poolallocator.hh>
00013 #include<dune/common/sllist.hh>
00014 
00015 #include<utility>
00016 #include<set>
00017 #include<algorithm>
00018 #include<limits>
00019 #include<ostream>
00020 
00021 namespace Dune
00022 {
00023   namespace Amg
00024   {
00025     
00039     template<class T>
00040     class AggregationCriterion : public T
00041     {
00042 
00043     public:
00047       typedef T DependencyPolicy;
00048       
00058       AggregationCriterion()
00059         : maxDistance_(2), minAggregateSize_(4), maxAggregateSize_(6), 
00060           connectivity_(15), debugLevel_(2)
00061       {}
00062       
00072       void setDefaultValuesIsotropic(std::size_t dim, std::size_t diameter=2)
00073       {
00074         maxDistance_=0;
00075         std::size_t csize=1;
00076 
00077         for(;dim>0;dim--){          
00078           csize*=diameter;
00079           maxDistance_+=diameter-1;
00080         }
00081         minAggregateSize_=csize;
00082         maxAggregateSize_=static_cast<std::size_t>(csize*1.5);
00083       }
00084 
00095       void setDefaultValuesAnisotropic(std::size_t dim,std::size_t diameter=2)
00096       {
00097         setDefaultValuesIsotropic(dim, diameter);
00098         maxDistance_+=dim-1;
00099       }
00107       std::size_t maxDistance() const { return maxDistance_;}
00108 
00117       void setMaxDistance(std::size_t distance) { maxDistance_ = distance;}
00118 
00119       bool skipIsolated() const
00120       {
00121         return false;
00122       }
00123 
00128       std::size_t minAggregateSize() const { return minAggregateSize_;}
00129     
00136       void setMinAggregateSize(std::size_t size){ minAggregateSize_=size;}
00137 
00142       std::size_t maxAggregateSize() const{ return maxAggregateSize_;}
00143 
00150       void setMaxAggregateSize(std::size_t size){ maxAggregateSize_ = size;}
00151 
00159       std::size_t maxConnectivity() const{ return connectivity_;}
00160 
00168       void setMaxConnectivity(std::size_t connectivity){ connectivity_ = connectivity;}
00169 
00175       void setDebugLevel(int level)
00176       {
00177         debugLevel_ = level;
00178       }
00179       
00185       int debugLevel() const
00186       {
00187         return debugLevel_;
00188       }
00189       
00190       
00191     private:
00192       std::size_t maxDistance_, minAggregateSize_, maxAggregateSize_, connectivity_;
00193       int debugLevel_;
00194     };
00195     
00196     template<class T>
00197     std::ostream& operator<<(std::ostream& os, const AggregationCriterion<T>& criterion)
00198     {
00199       os<<"{ maxdistance="<<criterion.maxDistance()<<" minAggregateSize="
00200         <<criterion.minAggregateSize()<< " maxAggregateSize="<<criterion.maxAggregateSize()
00201         <<" connectivity="<<criterion.maxConnectivity()<<" debugLevel="<<criterion.debugLevel()<<"}";
00202       return os;
00203     }
00204 
00208     class DependencyParameters
00209     {
00210     public:
00212       DependencyParameters()
00213         : alpha_(1.0/3.0), beta_(1.0E-5)
00214       {}
00215       
00220       void setBeta(double b)
00221       {
00222         beta_ = b;
00223       }
00224       
00230       double beta() const
00231       {
00232         return beta_;
00233       }
00234       
00239       void setAlpha(double a)
00240       {
00241         alpha_ = a;
00242       }
00243 
00248       double alpha() const
00249       {
00250         return alpha_;
00251       }
00252       
00253     private:
00254       double alpha_, beta_;
00255     };
00256     
00257     
00261     template<class M, class N>
00262     class Dependency : public DependencyParameters
00263     {
00264     public:
00268       typedef M Matrix;
00269       
00273       typedef N Norm;
00274 
00278       typedef typename Matrix::row_type Row;
00279 
00283       typedef typename Matrix::ConstColIterator ColIter;
00284       
00285       void init(const Matrix* matrix);
00286       
00287       void initRow(const Row& row, int index);
00288 
00289       void examine(const ColIter& col);
00290       
00291       template<class G>
00292       void examine(G& graph, const typename G::EdgeIterator& edge, const ColIter& col);
00293 
00294       bool isIsolated();
00295     private:
00297       const Matrix* matrix_;
00299       typename Matrix::field_type maxValue_;
00301       Norm norm_;      
00303       int row_;
00305       typename Matrix::field_type diagonal_;
00306     };
00307         
00311     template<class M, class N>
00312     class SymmetricDependency : public DependencyParameters
00313     {
00314     public:
00318       typedef M Matrix;
00319       
00323       typedef N Norm;
00324 
00328       typedef typename Matrix::row_type Row;
00329 
00333       typedef typename Matrix::ConstColIterator ColIter;
00334       
00335       void init(const Matrix* matrix);
00336       
00337       void initRow(const Row& row, int index);
00338 
00339       void examine(const ColIter& col);
00340       
00341       template<class G>
00342       void examine(G& graph, const typename G::EdgeIterator& edge, const ColIter& col);
00343 
00344       bool isIsolated();
00345     private:
00347       const Matrix* matrix_;
00349       typename Matrix::field_type maxValue_;
00351       Norm norm_;      
00353       int row_;
00355       typename Matrix::field_type diagonal_;
00356     };
00357 
00362     template<int N>
00363     class Diagonal
00364     {
00365     public:
00366       enum{ /* @brief We preserve the sign.*/
00367         is_sign_preserving = true
00368       };
00369       
00374       template<class M>
00375       typename M::field_type operator()(const M& m) const
00376       {
00377         return m[N][N];
00378       }
00379     };
00380 
00385     class FirstDiagonal : public Diagonal<0>
00386     {};
00387     
00393     struct RowSum
00394     {
00395       
00396       enum{ /* @brief We preserve the sign.*/
00397         is_sign_preserving = false
00398       };
00403       template<class M>
00404       typename M::field_type operator()(const M& m) const
00405       {
00406         return m.infinity_norm();
00407       }
00408     };
00409 
00419     template<class M, class Norm>
00420     class SymmetricCriterion : public AggregationCriterion<SymmetricDependency<M,Norm> >
00421     {};
00422 
00423     
00435     template<class M, class Norm>
00436     class UnSymmetricCriterion : public AggregationCriterion<Dependency<M,Norm> >
00437     {};
00438     // forward declaration
00439     template<class G> class Aggregator;
00440 
00441     
00449     template<class V>
00450     class AggregatesMap
00451     {
00452     public:
00453 
00457       static const V UNAGGREGATED;
00458       
00462       static const V ISOLATED;
00466       typedef V VertexDescriptor;
00467       
00471       typedef V AggregateDescriptor;
00472 
00477       typedef PoolAllocator<VertexDescriptor,100> Allocator;
00478       
00483       typedef SLList<VertexDescriptor,Allocator> VertexList;
00484 
00488       class DummyEdgeVisitor
00489       {
00490       public:
00491         template<class EdgeIterator>
00492         void operator()(const EdgeIterator& egde) const
00493         {}
00494       };
00495       
00496         
00500       AggregatesMap();
00501       
00507       AggregatesMap(std::size_t noVertices);
00508 
00512       ~AggregatesMap();
00513 
00521       template<class M, class G, class C>
00522       tuple<int,int,int,int> buildAggregates(const M& matrix, G& graph, const C& criterion);
00523       
00543       template<bool reset, class G, class F, class VM>
00544       std::size_t breadthFirstSearch(const VertexDescriptor& start,
00545                              const AggregateDescriptor& aggregate, 
00546                              const G& graph,
00547                              F& aggregateVisitor,
00548                                      VM& visitedMap) const;
00549       
00573       template<bool remove, bool reset, class G, class L, class F1, class F2, class VM>
00574       std::size_t breadthFirstSearch(const VertexDescriptor& start, 
00575                              const AggregateDescriptor& aggregate, 
00576                              const G& graph, L& visited, F1& aggregateVisitor,
00577                              F2& nonAggregateVisitor,
00578                              VM& visitedMap) const;
00579 
00585       void allocate(std::size_t noVertices);
00586       
00590       std::size_t noVertices() const;
00591       
00595       void free();
00596             
00602       AggregateDescriptor& operator[](const VertexDescriptor& v);
00603       
00609       const AggregateDescriptor& operator[](const VertexDescriptor& v) const;
00610 
00611       typedef const AggregateDescriptor* const_iterator;
00612       
00613       const_iterator begin() const
00614       {
00615         return aggregates_;
00616       }
00617       
00618       const_iterator end() const
00619       {
00620         return aggregates_+noVertices();
00621       }
00622       
00623       typedef AggregateDescriptor* iterator;
00624       
00625       iterator begin()
00626       {
00627         return aggregates_;
00628       }
00629       
00630       iterator end()
00631       {
00632         return aggregates_+noVertices();
00633       }
00634     private:
00636       AggregatesMap(const AggregatesMap<V>& map)
00637       {
00638         throw "Auch!";
00639       }
00640       
00642       AggregatesMap<V>& operator=(const AggregatesMap<V>& map)
00643       {
00644         throw "Auch!";
00645         return this;
00646       }
00647       
00651       AggregateDescriptor* aggregates_;
00652 
00656       std::size_t noVertices_;
00657     };
00658 
00662       template<class G, class C>
00663       void buildDependency(G& graph,
00664                            const typename C::Matrix& matrix,
00665                            C criterion);
00666     
00671     template<class G, class S>
00672     class Aggregate
00673     {
00674       
00675     public:
00676             
00677       /***
00678        * @brief The type of the matrix graph we work with.
00679        */
00680       typedef G MatrixGraph;
00684       typedef typename MatrixGraph::VertexDescriptor Vertex;
00685 
00690       typedef PoolAllocator<Vertex,100> Allocator;
00691       
00696       typedef SLList<Vertex,Allocator> VertexList;
00697 
00698       
00703       typedef S VertexSet;
00704 
00706       typedef typename VertexList::const_iterator const_iterator;
00707 
00711       typedef std::size_t* SphereMap;
00712       
00720       Aggregate(const MatrixGraph& graph, AggregatesMap<Vertex>& aggregates, 
00721                 VertexSet& connectivity);
00722             
00729       void reconstruct(const Vertex& vertex);
00730       
00734       void seed(const Vertex& vertex);
00735       
00739       void add(const Vertex& vertex);
00740       
00744       void clear();
00745       
00749       typename VertexList::size_type size();
00753       typename VertexList::size_type connectSize();
00754       
00758       int id();
00759       
00761       const_iterator begin() const;
00762       
00764       const_iterator end() const;
00765       
00766     private:
00770       VertexList vertices_;
00771       
00776       int id_;
00777 
00781       const MatrixGraph& graph_;
00782       
00786       AggregatesMap<Vertex>& aggregates_;
00787 
00791       VertexSet& connected_;
00792     };
00793     
00797     template<class G>
00798     class Aggregator
00799     {
00800     public:
00801             
00805       typedef G MatrixGraph;
00806 
00810       typedef typename MatrixGraph::VertexDescriptor Vertex;
00811       
00813       typedef typename MatrixGraph::VertexDescriptor AggregateDescriptor;
00814 
00818       Aggregator();
00819       
00823       ~Aggregator();
00824       
00837       template<class M, class C>
00838       tuple<int,int,int,int> build(const M& m, G& graph, 
00839                                AggregatesMap<Vertex>& aggregates, const C& c);
00840     private:
00845       typedef PoolAllocator<Vertex,100> Allocator;
00846       
00850       typedef SLList<Vertex,Allocator> VertexList;
00851 
00855       typedef std::set<Vertex,std::less<Vertex>,Allocator> VertexSet;
00856 
00860       typedef std::size_t* SphereMap;
00861       
00865       MatrixGraph* graph_;
00866       
00870       Aggregate<MatrixGraph,VertexSet>* aggregate_;
00871       
00875       VertexList front_;
00876 
00880       VertexSet connected_;
00881             
00885       int size_;
00886       
00890       class Stack
00891       {
00892       public:
00893         static const Vertex NullEntry;
00894         
00895         Stack(const MatrixGraph& graph, 
00896               const Aggregator<G>& aggregatesBuilder,
00897               const AggregatesMap<Vertex>& aggregates);
00898         ~Stack();
00899         bool push(const Vertex& v);
00900         void fill();
00901         Vertex pop();
00902       private:
00903         enum{ N = 256000 };
00904         
00906         const MatrixGraph& graph_;
00908         const Aggregator<G>& aggregatesBuilder_;
00910         const AggregatesMap<Vertex>& aggregates_;
00912         int size_;
00913         int maxSize_;
00915         int head_;
00916         int filled_;
00917         
00919         Vertex* vals_;
00920 
00921         void localPush(const Vertex& v);
00922       };
00923 
00924       friend class Stack;
00925 
00936       template<class V>
00937       void visitAggregateNeighbours(const Vertex& vertex, const AggregateDescriptor& aggregate,  
00938                                     const AggregatesMap<Vertex>& aggregates,
00939                                     V& visitor) const;
00940 
00945       template<class V>
00946       class AggregateVisitor
00947       {
00948       public:
00952         typedef V Visitor;
00960         AggregateVisitor(const AggregatesMap<Vertex>& aggregates, const AggregateDescriptor& aggregate,
00961                          Visitor& visitor);
00962         
00969         void operator()(const typename MatrixGraph::ConstEdgeIterator& edge);
00970         
00971       private:
00973         const AggregatesMap<Vertex>& aggregates_;
00975         AggregateDescriptor aggregate_;
00977         Visitor* visitor_;
00978       };
00979 
00983       class Counter
00984       {
00985       public:
00987         Counter();
00989         int value();
00990         
00991       protected:
00993         void increment();
00995         void decrement();
00996         
00997       private:
00998         int count_;
00999       };
01000 
01001       
01006       class FrontNeighbourCounter : public Counter
01007       {
01008       public:
01013         FrontNeighbourCounter(const MatrixGraph& front);
01014         
01015         void operator()(const typename MatrixGraph::ConstEdgeIterator& edge);
01016         
01017       private:
01018         const MatrixGraph& graph_;
01019       };
01020       
01025       int noFrontNeighbours(const Vertex& vertex) const;
01026       
01030       class TwoWayCounter : public Counter
01031       {
01032       public:
01033         void operator()(const typename MatrixGraph::ConstEdgeIterator& edge);
01034       };
01035 
01047       int twoWayConnections(const Vertex&, const AggregateDescriptor& aggregate,  
01048                              const AggregatesMap<Vertex>& aggregates) const;
01049 
01053       class OneWayCounter : public Counter
01054       {
01055       public:
01056         void operator()(const typename MatrixGraph::ConstEdgeIterator& edge);
01057       };        
01058 
01070       int oneWayConnections(const Vertex&, const AggregateDescriptor& aggregate,  
01071                             const AggregatesMap<Vertex>& aggregates) const;
01072       
01079       class ConnectivityCounter : public Counter
01080       {
01081       public:
01088         ConnectivityCounter(const VertexSet& connected, const AggregatesMap<Vertex>& aggregates);
01089 
01090         void operator()(const typename MatrixGraph::ConstEdgeIterator& edge);
01091 
01092       private:
01094         const VertexSet& connected_;
01096         const AggregatesMap<Vertex>& aggregates_;
01097         
01098       };
01099 
01111       double connectivity(const Vertex& vertex, const AggregatesMap<Vertex>& aggregates) const;
01119       bool connected(const Vertex& vertex, const AggregateDescriptor& aggregate, 
01120                      const AggregatesMap<Vertex>& aggregates) const;
01121 
01129       bool connected(const Vertex& vertex, const SLList<AggregateDescriptor>& aggregateList, 
01130                      const AggregatesMap<Vertex>& aggregates) const;
01131 
01139       class DependencyCounter: public Counter
01140       {
01141       public:
01145         DependencyCounter();
01146         
01147         void operator()(const typename MatrixGraph::ConstEdgeIterator& edge);
01148       };
01149       
01156       class FrontMarker
01157       {
01158       public:
01165         FrontMarker(VertexList& front, MatrixGraph& graph);
01166         
01167         void operator()(const typename MatrixGraph::ConstEdgeIterator& edge);
01168         
01169       private:
01171         VertexList& front_;
01173         MatrixGraph& graph_;
01174       };
01175 
01182       void markFront(const AggregatesMap<Vertex>& aggregates);
01183       
01187       void unmarkFront();
01188       
01203       int unusedNeighbours(const Vertex& vertex, const AggregatesMap<Vertex>& aggregates) const;
01204 
01218       std::pair<int,int> neighbours(const Vertex& vertex, 
01219                                     const AggregateDescriptor& aggregate,
01220                                     const AggregatesMap<Vertex>& aggregates) const;
01237       int aggregateNeighbours(const Vertex& vertex, const AggregateDescriptor& aggregate, const AggregatesMap<Vertex>& aggregates) const;
01238       
01246       bool admissible(const Vertex& vertex, const AggregateDescriptor& aggregate, const AggregatesMap<Vertex>& aggregates) const;
01247       
01254       void seedFromFront(Stack& stack,  bool isolated);
01255         
01263       std::size_t distance(const Vertex& vertex, const AggregatesMap<Vertex>& aggregates);
01264 
01273       Vertex mergeNeighbour(const Vertex& vertex, const AggregatesMap<Vertex>& aggregates) const;
01274 
01283       void nonisoNeighbourAggregate(const Vertex& vertex, 
01284                                     const AggregatesMap<Vertex>& aggregates,
01285                                     SLList<Vertex>& neighbours) const;
01286 
01294       template<class C>
01295       void growAggregate(const Vertex& vertex, const AggregatesMap<Vertex>& aggregates, const C& c);
01296       template<class C>
01297       void growIsolatedAggregate(const Vertex& vertex, const AggregatesMap<Vertex>& aggregates, const C& c);
01298     };
01299 
01300 #ifndef DOXYGEN
01301 
01302     template<class M, class N>
01303     inline void SymmetricDependency<M,N>::init(const Matrix* matrix)
01304     {
01305       matrix_ = matrix;
01306     }
01307     
01308     template<class M, class N>
01309     inline void SymmetricDependency<M,N>::initRow(const Row& row, int index)
01310     {
01311       maxValue_ = std::min(- std::numeric_limits<typename Matrix::field_type>::max(), std::numeric_limits<typename Matrix::field_type>::min());
01312       row_ = index;
01313       diagonal_ = norm_(matrix_->operator[](row_)[row_]);
01314     }
01315 
01316     template<class M, class N>
01317     inline void SymmetricDependency<M,N>::examine(const ColIter& col)
01318     {
01319       typename Matrix::field_type eij = norm_(*col);
01320       typename Matrix::field_type eji = norm_(matrix_->operator[](col.index())[row_]);
01321       
01322       // skip positve offdiagonals if norm preserves sign of them.
01323       if(!N::is_sign_preserving || eij<0 || eji<0)
01324         maxValue_ = std::max(maxValue_, 
01325                              eij /diagonal_ * eji/
01326                              norm_(matrix_->operator[](col.index())[col.index()]));
01327     }
01328     
01329     template<class M, class N>
01330     template<class G>
01331     inline void SymmetricDependency<M,N>::examine(G& graph, const typename G::EdgeIterator& edge, const ColIter& col)
01332     {      
01333       typename Matrix::field_type eij = norm_(*col);
01334       typename Matrix::field_type eji = norm_(matrix_->operator[](col.index())[row_]);
01335       
01336       // skip positve offdiagonals if norm preserves sign of them.
01337       if(!N::is_sign_preserving || (eij<0 || eji<0))
01338         if(eji / norm_(matrix_->operator[](edge.target())[edge.target()]) * 
01339            eij/ diagonal_ > alpha() * maxValue_){
01340         edge.properties().setDepends();
01341         edge.properties().setInfluences();
01342 
01343         typename G::EdgeProperties& other = graph.getEdgeProperties(edge.target(), edge.source());
01344         other.setInfluences();
01345         other.setDepends();
01346       }
01347     }
01348     
01349     template<class M, class N>
01350     inline bool SymmetricDependency<M,N>::isIsolated()
01351     {
01352       return maxValue_  < beta();
01353     }
01354     
01355     
01356     template<class M, class N>
01357     inline void Dependency<M,N>::init(const Matrix* matrix)
01358     {
01359       matrix_ = matrix;
01360     }
01361     
01362     template<class M, class N>
01363     inline void Dependency<M,N>::initRow(const Row& row, int index)
01364     {
01365       maxValue_ = std::min(- std::numeric_limits<typename Matrix::field_type>::max(), std::numeric_limits<typename Matrix::field_type>::min());
01366       row_ = index;
01367       diagonal_ = norm_(matrix_->operator[](row_)[row_]);
01368     }
01369 
01370     template<class M, class N>
01371     inline void Dependency<M,N>::examine(const ColIter& col)
01372     {
01373       maxValue_ = std::max(maxValue_, 
01374                            -norm_(*col));
01375     }
01376     
01377     template<class M, class N>
01378     template<class G>
01379     inline void Dependency<M,N>::examine(G& graph, const typename G::EdgeIterator& edge, const ColIter& col)
01380     {      
01381       if(-norm_(*col) >= maxValue_ * alpha()){
01382         edge.properties().setDepends();
01383         typename G::EdgeProperties& other = graph.getEdgeProperties(edge.target(), edge.source());
01384         other.setInfluences();
01385           }
01386     }
01387     
01388     template<class M, class N>
01389     inline bool Dependency<M,N>::isIsolated()
01390     {
01391       return maxValue_  < beta() * diagonal_;
01392     }
01393     
01394     template<class G,class S>
01395     Aggregate<G,S>::Aggregate(const MatrixGraph& graph, AggregatesMap<Vertex>& aggregates,
01396                             VertexSet& connected)
01397       : vertices_(), id_(-1), graph_(graph), aggregates_(aggregates),
01398         connected_(connected)
01399     {}
01400     
01401     template<class G,class S>
01402     void Aggregate<G,S>::reconstruct(const Vertex& vertex)
01403     {
01404       vertices_.push_back(vertex);
01405       typedef typename VertexList::const_iterator iterator;
01406       iterator begin = vertices_.begin();
01407       iterator end   = vertices_.end();
01408       throw "Not yet implemented";
01409 
01410       while(begin!=end){
01411         //for();
01412       }
01413       
01414     }
01415     
01416     template<class G,class S>
01417     inline void Aggregate<G,S>::seed(const Vertex& vertex)
01418     {
01419       dvverb<<"Connected cleared"<<std::endl;
01420       connected_.clear();
01421       vertices_.clear();
01422       connected_.insert(vertex);
01423       dvverb << " Inserting "<<vertex<<" size="<<connected_.size();
01424       id_ = vertex;
01425       add(vertex);
01426     }
01427     
01428 
01429     template<class G,class S>
01430     inline void Aggregate<G,S>::add(const Vertex& vertex)
01431     {
01432       vertices_.push_back(vertex);
01433       aggregates_[vertex]=id_;
01434 
01435       typedef typename MatrixGraph::ConstEdgeIterator iterator;
01436       const iterator end = graph_.endEdges(vertex);
01437       for(iterator edge = graph_.beginEdges(vertex); edge != end; ++edge){
01438         dvverb << " Inserting "<<aggregates_[edge.target()];
01439         connected_.insert(aggregates_[edge.target()]);
01440         dvverb <<" size="<<connected_.size();
01441       }
01442       dvverb <<std::endl;
01443     }
01444     template<class G,class S>
01445     inline void Aggregate<G,S>::clear()
01446     {
01447       vertices_.clear();
01448       connected_.clear();
01449       id_=-1;
01450     }
01451     
01452     template<class G,class S>
01453     inline typename Aggregate<G,S>::VertexList::size_type 
01454     Aggregate<G,S>::size()
01455     {
01456       return vertices_.size();
01457     }
01458     
01459     template<class G,class S>
01460     inline typename Aggregate<G,S>::VertexList::size_type 
01461     Aggregate<G,S>::connectSize()
01462     {
01463       return connected_.size();
01464     }
01465     
01466     template<class G,class S>
01467     inline int Aggregate<G,S>::id()
01468     {
01469       return id_;
01470     }
01471 
01472     template<class G,class S>
01473     inline typename Aggregate<G,S>::const_iterator Aggregate<G,S>::begin() const
01474     {
01475       return vertices_.begin();
01476     }
01477     
01478     template<class G,class S>
01479     inline typename Aggregate<G,S>::const_iterator Aggregate<G,S>::end() const
01480     {
01481       return vertices_.end();
01482     }
01483 
01484     template<class V> 
01485     const V AggregatesMap<V>::UNAGGREGATED = std::numeric_limits<V>::max();
01486     
01487     template<class V> 
01488     const V AggregatesMap<V>::ISOLATED = std::numeric_limits<V>::max()-1;
01489     
01490     template<class V>
01491     AggregatesMap<V>::AggregatesMap()
01492       : aggregates_(0)
01493     {}
01494 
01495     template<class V>
01496     AggregatesMap<V>::~AggregatesMap()
01497     {
01498       if(aggregates_!=0)
01499         delete[] aggregates_;
01500     }
01501     
01502 
01503     template<class V>
01504     inline AggregatesMap<V>::AggregatesMap(std::size_t noVertices)
01505     {
01506       allocate(noVertices);
01507     }
01508 
01509     template<class V>
01510     inline std::size_t AggregatesMap<V>::AggregatesMap::noVertices() const
01511     {
01512       return noVertices_;
01513     }
01514     
01515     template<class V>
01516     inline void AggregatesMap<V>::allocate(std::size_t noVertices)
01517     {
01518       aggregates_ = new AggregateDescriptor[noVertices];
01519       noVertices_ = noVertices;
01520       
01521       for(std::size_t i=0; i < noVertices; i++)
01522         aggregates_[i]=UNAGGREGATED;
01523     }
01524 
01525     template<class V>
01526     inline void AggregatesMap<V>::free()
01527     {
01528       assert(aggregates_ != 0);
01529       delete[] aggregates_;
01530       aggregates_=0;
01531     }
01532     
01533     template<class V>
01534     inline typename AggregatesMap<V>::AggregateDescriptor& 
01535     AggregatesMap<V>::operator[](const VertexDescriptor& v)
01536     {
01537       return aggregates_[v];
01538     }
01539 
01540     template<class V>
01541     inline const typename AggregatesMap<V>::AggregateDescriptor& 
01542     AggregatesMap<V>::operator[](const VertexDescriptor& v) const
01543     {
01544       return aggregates_[v];
01545     }
01546 
01547     template<class V>
01548     template<bool reset, class G, class F,class VM>
01549     inline std::size_t AggregatesMap<V>::breadthFirstSearch(const V& start,
01550                                                     const AggregateDescriptor& aggregate, 
01551                                                     const G& graph, F& aggregateVisitor,
01552                                                             VM& visitedMap) const
01553     {
01554       VertexList vlist;
01555       
01556       DummyEdgeVisitor dummy;
01557       return breadthFirstSearch<true,reset>(start, aggregate, graph, vlist, aggregateVisitor, dummy, visitedMap);
01558     }
01559       
01560     template<class V>
01561     template<bool remove, bool reset, class G, class L, class F1, class F2, class VM>
01562     std::size_t AggregatesMap<V>::breadthFirstSearch(const V& start,
01563                                              const AggregateDescriptor& aggregate, 
01564                                              const G& graph,
01565                                              L& visited,
01566                                              F1& aggregateVisitor,
01567                                              F2& nonAggregateVisitor,
01568                                              VM& visitedMap) const
01569     {
01570       typedef typename L::const_iterator ListIterator;
01571       int visitedSpheres = 0;
01572       
01573       visited.push_back(start);
01574       put(visitedMap, start, true);
01575       
01576       ListIterator current = visited.begin();
01577       ListIterator end = visited.end();
01578       std::size_t i=0, size=visited.size();
01579       
01580       // visit the neighbours of all vertices of the
01581       // current sphere.
01582       while(current != end){
01583         
01584         for(;i<size; ++current, ++i){
01585           typedef typename G::ConstEdgeIterator EdgeIterator;
01586           const EdgeIterator endEdge = graph.endEdges(*current);
01587           
01588           for(EdgeIterator edge = graph.beginEdges(*current);
01589               edge != endEdge; ++edge){
01590           
01591             if(aggregates_[edge.target()]==aggregate){
01592               if(!get(visitedMap, edge.target())){
01593                 put(visitedMap, edge.target(), true);
01594                 visited.push_back(edge.target());
01595                 aggregateVisitor(edge);
01596               }
01597             }else
01598               nonAggregateVisitor(edge);
01599           }
01600         }       
01601         end = visited.end();
01602         size = visited.size();
01603         if(current != end)
01604           visitedSpheres++;
01605       }
01606       
01607       if(reset)
01608         for(current = visited.begin(); current != end; ++current)
01609           put(visitedMap, *current, false);
01610       
01611         
01612       if(remove)
01613         visited.clear();
01614       
01615       return visitedSpheres;
01616     }
01617     
01618     template<class G>
01619     Aggregator<G>::Aggregator()
01620       : graph_(0), aggregate_(0), front_(), connected_(), size_(-1)
01621     {}
01622     
01623     template<class G>
01624     Aggregator<G>::~Aggregator()
01625     {
01626       size_=-1;
01627     }
01628     
01629     template<class G, class C>
01630     void buildDependency(G& graph,
01631                          const typename C::Matrix& matrix,
01632                          C criterion)
01633     {
01634       // The Criterion we use for building the dependency.
01635       typedef C Criterion;
01636      
01637       //      assert(graph.isBuilt());
01638       typedef typename C::Matrix Matrix;
01639       typedef typename G::VertexIterator VertexIterator;
01640       
01641       criterion.init(&matrix);
01642       
01643       for(VertexIterator vertex = graph.begin(); vertex != graph.end(); ++vertex){
01644         typedef typename Matrix::row_type Row;
01645         
01646         const Row& row = matrix[*vertex];
01647         
01648         // Tell the criterion what row we will examine now
01649         // This might for example be used for calculating the
01650         // maximum offdiagonal value
01651         criterion.initRow(row, *vertex);
01652         
01653         // On a first path all columns are examined. After this 
01654         // the calculator should know whether the vertex is isolated.
01655         typedef typename Matrix::ConstColIterator ColIterator;
01656         ColIterator end = row.end();
01657         typename Matrix::field_type absoffdiag=0;
01658 
01659         for(ColIterator col = row.begin(); col != end; ++col)
01660           if(col.index()!=*vertex){
01661             criterion.examine(col);
01662             absoffdiag=std::max(absoffdiag, col->frobenius_norm());
01663           }
01664         
01665         if(absoffdiag==0)
01666           vertex.properties().setExcludedBorder();
01667         
01668         // reset the vertex properties
01669         //vertex.properties().reset();
01670                 
01671         // Check whether the vertex is isolated.
01672         if(criterion.isIsolated()){
01673           //std::cout<<"ISOLATED: "<<*vertex<<std::endl;
01674           vertex.properties().setIsolated();
01675         }else{
01676           // Examine all the edges beginning at this vertex.
01677           typedef typename G::EdgeIterator EdgeIterator;
01678           typedef typename Matrix::ConstColIterator ColIterator;
01679           EdgeIterator end = vertex.end();
01680           ColIterator col = matrix[*vertex].begin();
01681           
01682           for(EdgeIterator edge = vertex.begin(); edge!= end; ++edge, ++col){
01683             // Move to the right column.
01684             while(col.index()!=edge.target())
01685               ++col;
01686             criterion.examine(graph, edge, col);
01687           }
01688         }
01689         
01690       }
01691     }
01692 
01693     
01694     template<class G>
01695     template<class V>
01696     inline Aggregator<G>::AggregateVisitor<V>::AggregateVisitor(const AggregatesMap<Vertex>& aggregates, 
01697                                                         const AggregateDescriptor& aggregate, V& visitor)
01698       : aggregates_(aggregates), aggregate_(aggregate), visitor_(&visitor)
01699     {}
01700     
01701     template<class G>
01702     template<class V>
01703     inline void Aggregator<G>::AggregateVisitor<V>::operator()(const typename MatrixGraph::ConstEdgeIterator& edge)
01704     {
01705       if(aggregates_[edge.target()]==aggregate_)
01706         visitor_->operator()(edge);
01707     }
01708     
01709     template<class G>
01710     template<class V>
01711     inline void Aggregator<G>::visitAggregateNeighbours(const Vertex& vertex,
01712                                                         const AggregateDescriptor& aggregate, 
01713                                                         const AggregatesMap<Vertex>& aggregates,
01714                                                         V& visitor) const
01715     {  
01716       // Only evaluates for edge pointing to the aggregate
01717       AggregateVisitor<V> v(aggregates, aggregate, visitor);
01718       visitNeighbours(*graph_, vertex, v);
01719     }
01720     
01721     
01722     template<class G>
01723     inline Aggregator<G>::Counter::Counter()
01724       : count_(0)
01725     {}
01726     
01727     template<class G>
01728     inline void Aggregator<G>::Counter::increment()
01729     {
01730       ++count_;
01731     }
01732 
01733     template<class G>
01734     inline void Aggregator<G>::Counter::decrement()
01735     {
01736       --count_;
01737     }
01738     template<class G>
01739     inline int Aggregator<G>::Counter::value()
01740     {
01741       return count_;
01742     }
01743     
01744     template<class G>
01745     inline void  Aggregator<G>::TwoWayCounter::operator()(const typename MatrixGraph::ConstEdgeIterator& edge)
01746     {
01747       if(edge.properties().isTwoWay())
01748         Counter::increment();
01749     }
01750     
01751     template<class G>
01752     int Aggregator<G>::twoWayConnections(const Vertex& vertex, const AggregateDescriptor& aggregate,
01753                                          const AggregatesMap<Vertex>& aggregates) const
01754     {
01755       TwoWayCounter counter;
01756       visitAggregateNeighbours(vertex, aggregate, aggregates, counter);
01757       return counter.value();
01758     }
01759     
01760     template<class G>
01761     int Aggregator<G>::oneWayConnections(const Vertex& vertex, const AggregateDescriptor& aggregate,
01762                                          const AggregatesMap<Vertex>& aggregates) const
01763     {
01764       OneWayCounter counter;
01765       visitAggregateNeighbours(vertex, aggregate, aggregates, counter);
01766       return counter.value();
01767     }
01768     
01769     template<class G>
01770     inline void Aggregator<G>::OneWayCounter::operator()(const typename MatrixGraph::ConstEdgeIterator& edge)
01771     {
01772       if(edge.properties().isOneWay())
01773         Counter::increment();
01774     }
01775     
01776     template<class G>
01777     inline Aggregator<G>::ConnectivityCounter::ConnectivityCounter(const VertexSet& connected,
01778                                                                    const AggregatesMap<Vertex>& aggregates)
01779       : Counter(), connected_(connected), aggregates_(aggregates)
01780     {}
01781     
01782     
01783     template<class G>
01784     inline void Aggregator<G>::ConnectivityCounter::operator()(const typename MatrixGraph::ConstEdgeIterator& edge)
01785     {
01786       if(connected_.find(aggregates_[edge.target()]) == connected_.end() || aggregates_[edge.target()]==AggregatesMap<Vertex>::UNAGGREGATED)
01787         // Would be a new connection
01788         Counter::increment();
01789       else{
01790         Counter::increment();
01791         Counter::increment();
01792       }
01793     }
01794     
01795     template<class G>
01796     inline double Aggregator<G>::connectivity(const Vertex& vertex, const AggregatesMap<Vertex>& aggregates) const
01797     {
01798       ConnectivityCounter counter(connected_, aggregates);
01799       double noNeighbours=visitNeighbours(*graph_, vertex, counter);
01800       return (double)counter.value()/noNeighbours;
01801     }
01802     
01803     template<class G>
01804     inline Aggregator<G>::DependencyCounter::DependencyCounter()
01805       : Counter()
01806     {}
01807     
01808     template<class G>
01809     inline void Aggregator<G>::DependencyCounter::operator()(const typename MatrixGraph::ConstEdgeIterator& edge)
01810     {
01811       if(edge.properties().depends())
01812         Counter::increment();
01813       if(edge.properties().influences())
01814         Counter::increment();
01815     }
01816     
01817     template<class G>
01818     int Aggregator<G>::unusedNeighbours(const Vertex& vertex, const AggregatesMap<Vertex>& aggregates) const
01819     {
01820       return aggregateNeighbours(vertex, AggregatesMap<Vertex>::UNAGGREGATED, aggregates);
01821     }
01822     
01823     template<class G>
01824     std::pair<int,int> Aggregator<G>::neighbours(const Vertex& vertex,
01825                                                  const AggregateDescriptor& aggregate,
01826                                                  const AggregatesMap<Vertex>& aggregates) const
01827     {
01828       DependencyCounter unused, aggregated;
01829       typedef AggregateVisitor<DependencyCounter> Counter;
01830       typedef tuple<Counter,Counter> CounterTuple;
01831       CombinedFunctor<CounterTuple> visitors(CounterTuple(Counter(aggregates, AggregatesMap<Vertex>::UNAGGREGATED, unused), Counter(aggregates, aggregate, aggregated)));
01832       visitNeighbours(*graph_, vertex, visitors);
01833       return std::make_pair(unused.value(), aggregated.value());
01834 }
01835       
01836       
01837     template<class G>
01838     int Aggregator<G>::aggregateNeighbours(const Vertex& vertex, const AggregateDescriptor& aggregate, const AggregatesMap<Vertex>& aggregates) const
01839     {
01840       DependencyCounter counter;
01841       visitAggregateNeighbours(vertex, aggregate, aggregates, counter);
01842       return counter.value();
01843     }
01844     
01845     template<class G>
01846     std::size_t Aggregator<G>::distance(const Vertex& vertex, const AggregatesMap<Vertex>& aggregates)
01847     {
01848       typename PropertyMapTypeSelector<VertexVisitedTag,G>::Type visitedMap = get(VertexVisitedTag(), *graph_);
01849       VertexList vlist;
01850       typename AggregatesMap<Vertex>::DummyEdgeVisitor dummy;
01851       return aggregates.template breadthFirstSearch<true,true>(vertex, 
01852                                                       aggregate_->id(), *graph_, 
01853                                            vlist, dummy, dummy, visitedMap);
01854     }
01855     
01856     template<class G>
01857     inline Aggregator<G>::FrontMarker::FrontMarker(VertexList& front, MatrixGraph& graph)
01858       : front_(front), graph_(graph)
01859     {}
01860     
01861     template<class G>
01862     inline void Aggregator<G>::FrontMarker::operator()(const typename MatrixGraph::ConstEdgeIterator& edge)
01863     {
01864       Vertex target = edge.target();
01865       
01866       if(!graph_.getVertexProperties(target).front()){
01867         front_.push_back(target);
01868         graph_.getVertexProperties(target).setFront();
01869       }
01870     }
01871         
01872 
01873     template<class G>
01874     void Aggregator<G>::markFront(const AggregatesMap<Vertex>& aggregates)
01875     {
01876       assert(front_.size()==0);
01877       FrontMarker frontBuilder(front_, *graph_);
01878       typedef typename Aggregate<G,VertexSet>::const_iterator Iterator;
01879       
01880       for(Iterator vertex=aggregate_->begin(); vertex != aggregate_->end(); ++vertex)
01881         visitAggregateNeighbours(*vertex, AggregatesMap<Vertex>::UNAGGREGATED, aggregates, frontBuilder);
01882       
01883     }
01884 
01885     template<class G>
01886     inline bool Aggregator<G>::admissible(const Vertex& vertex, const AggregateDescriptor& aggregate, const AggregatesMap<Vertex>& aggregates) const
01887     {
01888       // Todo
01889       Dune::dvverb<<" Admissible not yet implemented!"<<std::endl;
01890       return true;
01891       //Situation 1: front node depends on two nodes. Then these
01892       // have to be strongly connected to each other
01893       
01894       // Iterate over all all neighbours of front node
01895       typedef typename MatrixGraph::ConstEdgeIterator Iterator;
01896       Iterator vend = graph_->endEdges(vertex);
01897       for(Iterator edge = graph_->beginEdges(vertex); edge != vend; ++edge){
01898         // if(edge.properties().depends() && !edge.properties().influences()
01899         if(edge.properties().isStrong() 
01900            && aggregates[edge.target()]==aggregate)
01901           {
01902             // Search for another link to the aggregate
01903             Iterator edge1 = edge;
01904             for(++edge1; edge1 != vend; ++edge1){
01905               //if(edge1.properties().depends() && !edge1.properties().influences()
01906               if(edge1.properties().isStrong() 
01907                  && aggregates[edge.target()]==aggregate)
01908                 {
01909                   //Search for an edge connecting the two vertices that is
01910                   //strong
01911                   bool found=false;
01912                   Iterator v2end = graph_->endEdges(edge.target());
01913                   for(Iterator edge2 = graph_->beginEdges(edge.target()); edge2 != v2end; ++edge2){
01914                     if(edge2.target()==edge1.target() && 
01915                        edge2.properties().isStrong()){
01916                       found =true;
01917                       break;
01918                     }
01919                   }             
01920                   if(found)
01921                     return true;
01922                 }
01923             }
01924           }
01925       }
01926       
01927       // Situation 2: cluster node depends on front node and other cluster node
01929       vend = graph_->endEdges(vertex);
01930       for(Iterator edge = graph_->beginEdges(vertex); edge != vend; ++edge){
01931         //if(!edge.properties().depends() && edge.properties().influences()
01932         if(edge.properties().isStrong() 
01933            && aggregates[edge.target()]==aggregate)
01934           {
01935             // Search for a link from target that stays within the aggregate
01936             Iterator v1end = graph_->endEdges(edge.target());
01937             
01938             for(Iterator edge1=graph_->beginEdges(edge.target()); edge1 != v1end; ++edge1){
01939               //if(edge1.properties().depends() && !edge1.properties().influences()
01940               if(edge1.properties().isStrong()
01941                  && aggregates[edge1.target()]==aggregate)
01942                 {
01943                   bool found=false;
01944                   // Check if front node is also connected to this one
01945                   Iterator v2end = graph_->endEdges(vertex);
01946                   for(Iterator edge2 = graph_->beginEdges(vertex); edge2 != v2end; ++edge2){
01947                     if(edge2.target()==edge1.target()){
01948                       if(edge2.properties().isStrong())
01949                         found=true;
01950                       break;
01951                     }
01952                   }
01953                   if(found)
01954                     return true;
01955                 }
01956             }
01957           }
01958       }
01959       return false;
01960     }
01961     
01962     template<class G>
01963     void Aggregator<G>::unmarkFront()
01964     {      
01965       typedef typename VertexList::const_iterator Iterator;
01966       
01967       for(Iterator vertex=front_.begin(); vertex != front_.end(); ++vertex)
01968         graph_->getVertexProperties(*vertex).resetFront();      
01969       
01970       front_.clear();
01971     }
01972 
01973     template<class G>
01974     inline void
01975     Aggregator<G>::nonisoNeighbourAggregate(const Vertex& vertex, 
01976                                             const AggregatesMap<Vertex>& aggregates,
01977                                             SLList<Vertex>& neighbours) const
01978     {
01979       typedef typename MatrixGraph::ConstEdgeIterator Iterator;
01980       Iterator end=graph_->beginEdges(vertex);
01981       neighbours.clear();
01982       
01983       for(Iterator edge=graph_->beginEdges(vertex); edge!=end; ++edge)
01984         {
01985           if(aggregates[edge.target()]!=AggregatesMap<Vertex>::UNAGGREGATED && graph_->getVertexProperties(edge.target()).isolated())
01986             neighbours.push_back(aggregates[edge.target()]);
01987         }
01988     }
01989     
01990     template<class G>
01991     inline typename G::VertexDescriptor Aggregator<G>::mergeNeighbour(const Vertex& vertex, const AggregatesMap<Vertex>& aggregates) const
01992     {
01993       typedef typename MatrixGraph::ConstEdgeIterator Iterator;
01994       
01995       Iterator end = graph_->endEdges(vertex);
01996       for(Iterator edge = graph_->beginEdges(vertex); edge != end; ++edge){
01997         if(aggregates[edge.target()] != AggregatesMap<Vertex>::UNAGGREGATED &&
01998            graph_->getVertexProperties(edge.target()).isolated() == graph_->getVertexProperties(edge.source()).isolated()){
01999           if( graph_->getVertexProperties(vertex).isolated() || 
02000               ((edge.properties().depends() || edge.properties().influences())
02001                && admissible(vertex, aggregates[edge.target()], aggregates)))
02002             return edge.target();
02003         }
02004       }
02005       return AggregatesMap<Vertex>::UNAGGREGATED;
02006     }
02007     
02008     template<class G>
02009     Aggregator<G>::FrontNeighbourCounter::FrontNeighbourCounter(const MatrixGraph& graph)
02010       : Counter(), graph_(graph)
02011     {}
02012 
02013     template<class G>
02014     void Aggregator<G>::FrontNeighbourCounter::operator()(const typename MatrixGraph::ConstEdgeIterator& edge)
02015     {
02016       if(graph_.getVertexProperties(edge.target()).front())
02017         Counter::increment();
02018     }
02019     
02020     template<class G>
02021     int Aggregator<G>::noFrontNeighbours(const Vertex& vertex) const
02022     {
02023       FrontNeighbourCounter counter(*graph_);
02024       visitNeighbours(*graph_, vertex, counter);
02025       return counter.value();
02026     }
02027     template<class G>
02028     inline bool Aggregator<G>::connected(const Vertex& vertex, 
02029                                          const AggregateDescriptor& aggregate,
02030                                          const AggregatesMap<Vertex>& aggregates) const
02031     {
02032       typedef typename G::ConstEdgeIterator iterator;
02033       const iterator end = graph_->endEdges(vertex);
02034       for(iterator edge = graph_->beginEdges(vertex); edge != end; ++edge)
02035             if(aggregates[edge.target()]==aggregate)
02036               return true;
02037       return false;
02038     }
02039     template<class G>
02040     inline bool Aggregator<G>::connected(const Vertex& vertex, 
02041                                          const SLList<AggregateDescriptor>& aggregateList,
02042                                          const AggregatesMap<Vertex>& aggregates) const
02043     {
02044       typedef typename SLList<AggregateDescriptor>::const_iterator Iter;
02045       for(Iter i=aggregateList.begin(); i!=aggregateList.end(); ++i)
02046         if(connected(vertex, *i, aggregates))
02047            return true;
02048       return false;
02049     }
02050     
02051     template<class G>
02052     template<class C>
02053     void Aggregator<G>::growIsolatedAggregate(const Vertex& seed, const AggregatesMap<Vertex>& aggregates, const C& c)
02054     {
02055       SLList<Vertex> connectedAggregates;
02056       nonisoNeighbourAggregate(seed, aggregates,connectedAggregates);
02057       
02058       while(aggregate_->size()< c.minAggregateSize() && aggregate_->connectSize() < c.maxConnectivity()){
02059         double maxCon=-1;
02060         std::size_t maxFrontNeighbours=0;
02061         
02062         Vertex candidate=AggregatesMap<Vertex>::UNAGGREGATED;
02063         unmarkFront();
02064         markFront(aggregates);
02065         typedef typename VertexList::const_iterator Iterator;
02066         
02067         for(Iterator vertex = front_.begin(); vertex != front_.end(); ++vertex){
02068           if(distance(*vertex, aggregates)>c.maxDistance())
02069             continue; // distance of proposes aggregate too big
02070           
02071           if(connectedAggregates.size()>0){
02072             // there is already a neighbour cluster
02073             // front node must be connected to same neighbour cluster
02074             
02075             if(!connected(*vertex, connectedAggregates, aggregates))
02076               continue;
02077           }
02078           
02079           double con = connectivity(*vertex, aggregates);
02080           
02081           if(con == maxCon){
02082             std::size_t frontNeighbours = noFrontNeighbours(*vertex);
02083             
02084             if(frontNeighbours >= maxFrontNeighbours){
02085               maxFrontNeighbours = frontNeighbours;
02086               candidate = *vertex;
02087             }
02088           }else if(con > maxCon){
02089               maxCon = con;
02090               maxFrontNeighbours = noFrontNeighbours(*vertex);
02091               candidate = *vertex;
02092           }
02093         }
02094 
02095         if(candidate==AggregatesMap<Vertex>::UNAGGREGATED)
02096           break;
02097 
02098         aggregate_->add(candidate);
02099       }
02100     }
02101     
02102     template<class G>
02103     template<class C>
02104     void Aggregator<G>::growAggregate(const Vertex& seed, const AggregatesMap<Vertex>& aggregates, const C& c)
02105     {
02106       while(aggregate_->size() < c.minAggregateSize()){
02107         int maxTwoCons=0, maxOneCons=0, maxNeighbours=-1;
02108         double maxCon=-1;
02109                 
02110         Vertex candidate = AggregatesMap<Vertex>::UNAGGREGATED;
02111         
02112         unmarkFront();
02113         markFront(aggregates);
02114 
02115         typedef typename VertexList::const_iterator Iterator;
02116           
02117         for(Iterator vertex = front_.begin(); vertex != front_.end(); ++vertex){
02118           // Only nonisolated nodes are considered
02119           if(graph_->getVertexProperties(*vertex).isolated())
02120             continue;
02121           
02122           int twoWayCons = twoWayConnections(*vertex, aggregate_->id(), aggregates);
02123           
02124           /* The case of two way connections. */
02125           if( maxTwoCons == twoWayCons && twoWayCons > 0){
02126             double con = connectivity(*vertex, aggregates);
02127 
02128             if(con == maxCon){
02129               int neighbours = noFrontNeighbours(*vertex);
02130               
02131               if(neighbours > maxNeighbours){
02132                 maxNeighbours = neighbours;
02133                 
02134                 std::size_t distance_ = distance(*vertex, aggregates);
02135 
02136                 if(c.maxDistance() >= distance_){
02137                   candidate = *vertex;
02138                 }
02139               }
02140             }else if( con > maxCon){
02141               maxCon = con;
02142               maxNeighbours = noFrontNeighbours(*vertex);
02143               std::size_t distance_ = distance(*vertex, aggregates);
02144 
02145               if(c.maxDistance() >= distance_){
02146                 candidate = *vertex;
02147               }
02148             }
02149           }else if(twoWayCons > maxTwoCons){
02150             maxTwoCons = twoWayCons;
02151             maxCon = connectivity(*vertex, aggregates);
02152             maxNeighbours = noFrontNeighbours(*vertex);
02153             std::size_t distance_ = distance(*vertex, aggregates);
02154             
02155             if(c.maxDistance() >= distance_){
02156               candidate = *vertex;
02157             }
02158             
02159             // two way connections preceed
02160             maxOneCons = std::numeric_limits<int>::max();
02161           }
02162           
02163           if(twoWayCons > 0)
02164             continue; // THis is a two-way node, skip tests for one way nodes
02165 
02166           /* The one way case */
02167           int oneWayCons = oneWayConnections(*vertex, aggregate_->id(), aggregates);
02168           
02169           if(oneWayCons==0)
02170             continue; // No strong connections, skip the tests.
02171 
02172           if(!admissible(*vertex, aggregate_->id(), aggregates))
02173             continue;
02174           
02175           if( maxOneCons == oneWayCons && oneWayCons > 0){
02176             double con = connectivity(*vertex, aggregates);
02177 
02178             if(con == maxCon){
02179               int neighbours = noFrontNeighbours(*vertex);
02180               
02181               if(neighbours > maxNeighbours){
02182                 maxNeighbours = neighbours;
02183                 std::size_t distance_ = distance(*vertex, aggregates);
02184                 
02185                 if(c.maxDistance() >= distance_){
02186                   candidate = *vertex;
02187                 }
02188               }
02189             }else if( con > maxCon){
02190               maxCon = con;
02191               maxNeighbours = noFrontNeighbours(*vertex);
02192               std::size_t distance_ = distance(*vertex, aggregates);
02193               if(c.maxDistance() >= distance_){
02194                 candidate = *vertex;
02195               }
02196             }
02197           }else if(oneWayCons > maxOneCons){
02198             maxOneCons = oneWayCons;
02199             maxCon = connectivity(*vertex, aggregates);
02200             maxNeighbours = noFrontNeighbours(*vertex);
02201             std::size_t distance_ = distance(*vertex, aggregates);
02202                 
02203             if(c.maxDistance() >= distance_){
02204               candidate = *vertex;
02205             }
02206           }
02207         }
02208         
02209         
02210         if(candidate == AggregatesMap<Vertex>::UNAGGREGATED)
02211           break; // No more candidates found
02212 
02213         aggregate_->add(candidate);
02214       }
02215     }
02216       
02217     template<typename V>
02218     template<typename M, typename G, typename C>
02219     tuple<int,int,int,int> AggregatesMap<V>::buildAggregates(const M& matrix, G& graph, const C& criterion)
02220     {
02221       Aggregator<G> aggregator;
02222       return aggregator.build(matrix, graph, *this, criterion);
02223     }
02224     
02225     template<class G>
02226     template<class M, class C>
02227     tuple<int,int,int,int> Aggregator<G>::build(const M& m, G& graph, AggregatesMap<Vertex>& aggregates, const C& c)
02228     {
02229       // Stack for fast vertex access
02230       Stack stack_(graph, *this, aggregates);
02231       
02232       graph_ = &graph;
02233             
02234       aggregate_ = new Aggregate<G,VertexSet>(graph, aggregates, connected_);
02235       
02236       Timer watch;
02237       watch.reset();
02238 
02239       buildDependency(graph, m, c);
02240 
02241       dverb<<"Build dependency took "<< watch.elapsed()<<" seconds."<<std::endl;
02242       int noAggregates, conAggregates, isoAggregates, oneAggregates;
02243       std::size_t maxA=0, minA=1000000, avg=0;
02244       int skippedAggregates;
02245       noAggregates = conAggregates = isoAggregates = oneAggregates = 
02246         skippedAggregates = 0;
02247       
02248       while(true){
02249         Vertex seed = stack_.pop();
02250         
02251         if(seed == Stack::NullEntry)
02252           // No more unaggregated vertices. We are finished!
02253           break;
02254         
02255         // Debugging output
02256         if((noAggregates+1)%10000 == 0)
02257           Dune::dverb<<"c";
02258         
02259         aggregate_->seed(seed);
02260         
02261         if(graph.getVertexProperties(seed).excludedBorder()){
02262           aggregates[seed]=AggregatesMap<Vertex>::ISOLATED;
02263           ++skippedAggregates;
02264           continue;
02265         }
02266         
02267         if(graph.getVertexProperties(seed).isolated()){
02268           if(c.skipIsolated()){
02269             // isolated vertices are not aggregated but skipped on the coarser levels.
02270             aggregates[seed]=AggregatesMap<Vertex>::ISOLATED;
02271             ++skippedAggregates;
02272             // skip rest as no agglomeration is done.
02273             continue;
02274           }else
02275             growIsolatedAggregate(seed, aggregates, c);
02276         }else
02277           growAggregate(seed, aggregates, c);
02278         
02279         
02280         /* The rounding step. */
02281         while(!(graph.getVertexProperties(seed).isolated()) && aggregate_->size() < c.maxAggregateSize()){
02282           
02283           unmarkFront();
02284           markFront(aggregates);
02285           
02286           Vertex candidate = AggregatesMap<Vertex>::UNAGGREGATED;
02287           
02288           typedef typename VertexList::const_iterator Iterator;
02289           
02290           for(Iterator vertex = front_.begin(); vertex != front_.end(); ++vertex){
02291 
02292             if(graph.getVertexProperties(*vertex).isolated())
02293               continue; // No isolated nodes here
02294 
02295             if(twoWayConnections( *vertex, aggregate_->id(), aggregates) == 0 && 
02296                (oneWayConnections( *vertex, aggregate_->id(), aggregates) == 0 || 
02297                 !admissible( *vertex, aggregate_->id(), aggregates) ))
02298               continue;
02299           
02300             std::pair<int,int> neighbourPair=neighbours(*vertex, aggregate_->id(),
02301                                                      aggregates);
02302             
02303             //if(aggregateNeighbours(*vertex, aggregate_->id(), aggregates) <= unusedNeighbours(*vertex, aggregates))
02304             // continue;
02305             
02306             if(neighbourPair.first >= neighbourPair.second)
02307               continue;
02308                     
02309             if(distance(*vertex, aggregates) > c.maxDistance())
02310               continue; // Distance too far
02311             candidate = *vertex;
02312             break;
02313           }
02314                   
02315           if(candidate == AggregatesMap<Vertex>::UNAGGREGATED) break; // no more candidates found.
02316           
02317           aggregate_->add(candidate);
02318           
02319         }
02320         
02321         // try to merge aggregates consisting of only one nonisolated vertex with other aggregates
02322         if(aggregate_->size()==1){
02323           if(!graph.getVertexProperties(seed).isolated()){
02324             Vertex mergedNeighbour = mergeNeighbour(seed, aggregates);
02325 
02326             if(mergedNeighbour != AggregatesMap<Vertex>::UNAGGREGATED){
02327               // assign vertex to the neighbouring cluster
02328               aggregates[seed] = aggregates[mergedNeighbour];
02329             }else{
02330               minA=std::min(minA,static_cast<std::size_t>(1));
02331               maxA=std::max(maxA,static_cast<std::size_t>(1));
02332               ++oneAggregates;
02333               ++conAggregates;
02334             }
02335           }else{
02336             ++avg;
02337             minA=std::min(minA,static_cast<std::size_t>(1));
02338             maxA=std::max(maxA,static_cast<std::size_t>(1));
02339             ++oneAggregates;
02340             ++isoAggregates;
02341           }
02342           ++avg;
02343         }else{
02344           avg+=aggregate_->size();
02345           minA=std::min(minA,aggregate_->size());
02346           maxA=std::max(maxA,aggregate_->size());
02347           if(graph.getVertexProperties(seed).isolated())
02348             ++isoAggregates;
02349           else
02350             ++conAggregates;
02351         }
02352         unmarkFront();
02353         markFront(aggregates);
02354         seedFromFront(stack_, graph.getVertexProperties(seed).isolated());
02355         unmarkFront();
02356       }
02357       
02358       Dune::dinfo<<"connected aggregates: "<<conAggregates;
02359       Dune::dinfo<<" isolated aggregates: "<<isoAggregates;
02360       Dune::dinfo<<" one node aggregates: "<<oneAggregates<<" min size="<<minA<<" max size="<<maxA
02361                <<" avg="<<avg/(conAggregates+isoAggregates)<<std::endl;
02362       
02363       delete aggregate_;
02364       return make_tuple(conAggregates+isoAggregates,isoAggregates,
02365                         oneAggregates,skippedAggregates);
02366     }
02367     
02368     template<class G>
02369     inline void Aggregator<G>::seedFromFront(Stack& stack_, bool isolated)
02370     {
02371       typedef typename VertexList::const_iterator Iterator;
02372       
02373       Iterator end= front_.end();
02374       int count=0;
02375       for(Iterator vertex=front_.begin(); vertex != end; ++vertex,++count)
02376         if(graph_->getVertexProperties(*vertex).isolated()==isolated)
02377           stack_.push(*vertex);
02378       /*
02379       if(MINIMAL_DEBUG_LEVEL<=2 && count==0 && !isolated)
02380         Dune::dverb<< " no vertices pushed for nonisolated aggregate!"<<std::endl;
02381       */
02382     }
02383 
02384     template<class G>
02385     Aggregator<G>::Stack::Stack(const MatrixGraph& graph, const Aggregator<G>& aggregatesBuilder,
02386                                 const AggregatesMap<Vertex>& aggregates)
02387       : graph_(graph), aggregatesBuilder_(aggregatesBuilder), aggregates_(aggregates), size_(0), maxSize_(0), head_(0), filled_(0)
02388     {
02389       vals_ = new  Vertex[N];
02390     }
02391     
02392     template<class G>
02393     Aggregator<G>::Stack::~Stack()
02394     {
02395       Dune::dverb << "Max stack size was "<<maxSize_<<" filled="<<filled_<<std::endl;
02396       delete[] vals_;
02397     }
02398     
02399     template<class G> 
02400     const typename Aggregator<G>::Vertex Aggregator<G>::Stack::NullEntry 
02401     = std::numeric_limits<typename G::VertexDescriptor>::max();
02402 
02403     template<class G>
02404     inline bool Aggregator<G>::Stack::push(const Vertex& v)
02405     {
02406       if(aggregates_[v] == AggregatesMap<Vertex>::UNAGGREGATED){
02407         localPush(v);
02408         return true;
02409       }else
02410         return false;
02411     }
02412     
02413     template<class G>
02414     inline void Aggregator<G>::Stack::localPush(const Vertex& v)
02415     {
02416       vals_[head_] = v;
02417       size_ = std::min<int>(size_+1, N);
02418       head_ = (head_+N+1)%N;
02419     }
02420     
02421     template<class G>
02422     void Aggregator<G>::Stack::fill()
02423     {
02424       int isolated = 0, connected=0;
02425       int isoumin, umin;
02426       filled_++;
02427       
02428       head_ = size_ = 0;
02429       isoumin = umin = std::numeric_limits<int>::max();
02430       
02431       typedef typename MatrixGraph::ConstVertexIterator Iterator;
02432       
02433       const Iterator end = graph_.end();
02434       
02435       for(Iterator vertex = graph_.begin(); vertex != end; ++vertex){
02436         // Skip already aggregated vertices
02437         if(aggregates_[*vertex] != AggregatesMap<Vertex>::UNAGGREGATED)
02438           continue;
02439         
02440         if(vertex.properties().isolated()){
02441           isoumin = std::min(isoumin, aggregatesBuilder_.unusedNeighbours(*vertex, aggregates_));
02442           isolated++;
02443         }else{
02444           umin = std::min(umin, aggregatesBuilder_.unusedNeighbours(*vertex, aggregates_));
02445           connected++;
02446         }
02447       }
02448       
02449       if(connected + isolated == 0)
02450         // No unaggregated vertices.
02451         return;
02452         
02453       if(connected > 0){
02454         // Connected vertices have higher priority.
02455          for(Iterator vertex = graph_.begin(); vertex != end; ++vertex)
02456            if(aggregates_[*vertex] == AggregatesMap<Vertex>::UNAGGREGATED && !vertex.properties().isolated() 
02457               && aggregatesBuilder_.unusedNeighbours(*vertex, aggregates_) == umin)
02458              localPush(*vertex);
02459       }else{
02460         for(Iterator vertex = graph_.begin(); vertex != end; ++vertex)
02461            if(aggregates_[*vertex] == AggregatesMap<Vertex>::UNAGGREGATED && vertex.properties().isolated() 
02462               && aggregatesBuilder_.unusedNeighbours(*vertex, aggregates_) == isoumin)
02463              localPush(*vertex);
02464       }
02465       maxSize_ = std::max(size_, maxSize_);
02466     }
02467 
02468     template<class G>
02469     inline typename G::VertexDescriptor Aggregator<G>::Stack::pop()
02470     {
02471       while(size_>0){
02472         head_ = (head_ + N -1) % N;
02473         size_--;
02474         Vertex v = vals_[head_];
02475         if(aggregates_[v]==AggregatesMap<Vertex>::UNAGGREGATED)
02476           return v;
02477       }
02478       // Stack is empty try to fill it
02479       fill();
02480       
02481       // try again
02482       while(size_>0){
02483         head_ = (head_ + N -1) % N;
02484         size_--;
02485         Vertex v = vals_[head_];
02486         if(aggregates_[v]==AggregatesMap<Vertex>::UNAGGREGATED)
02487           return v;
02488       }
02489       return NullEntry;
02490     }
02491 
02492 #endif // DOXYGEN
02493 
02494     template<class V>
02495     void printAggregates2d(const AggregatesMap<V>& aggregates, int n, int m,  std::ostream& os)
02496     {
02497       std::ios_base::fmtflags oldOpts=os.flags();
02498       
02499       os.setf(std::ios_base::right, std::ios_base::adjustfield);
02500       
02501       V max=0;
02502       int width=1;
02503 
02504       for(int i=0; i< n*m; i++)
02505         max=std::max(max, aggregates[i]);
02506       
02507       for(int i=10; i < 1000000; i*=10)
02508         if(max/i>0)
02509           width++;
02510         else
02511           break;
02512       
02513       for(int j=0, entry=0; j < m; j++){
02514         for(int i=0; i<n; i++, entry++){
02515           os.width(width);
02516           os<<aggregates[entry]<<" ";
02517         }
02518         
02519         os<<std::endl;
02520       }
02521       os<<std::endl;
02522       os.flags(oldOpts);
02523     }
02524     
02525     
02526   }// namespace Amg
02527   
02528 }// namespace Dune
02529 
02530 
02531 #endif
Generated on Sat Apr 24 11:13:45 2010 for dune-istl by  doxygen 1.6.3