COIN-OR::LEMON - Graph Library

Changeset 2535:716024e7c080 in lemon-0.x


Ignore:
Timestamp:
12/05/07 14:03:19 (16 years ago)
Author:
Peter Kovacs
Branch:
default
Phase:
public
Convert:
svn:c9d7d8f5-90d6-0310-b91f-818b3a526b0e/lemon/trunk@3412
Message:

Redesigned CapacityScaling? algorithm with almost the same interface.
The new version does not use the ResidualGraphAdaptor? for performance reasons.
Scaling can be enabled and disabled with a parameter of the run() function.

File:
1 edited

Legend:

Unmodified
Added
Removed
  • lemon/capacity_scaling.h

    r2533 r2535  
    2626/// flow.
    2727
     28#include <lemon/graph_adaptor.h>
     29#include <lemon/bin_heap.h>
    2830#include <vector>
    29 #include <lemon/graph_adaptor.h>
    30 #include <lemon/dijkstra.h>
    31 
    32 #define WITH_SCALING
    33 
    34 #ifdef WITH_SCALING
    35 #define SCALING_FACTOR    2
    36 #endif
    37 
    38 //#define _DEBUG_ITER_
    3931
    4032namespace lemon {
     
    4739  /// flow.
    4840  ///
    49   /// \ref lemon::CapacityScaling "CapacityScaling" implements the
    50   /// capacity scaling version of the successive shortest path
    51   /// algorithm for finding a minimum cost flow.
     41  /// \ref CapacityScaling implements the capacity scaling version
     42  /// of the successive shortest path algorithm for finding a minimum
     43  /// cost flow.
    5244  ///
    5345  /// \param Graph The directed graph type the algorithm runs on.
     
    5951  /// \warning
    6052  /// - Edge capacities and costs should be nonnegative integers.
    61   ///   However \c CostMap::Value should be signed type.
     53  ///   However \c CostMap::Value should be signed type.
    6254  /// - Supply values should be signed integers.
    6355  /// - \c LowerMap::Value must be convertible to
    64   ///   \c CapacityMap::Value and \c CapacityMap::Value must be
    65   ///   convertible to \c SupplyMap::Value.
     56  ///   \c CapacityMap::Value and \c CapacityMap::Value must be
     57  ///   convertible to \c SupplyMap::Value.
    6658  ///
    6759  /// \author Peter Kovacs
    6860
    6961  template < typename Graph,
    70              typename LowerMap = typename Graph::template EdgeMap<int>,
    71              typename CapacityMap = LowerMap,
    72              typename CostMap = typename Graph::template EdgeMap<int>,
    73              typename SupplyMap = typename Graph::template NodeMap
    74                                   <typename CapacityMap::Value> >
     62             typename LowerMap = typename Graph::template EdgeMap<int>,
     63             typename CapacityMap = LowerMap,
     64             typename CostMap = typename Graph::template EdgeMap<int>,
     65             typename SupplyMap = typename Graph::template NodeMap
     66                                  <typename CapacityMap::Value> >
    7567  class CapacityScaling
    7668  {
     
    8880    typedef typename Graph::template EdgeMap<Capacity> CapacityRefMap;
    8981    typedef typename Graph::template NodeMap<Supply> SupplyRefMap;
    90 
    91     typedef ResGraphAdaptor< const Graph, Capacity,
    92                              CapacityRefMap, CapacityRefMap > ResGraph;
    93     typedef typename ResGraph::Node ResNode;
    94     typedef typename ResGraph::NodeIt ResNodeIt;
    95     typedef typename ResGraph::Edge ResEdge;
    96     typedef typename ResGraph::EdgeIt ResEdgeIt;
     82    typedef typename Graph::template NodeMap<Edge> PredMap;
    9783
    9884  public:
     85
     86    /// \brief Type to enable or disable capacity scaling.
     87    enum ScalingEnum {
     88      WITH_SCALING = 0,
     89      WITHOUT_SCALING = -1
     90    };
    9991
    10092    /// \brief The type of the flow map.
     
    10597  protected:
    10698
    107     /// \brief Map adaptor class for handling reduced edge costs.
    108     class ReducedCostMap : public MapBase<ResEdge, Cost>
     99    /// \brief Special implementation of the \ref Dijkstra algorithm
     100    /// for finding shortest paths in the residual network of the graph
     101    /// with respect to the reduced edge costs and modifying the
     102    /// node potentials according to the distance of the nodes.
     103    class ResidualDijkstra
    109104    {
    110     private:
    111 
    112       const ResGraph &gr;
    113       const CostMap &cost_map;
    114       const PotentialMap &pot_map;
     105      typedef typename Graph::template NodeMap<Cost> CostNodeMap;
     106      typedef typename Graph::template NodeMap<Edge> PredMap;
     107
     108      typedef typename Graph::template NodeMap<int> HeapCrossRef;
     109      typedef BinHeap<Cost, HeapCrossRef> Heap;
     110
     111    protected:
     112
     113      /// \brief The directed graph the algorithm runs on.
     114      const Graph &graph;
     115
     116      /// \brief The flow map.
     117      const FlowMap &flow;
     118      /// \brief The residual capacity map.
     119      const CapacityRefMap &res_cap;
     120      /// \brief The cost map.
     121      const CostMap &cost;
     122      /// \brief The excess map.
     123      const SupplyRefMap &excess;
     124
     125      /// \brief The potential map.
     126      PotentialMap &potential;
     127
     128      /// \brief The distance map.
     129      CostNodeMap dist;
     130      /// \brief The map of predecessors edges.
     131      PredMap &pred;
     132      /// \brief The processed (i.e. permanently labeled) nodes.
     133      std::vector<Node> proc_nodes;
    115134
    116135    public:
    117136
    118       ReducedCostMap( const ResGraph &_gr,
    119                       const CostMap &_cost,
    120                       const PotentialMap &_pot ) :
    121         gr(_gr), cost_map(_cost), pot_map(_pot) {}
    122 
    123       Cost operator[](const ResEdge &e) const {
    124         return ResGraph::forward(e) ?
    125            cost_map[e] - pot_map[gr.source(e)] + pot_map[gr.target(e)] :
    126           -cost_map[e] - pot_map[gr.source(e)] + pot_map[gr.target(e)];
    127       }
    128 
    129     }; //class ReducedCostMap
    130 
    131     /// \brief Map class for the \ref lemon::Dijkstra "Dijkstra"
    132     /// algorithm to update node potentials.
    133     class PotentialUpdateMap : public MapBase<ResNode, Cost>
    134     {
    135     private:
    136 
    137       PotentialMap *pot;
    138       typedef std::pair<ResNode, Cost> Pair;
    139       std::vector<Pair> data;
    140 
    141     public:
    142 
    143       void potentialMap(PotentialMap &_pot) {
    144         pot = &_pot;
    145       }
    146 
    147       void init() {
    148         data.clear();
    149       }
    150 
    151       void set(const ResNode &n, const Cost &v) {
    152         data.push_back(Pair(n, v));
    153       }
    154 
    155       void update() {
    156         Cost val = data[data.size()-1].second;
    157         for (int i = 0; i < data.size()-1; ++i)
    158           (*pot)[data[i].first] += val - data[i].second;
    159       }
    160 
    161     }; //class PotentialUpdateMap
    162 
    163 #ifdef WITH_SCALING
    164     /// \brief Map adaptor class for identifing deficit nodes.
    165     class DeficitBoolMap : public MapBase<ResNode, bool>
    166     {
    167     private:
    168 
    169       const SupplyRefMap &imb;
    170       const Capacity &delta;
    171 
    172     public:
    173 
    174       DeficitBoolMap(const SupplyRefMap &_imb, const Capacity &_delta) :
    175         imb(_imb), delta(_delta) {}
    176 
    177       bool operator[](const ResNode &n) const {
    178         return imb[n] <= -delta;
    179       }
    180 
    181     }; //class DeficitBoolMap
    182 
    183     /// \brief Map adaptor class for filtering edges with at least
    184     /// \c delta residual capacity.
    185     class DeltaFilterMap : public MapBase<ResEdge, bool>
    186     {
    187     private:
    188 
    189       const ResGraph &gr;
    190       const Capacity &delta;
    191 
    192     public:
    193 
    194       DeltaFilterMap(const ResGraph &_gr, const Capacity &_delta) :
    195         gr(_gr), delta(_delta) {}
    196 
    197       bool operator[](const ResEdge &e) const {
    198         return gr.rescap(e) >= delta;
    199       }
    200 
    201     }; //class DeltaFilterMap
    202 
    203     typedef EdgeSubGraphAdaptor<const ResGraph, const DeltaFilterMap>
    204       DeltaResGraph;
    205 
    206     /// \brief Traits class for \ref lemon::Dijkstra "Dijkstra" class.
    207     class ResDijkstraTraits :
    208       public DijkstraDefaultTraits<DeltaResGraph, ReducedCostMap>
    209     {
    210     public:
    211 
    212       typedef PotentialUpdateMap DistMap;
    213 
    214       static DistMap *createDistMap(const DeltaResGraph&) {
    215         return new DistMap();
    216       }
    217 
    218     }; //class ResDijkstraTraits
    219 
    220 #else //WITHOUT_CAPACITY_SCALING
    221     /// \brief Map adaptor class for identifing deficit nodes.
    222     class DeficitBoolMap : public MapBase<ResNode, bool>
    223     {
    224     private:
    225 
    226       const SupplyRefMap &imb;
    227 
    228     public:
    229 
    230       DeficitBoolMap(const SupplyRefMap &_imb) : imb(_imb) {}
    231 
    232       bool operator[](const ResNode &n) const {
    233         return imb[n] < 0;
    234       }
    235 
    236     }; //class DeficitBoolMap
    237 
    238     /// \brief Traits class for \ref lemon::Dijkstra "Dijkstra" class.
    239     class ResDijkstraTraits :
    240       public DijkstraDefaultTraits<ResGraph, ReducedCostMap>
    241     {
    242     public:
    243 
    244       typedef PotentialUpdateMap DistMap;
    245 
    246       static DistMap *createDistMap(const ResGraph&) {
    247         return new DistMap();
    248       }
    249 
    250     }; //class ResDijkstraTraits
    251 #endif
     137      /// \brief The constructor of the class.
     138      ResidualDijkstra( const Graph &_graph,
     139                        const FlowMap &_flow,
     140                        const CapacityRefMap &_res_cap,
     141                        const CostMap &_cost,
     142                        const SupplyMap &_excess,
     143                        PotentialMap &_potential,
     144                        PredMap &_pred ) :
     145        graph(_graph), flow(_flow), res_cap(_res_cap), cost(_cost),
     146        excess(_excess), potential(_potential), dist(_graph),
     147        pred(_pred)
     148      {}
     149
     150      /// \brief Runs the algorithm from the given source node.
     151      Node run(Node s, Capacity delta) {
     152        HeapCrossRef heap_cross_ref(graph, Heap::PRE_HEAP);
     153        Heap heap(heap_cross_ref);
     154        heap.push(s, 0);
     155        pred[s] = INVALID;
     156        proc_nodes.clear();
     157
     158        // Processing nodes
     159        while (!heap.empty() && excess[heap.top()] > -delta) {
     160          Node u = heap.top(), v;
     161          Cost d = heap.prio() - potential[u], nd;
     162          dist[u] = heap.prio();
     163          heap.pop();
     164          proc_nodes.push_back(u);
     165
     166          // Traversing outgoing edges
     167          for (OutEdgeIt e(graph, u); e != INVALID; ++e) {
     168            if (res_cap[e] >= delta) {
     169              v = graph.target(e);
     170              switch(heap.state(v)) {
     171              case Heap::PRE_HEAP:
     172                heap.push(v, d + cost[e] + potential[v]);
     173                pred[v] = e;
     174                break;
     175              case Heap::IN_HEAP:
     176                nd = d + cost[e] + potential[v];
     177                if (nd < heap[v]) {
     178                  heap.decrease(v, nd);
     179                  pred[v] = e;
     180                }
     181                break;
     182              case Heap::POST_HEAP:
     183                break;
     184              }
     185            }
     186          }
     187
     188          // Traversing incoming edges
     189          for (InEdgeIt e(graph, u); e != INVALID; ++e) {
     190            if (flow[e] >= delta) {
     191              v = graph.source(e);
     192              switch(heap.state(v)) {
     193              case Heap::PRE_HEAP:
     194                heap.push(v, d - cost[e] + potential[v]);
     195                pred[v] = e;
     196                break;
     197              case Heap::IN_HEAP:
     198                nd = d - cost[e] + potential[v];
     199                if (nd < heap[v]) {
     200                  heap.decrease(v, nd);
     201                  pred[v] = e;
     202                }
     203                break;
     204              case Heap::POST_HEAP:
     205                break;
     206              }
     207            }
     208          }
     209        }
     210        if (heap.empty()) return INVALID;
     211
     212        // Updating potentials of processed nodes
     213        Node t = heap.top();
     214        Cost dt = heap.prio();
     215        for (int i = 0; i < proc_nodes.size(); ++i)
     216          potential[proc_nodes[i]] -= dist[proc_nodes[i]] - dt;
     217
     218        return t;
     219      }
     220
     221    }; //class ResidualDijkstra
    252222
    253223  protected:
     
    270240    /// \brief The potential node map.
    271241    PotentialMap potential;
    272     /// \brief The residual graph.
    273     ResGraph res_graph;
    274     /// \brief The reduced cost map.
    275     ReducedCostMap red_cost;
    276 
    277     /// \brief The imbalance map.
    278     SupplyRefMap imbalance;
    279     /// \brief The excess nodes.
    280     std::vector<ResNode> excess_nodes;
     242
     243    /// \brief The residual capacity map.
     244    CapacityRefMap res_cap;
     245    /// \brief The excess map.
     246    SupplyRefMap excess;
     247    /// \brief The excess nodes (i.e. nodes with positive excess).
     248    std::vector<Node> excess_nodes;
    281249    /// \brief The index of the next excess node.
    282250    int next_node;
    283251
    284 #ifdef WITH_SCALING
    285     typedef Dijkstra<DeltaResGraph, ReducedCostMap, ResDijkstraTraits>
    286       ResDijkstra;
    287     /// \brief \ref lemon::Dijkstra "Dijkstra" class for finding
    288     /// shortest paths in the residual graph with respect to the
    289     /// reduced edge costs.
    290     ResDijkstra dijkstra;
    291 
     252    /// \brief The scaling status (enabled or disabled).
     253    ScalingEnum scaling;
    292254    /// \brief The delta parameter used for capacity scaling.
    293255    Capacity delta;
    294     /// \brief Edge filter map for filtering edges with at least
    295     /// \c delta residual capacity.
    296     DeltaFilterMap delta_filter;
    297     /// \brief The delta residual graph (i.e. the subgraph of the
    298     /// residual graph consisting of edges with at least \c delta
    299     /// residual capacity).
    300     DeltaResGraph dres_graph;
    301     /// \brief Map for identifing deficit nodes.
    302     DeficitBoolMap delta_deficit;
    303 
     256    /// \brief The maximum number of phases.
     257    Capacity phase_num;
    304258    /// \brief The deficit nodes.
    305     std::vector<ResNode> deficit_nodes;
    306 
    307 #else //WITHOUT_CAPACITY_SCALING
    308     typedef Dijkstra<ResGraph, ReducedCostMap, ResDijkstraTraits>
    309       ResDijkstra;
    310     /// \brief \ref lemon::Dijkstra "Dijkstra" class for finding
    311     /// shortest paths in the residual graph with respect to the
    312     /// reduced edge costs.
    313     ResDijkstra dijkstra;
    314     /// \brief Map for identifing deficit nodes.
    315     DeficitBoolMap has_deficit;
    316 #endif
    317 
    318     /// \brief Pred map for the \ref lemon::Dijkstra "Dijkstra" class.
    319     typename ResDijkstra::PredMap pred;
    320     /// \brief Dist map for the \ref lemon::Dijkstra "Dijkstra" class to
    321     /// update node potentials.
    322     PotentialUpdateMap updater;
     259    std::vector<Node> deficit_nodes;
     260
     261    /// \brief Implementation of the \ref Dijkstra algorithm for
     262    /// finding augmenting shortest paths in the residual network.
     263    ResidualDijkstra dijkstra;
     264    /// \brief The map of predecessors edges.
     265    PredMap pred;
    323266
    324267  public :
     
    334277    /// \param _supply The supply values of the nodes (signed).
    335278    CapacityScaling( const Graph &_graph,
    336                      const LowerMap &_lower,
    337                      const CapacityMap &_capacity,
    338                      const CostMap &_cost,
    339                      const SupplyMap &_supply ) :
     279                     const LowerMap &_lower,
     280                     const CapacityMap &_capacity,
     281                     const CostMap &_cost,
     282                     const SupplyMap &_supply ) :
    340283      graph(_graph), lower(&_lower), capacity(_graph), cost(_cost),
    341284      supply(_graph), flow(_graph, 0), potential(_graph, 0),
    342       res_graph(_graph, capacity, flow),
    343       red_cost(res_graph, cost, potential), imbalance(_graph),
    344 #ifdef WITH_SCALING
    345       delta(0), delta_filter(res_graph, delta),
    346       dres_graph(res_graph, delta_filter),
    347       dijkstra(dres_graph, red_cost), pred(dres_graph),
    348       delta_deficit(imbalance, delta)
    349 #else //WITHOUT_CAPACITY_SCALING
    350       dijkstra(res_graph, red_cost), pred(res_graph),
    351       has_deficit(imbalance)
    352 #endif
     285      res_cap(_graph), excess(_graph), pred(_graph),
     286      dijkstra(graph, flow, res_cap, cost, excess, potential, pred)
    353287    {
    354288      // Removing nonzero lower bounds
    355289      capacity = subMap(_capacity, _lower);
     290      res_cap = capacity;
    356291      Supply sum = 0;
    357292      for (NodeIt n(graph); n != INVALID; ++n) {
    358         Supply s = _supply[n];
    359         for (InEdgeIt e(graph, n); e != INVALID; ++e)
    360           s += _lower[e];
    361         for (OutEdgeIt e(graph, n); e != INVALID; ++e)
    362           s -= _lower[e];
    363         supply[n] = s;
    364         sum += s;
     293        Supply s = _supply[n];
     294        for (InEdgeIt e(graph, n); e != INVALID; ++e)
     295          s += _lower[e];
     296        for (OutEdgeIt e(graph, n); e != INVALID; ++e)
     297          s -= _lower[e];
     298        supply[n] = s;
     299        sum += s;
    365300      }
    366301      valid_supply = sum == 0;
     
    376311    /// \param _supply The supply values of the nodes (signed).
    377312    CapacityScaling( const Graph &_graph,
    378                      const CapacityMap &_capacity,
    379                      const CostMap &_cost,
    380                      const SupplyMap &_supply ) :
     313                     const CapacityMap &_capacity,
     314                     const CostMap &_cost,
     315                     const SupplyMap &_supply ) :
    381316      graph(_graph), lower(NULL), capacity(_capacity), cost(_cost),
    382317      supply(_supply), flow(_graph, 0), potential(_graph, 0),
    383       res_graph(_graph, capacity, flow),
    384       red_cost(res_graph, cost, potential), imbalance(_graph),
    385 #ifdef WITH_SCALING
    386       delta(0), delta_filter(res_graph, delta),
    387       dres_graph(res_graph, delta_filter),
    388       dijkstra(dres_graph, red_cost), pred(dres_graph),
    389       delta_deficit(imbalance, delta)
    390 #else //WITHOUT_CAPACITY_SCALING
    391       dijkstra(res_graph, red_cost), pred(res_graph),
    392       has_deficit(imbalance)
    393 #endif
     318      res_cap(_capacity), excess(_graph), pred(_graph),
     319      dijkstra(graph, flow, res_cap, cost, excess, potential)
    394320    {
    395321      // Checking the sum of supply values
     
    413339    /// \c _t).
    414340    CapacityScaling( const Graph &_graph,
    415                      const LowerMap &_lower,
    416                      const CapacityMap &_capacity,
    417                      const CostMap &_cost,
    418                      Node _s, Node _t,
    419                      Supply _flow_value ) :
     341                     const LowerMap &_lower,
     342                     const CapacityMap &_capacity,
     343                     const CostMap &_cost,
     344                     Node _s, Node _t,
     345                     Supply _flow_value ) :
    420346      graph(_graph), lower(&_lower), capacity(_graph), cost(_cost),
    421347      supply(_graph), flow(_graph, 0), potential(_graph, 0),
    422       res_graph(_graph, capacity, flow),
    423       red_cost(res_graph, cost, potential), imbalance(_graph),
    424 #ifdef WITH_SCALING
    425       delta(0), delta_filter(res_graph, delta),
    426       dres_graph(res_graph, delta_filter),
    427       dijkstra(dres_graph, red_cost), pred(dres_graph),
    428       delta_deficit(imbalance, delta)
    429 #else //WITHOUT_CAPACITY_SCALING
    430       dijkstra(res_graph, red_cost), pred(res_graph),
    431       has_deficit(imbalance)
    432 #endif
     348      res_cap(_graph), excess(_graph), pred(_graph),
     349      dijkstra(graph, flow, res_cap, cost, excess, potential)
    433350    {
    434351      // Removing nonzero lower bounds
    435352      capacity = subMap(_capacity, _lower);
     353      res_cap = capacity;
    436354      for (NodeIt n(graph); n != INVALID; ++n) {
    437         Supply s = 0;
    438         if (n == _s) s =  _flow_value;
    439         if (n == _t) s = -_flow_value;
    440         for (InEdgeIt e(graph, n); e != INVALID; ++e)
    441           s += _lower[e];
    442         for (OutEdgeIt e(graph, n); e != INVALID; ++e)
    443           s -= _lower[e];
    444         supply[n] = s;
     355        Supply s = 0;
     356        if (n == _s) s =  _flow_value;
     357        if (n == _t) s = -_flow_value;
     358        for (InEdgeIt e(graph, n); e != INVALID; ++e)
     359          s += _lower[e];
     360        for (OutEdgeIt e(graph, n); e != INVALID; ++e)
     361          s -= _lower[e];
     362        supply[n] = s;
    445363      }
    446364      valid_supply = true;
     
    460378    /// \c _t).
    461379    CapacityScaling( const Graph &_graph,
    462                      const CapacityMap &_capacity,
    463                      const CostMap &_cost,
    464                      Node _s, Node _t,
    465                      Supply _flow_value ) :
     380                     const CapacityMap &_capacity,
     381                     const CostMap &_cost,
     382                     Node _s, Node _t,
     383                     Supply _flow_value ) :
    466384      graph(_graph), lower(NULL), capacity(_capacity), cost(_cost),
    467385      supply(_graph, 0), flow(_graph, 0), potential(_graph, 0),
    468       res_graph(_graph, capacity, flow),
    469       red_cost(res_graph, cost, potential), imbalance(_graph),
    470 #ifdef WITH_SCALING
    471       delta(0), delta_filter(res_graph, delta),
    472       dres_graph(res_graph, delta_filter),
    473       dijkstra(dres_graph, red_cost), pred(dres_graph),
    474       delta_deficit(imbalance, delta)
    475 #else //WITHOUT_CAPACITY_SCALING
    476       dijkstra(res_graph, red_cost), pred(res_graph),
    477       has_deficit(imbalance)
    478 #endif
     386      res_cap(_capacity), excess(_graph), pred(_graph),
     387      dijkstra(graph, flow, res_cap, cost, excess, potential)
    479388    {
    480389      supply[_s] =  _flow_value;
     
    512421      Cost c = 0;
    513422      for (EdgeIt e(graph); e != INVALID; ++e)
    514         c += flow[e] * cost[e];
     423        c += flow[e] * cost[e];
    515424      return c;
    516425    }
     
    520429    /// Runs the algorithm.
    521430    ///
     431    /// \param scaling_mode The scaling mode. In case of WITH_SCALING
     432    /// capacity scaling is enabled in the algorithm (this is the
     433    /// default value) otherwise it is disabled.
     434    /// If the maximum edge capacity and/or the amount of total supply
     435    /// is small, the algorithm could be faster without scaling.
     436    ///
    522437    /// \return \c true if a feasible flow can be found.
    523     bool run() {
    524       return init() && start();
     438    bool run(int scaling_mode = WITH_SCALING) {
     439      return init(scaling_mode) && start();
    525440    }
    526441
     
    528443
    529444    /// \brief Initializes the algorithm.
    530     bool init() {
     445    bool init(int scaling_mode) {
    531446      if (!valid_supply) return false;
    532       imbalance = supply;
    533 
    534       // Initalizing Dijkstra class
    535       updater.potentialMap(potential);
    536       dijkstra.distMap(updater).predMap(pred);
    537 
    538 #ifdef WITH_SCALING
     447      excess = supply;
     448
    539449      // Initilaizing delta value
    540       Supply max_sup = 0, max_dem = 0;
    541       for (NodeIt n(graph); n != INVALID; ++n) {
    542         if (supply[n] >  max_sup) max_sup =  supply[n];
    543         if (supply[n] < -max_dem) max_dem = -supply[n];
    544       }
    545       if (max_dem < max_sup) max_sup = max_dem;
    546       for ( delta = 1; SCALING_FACTOR * delta < max_sup;
    547             delta *= SCALING_FACTOR ) ;
    548 #endif
     450      if (scaling_mode == WITH_SCALING) {
     451        // With scaling
     452        Supply max_sup = 0, max_dem = 0;
     453        for (NodeIt n(graph); n != INVALID; ++n) {
     454          if ( supply[n] > max_sup) max_sup =  supply[n];
     455          if (-supply[n] > max_dem) max_dem = -supply[n];
     456        }
     457        if (max_dem < max_sup) max_sup = max_dem;
     458        phase_num = 0;
     459        for (delta = 1; 2 * delta <= max_sup; delta *= 2)
     460          ++phase_num;
     461      } else {
     462        // Without scaling
     463        delta = 1;
     464      }
    549465      return true;
    550466    }
    551467
    552 #ifdef WITH_SCALING
     468    /// \brief Executes the algorithm.
     469    bool start() {
     470      if (delta > 1)
     471        return startWithScaling();
     472      else
     473        return startWithoutScaling();
     474    }
     475
    553476    /// \brief Executes the capacity scaling version of the successive
    554477    /// shortest path algorithm.
    555     bool start() {
    556       typedef typename DeltaResGraph::EdgeIt DeltaResEdgeIt;
    557       typedef typename DeltaResGraph::Edge DeltaResEdge;
    558 #ifdef _DEBUG_ITER_
    559       int dijk_num = 0;
    560 #endif
    561 
     478    bool startWithScaling() {
    562479      // Processing capacity scaling phases
    563       ResNode s, t;
    564       for ( ; delta >= 1; delta = delta < SCALING_FACTOR && delta > 1 ?
    565                                   1 : delta / SCALING_FACTOR )
    566       {
    567         // Saturating edges not satisfying the optimality condition
    568         Capacity r;
    569         for (DeltaResEdgeIt e(dres_graph); e != INVALID; ++e) {
    570           if (red_cost[e] < 0) {
    571             res_graph.augment(e, r = res_graph.rescap(e));
    572             imbalance[dres_graph.source(e)] -= r;
    573             imbalance[dres_graph.target(e)] += r;
    574           }
    575         }
    576 
    577         // Finding excess nodes
    578         excess_nodes.clear();
    579         deficit_nodes.clear();
    580         for (ResNodeIt n(res_graph); n != INVALID; ++n) {
    581           if (imbalance[n] >=  delta) excess_nodes.push_back(n);
    582           if (imbalance[n] <= -delta) deficit_nodes.push_back(n);
    583         }
    584         next_node = 0;
    585 
    586         // Finding shortest paths
    587         while (next_node < excess_nodes.size()) {
    588           // Checking deficit nodes
    589           if (delta > 1) {
    590             bool delta_def = false;
    591             for (int i = 0; i < deficit_nodes.size(); ++i) {
    592               if (imbalance[deficit_nodes[i]] <= -delta) {
    593                 delta_def = true;
    594                 break;
    595               }
    596             }
    597             if (!delta_def) break;
    598           }
    599 
    600           // Running Dijkstra
    601           s = excess_nodes[next_node];
    602           updater.init();
    603           dijkstra.init();
    604           dijkstra.addSource(s);
    605 #ifdef _DEBUG_ITER_
    606           ++dijk_num;
    607 #endif
    608           if ((t = dijkstra.start(delta_deficit)) == INVALID) {
    609             if (delta > 1) {
    610               ++next_node;
    611               continue;
    612             }
    613             return false;
    614           }
    615 
    616           // Updating node potentials
    617           updater.update();
    618 
    619           // Augment along a shortest path from s to t
    620           Capacity d = imbalance[s] < -imbalance[t] ?
    621             imbalance[s] : -imbalance[t];
    622           ResNode u = t;
    623           ResEdge e;
    624           if (d > delta) {
    625             while ((e = pred[u]) != INVALID) {
    626               if (res_graph.rescap(e) < d) d = res_graph.rescap(e);
    627               u = dres_graph.source(e);
    628             }
    629           }
    630           u = t;
    631           while ((e = pred[u]) != INVALID) {
    632             res_graph.augment(e, d);
    633             u = dres_graph.source(e);
    634           }
    635           imbalance[s] -= d;
    636           imbalance[t] += d;
    637           if (imbalance[s] < delta) ++next_node;
    638         }
    639       }
    640 #ifdef _DEBUG_ITER_
    641       std::cout << "Capacity Scaling algorithm finished with running Dijkstra algorithm "
    642         << dijk_num << " times." << std::endl;
    643 #endif
     480      Node s, t;
     481      int phase_cnt = 0;
     482      int factor = 4;
     483      while (true) {
     484        // Saturating all edges not satisfying the optimality condition
     485        for (EdgeIt e(graph); e != INVALID; ++e) {
     486          Node u = graph.source(e), v = graph.target(e);
     487          Cost c = cost[e] - potential[u] + potential[v];
     488          if (c < 0 && res_cap[e] >= delta) {
     489            excess[u] -= res_cap[e];
     490            excess[v] += res_cap[e];
     491            flow[e] = capacity[e];
     492            res_cap[e] = 0;
     493          }
     494          else if (c > 0 && flow[e] >= delta) {
     495            excess[u] += flow[e];
     496            excess[v] -= flow[e];
     497            flow[e] = 0;
     498            res_cap[e] = capacity[e];
     499          }
     500        }
     501
     502        // Finding excess nodes and deficit nodes
     503        excess_nodes.clear();
     504        deficit_nodes.clear();
     505        for (NodeIt n(graph); n != INVALID; ++n) {
     506          if (excess[n] >=  delta) excess_nodes.push_back(n);
     507          if (excess[n] <= -delta) deficit_nodes.push_back(n);
     508        }
     509        next_node = 0;
     510
     511        // Finding augmenting shortest paths
     512        while (next_node < excess_nodes.size()) {
     513          // Checking deficit nodes
     514          if (delta > 1) {
     515            bool delta_deficit = false;
     516            for (int i = 0; i < deficit_nodes.size(); ++i) {
     517              if (excess[deficit_nodes[i]] <= -delta) {
     518                delta_deficit = true;
     519                break;
     520              }
     521            }
     522            if (!delta_deficit) break;
     523          }
     524
     525          // Running Dijkstra
     526          s = excess_nodes[next_node];
     527          if ((t = dijkstra.run(s, delta)) == INVALID) {
     528            if (delta > 1) {
     529              ++next_node;
     530              continue;
     531            }
     532            return false;
     533          }
     534
     535          // Augmenting along a shortest path from s to t.
     536          Capacity d = excess[s] < -excess[t] ? excess[s] : -excess[t];
     537          Node u = t;
     538          Edge e;
     539          if (d > delta) {
     540            while ((e = pred[u]) != INVALID) {
     541              Capacity rc;
     542              if (u == graph.target(e)) {
     543                rc = res_cap[e];
     544                u = graph.source(e);
     545              } else {
     546                rc = flow[e];
     547                u = graph.target(e);
     548              }
     549              if (rc < d) d = rc;
     550            }
     551          }
     552          u = t;
     553          while ((e = pred[u]) != INVALID) {
     554            if (u == graph.target(e)) {
     555              flow[e] += d;
     556              res_cap[e] -= d;
     557              u = graph.source(e);
     558            } else {
     559              flow[e] -= d;
     560              res_cap[e] += d;
     561              u = graph.target(e);
     562            }
     563          }
     564          excess[s] -= d;
     565          excess[t] += d;
     566
     567          if (excess[s] < delta) ++next_node;
     568        }
     569
     570        if (delta == 1) break;
     571        if (++phase_cnt > phase_num / 4) factor = 2;
     572        delta = delta <= factor ? 1 : delta / factor;
     573      }
    644574
    645575      // Handling nonzero lower bounds
    646576      if (lower) {
    647         for (EdgeIt e(graph); e != INVALID; ++e)
    648           flow[e] += (*lower)[e];
     577        for (EdgeIt e(graph); e != INVALID; ++e)
     578          flow[e] += (*lower)[e];
    649579      }
    650580      return true;
    651581    }
    652582
    653 #else //WITHOUT_CAPACITY_SCALING
    654583    /// \brief Executes the successive shortest path algorithm without
    655584    /// capacity scaling.
    656     bool start() {
     585    bool startWithoutScaling() {
    657586      // Finding excess nodes
    658       for (ResNodeIt n(res_graph); n != INVALID; ++n) {
    659         if (imbalance[n] > 0) excess_nodes.push_back(n);
     587      for (NodeIt n(graph); n != INVALID; ++n) {
     588        if (excess[n] > 0) excess_nodes.push_back(n);
    660589      }
    661590      if (excess_nodes.size() == 0) return true;
     
    663592
    664593      // Finding shortest paths
    665       ResNode s, t;
    666       while ( imbalance[excess_nodes[next_node]] > 0 ||
    667               ++next_node < excess_nodes.size() )
     594      Node s, t;
     595      while ( excess[excess_nodes[next_node]] > 0 ||
     596              ++next_node < excess_nodes.size() )
    668597      {
    669         // Running Dijkstra
    670         s = excess_nodes[next_node];
    671         updater.init();
    672         dijkstra.init();
    673         dijkstra.addSource(s);
    674         if ((t = dijkstra.start(has_deficit)) == INVALID)
    675           return false;
    676 
    677         // Updating node potentials
    678         updater.update();
    679 
    680         // Augmenting along a shortest path from s to t
    681         Capacity delta = imbalance[s] < -imbalance[t] ?
    682           imbalance[s] : -imbalance[t];
    683         ResNode u = t;
    684         ResEdge e;
    685         while ((e = pred[u]) != INVALID) {
    686           if (res_graph.rescap(e) < delta) delta = res_graph.rescap(e);
    687           u = res_graph.source(e);
    688         }
    689         u = t;
    690         while ((e = pred[u]) != INVALID) {
    691           res_graph.augment(e, delta);
    692           u = res_graph.source(e);
    693         }
    694         imbalance[s] -= delta;
    695         imbalance[t] += delta;
     598        // Running Dijkstra
     599        s = excess_nodes[next_node];
     600        if ((t = dijkstra.run(s, 1)) == INVALID)
     601          return false;
     602
     603        // Augmenting along a shortest path from s to t
     604        Capacity d = excess[s] < -excess[t] ? excess[s] : -excess[t];
     605        Node u = t;
     606        Edge e;
     607        while ((e = pred[u]) != INVALID) {
     608          Capacity rc;
     609          if (u == graph.target(e)) {
     610            rc = res_cap[e];
     611            u = graph.source(e);
     612          } else {
     613            rc = flow[e];
     614            u = graph.target(e);
     615          }
     616          if (rc < d) d = rc;
     617        }
     618        u = t;
     619        while ((e = pred[u]) != INVALID) {
     620          if (u == graph.target(e)) {
     621            flow[e] += d;
     622            res_cap[e] -= d;
     623            u = graph.source(e);
     624          } else {
     625            flow[e] -= d;
     626            res_cap[e] += d;
     627            u = graph.target(e);
     628          }
     629        }
     630        excess[s] -= d;
     631        excess[t] += d;
    696632      }
    697633
    698634      // Handling nonzero lower bounds
    699635      if (lower) {
    700         for (EdgeIt e(graph); e != INVALID; ++e)
    701           flow[e] += (*lower)[e];
     636        for (EdgeIt e(graph); e != INVALID; ++e)
     637          flow[e] += (*lower)[e];
    702638      }
    703639      return true;
    704640    }
    705 #endif
    706641
    707642  }; //class CapacityScaling
Note: See TracChangeset for help on using the changeset viewer.