Improvements in CapacityScaling.
authorkpeter
Mon, 18 Feb 2008 03:30:53 +0000
changeset 25747058c9690e7d
parent 2573 a9758ea1f01c
child 2575 e866e288cba6
Improvements in CapacityScaling.

Main changes:
- Use -potenital[] instead of potential[] to conform to the usual
terminology.
- Change the name of private members to start with "_".
- Change the name of function parameters not to start with "_".
- Remove unnecessary documentation for private members.
- Doc improvements.
lemon/capacity_scaling.h
     1.1 --- a/lemon/capacity_scaling.h	Mon Feb 18 03:30:12 2008 +0000
     1.2 +++ b/lemon/capacity_scaling.h	Mon Feb 18 03:30:53 2008 +0000
     1.3 @@ -22,52 +22,51 @@
     1.4  /// \ingroup min_cost_flow
     1.5  ///
     1.6  /// \file
     1.7 -/// \brief The capacity scaling algorithm for finding a minimum cost flow.
     1.8 +/// \brief Capacity scaling algorithm for finding a minimum cost flow.
     1.9 +
    1.10 +#include <vector>
    1.11  
    1.12  #include <lemon/graph_adaptor.h>
    1.13  #include <lemon/bin_heap.h>
    1.14 -#include <vector>
    1.15  
    1.16  namespace lemon {
    1.17  
    1.18    /// \addtogroup min_cost_flow
    1.19    /// @{
    1.20  
    1.21 -  /// \brief Implementation of the capacity scaling version of the
    1.22 -  /// successive shortest path algorithm for finding a minimum cost
    1.23 -  /// flow.
    1.24 +  /// \brief Implementation of the capacity scaling algorithm for
    1.25 +  /// finding a minimum cost flow.
    1.26    ///
    1.27    /// \ref CapacityScaling implements the capacity scaling version
    1.28    /// of the successive shortest path algorithm for finding a minimum
    1.29    /// cost flow.
    1.30    ///
    1.31 -  /// \param Graph The directed graph type the algorithm runs on.
    1.32 -  /// \param LowerMap The type of the lower bound map.
    1.33 -  /// \param CapacityMap The type of the capacity (upper bound) map.
    1.34 -  /// \param CostMap The type of the cost (length) map.
    1.35 -  /// \param SupplyMap The type of the supply map.
    1.36 +  /// \tparam Graph The directed graph type the algorithm runs on.
    1.37 +  /// \tparam LowerMap The type of the lower bound map.
    1.38 +  /// \tparam CapacityMap The type of the capacity (upper bound) map.
    1.39 +  /// \tparam CostMap The type of the cost (length) map.
    1.40 +  /// \tparam SupplyMap The type of the supply map.
    1.41    ///
    1.42    /// \warning
    1.43 -  /// - Edge capacities and costs should be non-negative integers.
    1.44 -  ///   However \c CostMap::Value should be signed type.
    1.45 -  /// - Supply values should be signed integers.
    1.46 -  /// - \c LowerMap::Value must be convertible to
    1.47 -  ///   \c CapacityMap::Value and \c CapacityMap::Value must be
    1.48 -  ///   convertible to \c SupplyMap::Value.
    1.49 +  /// - Edge capacities and costs should be \e non-negative \e integers.
    1.50 +  /// - Supply values should be \e signed \e integers.
    1.51 +  /// - \c LowerMap::Value must be convertible to \c CapacityMap::Value.
    1.52 +  /// - \c CapacityMap::Value and \c SupplyMap::Value must be
    1.53 +  ///   convertible to each other.
    1.54 +  /// - All value types must be convertible to \c CostMap::Value, which
    1.55 +  ///   must be signed type.
    1.56    ///
    1.57    /// \author Peter Kovacs
    1.58  
    1.59    template < typename Graph,
    1.60               typename LowerMap = typename Graph::template EdgeMap<int>,
    1.61 -             typename CapacityMap = LowerMap,
    1.62 +             typename CapacityMap = typename Graph::template EdgeMap<int>,
    1.63               typename CostMap = typename Graph::template EdgeMap<int>,
    1.64 -             typename SupplyMap = typename Graph::template NodeMap
    1.65 -                                  <typename CapacityMap::Value> >
    1.66 +             typename SupplyMap = typename Graph::template NodeMap<int> >
    1.67    class CapacityScaling
    1.68    {
    1.69      GRAPH_TYPEDEFS(typename Graph);
    1.70  
    1.71 -    typedef typename LowerMap::Value Lower;
    1.72      typedef typename CapacityMap::Value Capacity;
    1.73      typedef typename CostMap::Value Cost;
    1.74      typedef typename SupplyMap::Value Supply;
    1.75 @@ -77,23 +76,21 @@
    1.76  
    1.77    public:
    1.78  
    1.79 -    /// Type to enable or disable capacity scaling.
    1.80 -    enum ScalingEnum {
    1.81 -      WITH_SCALING = 0,
    1.82 -      WITHOUT_SCALING = -1
    1.83 -    };
    1.84 -
    1.85      /// The type of the flow map.
    1.86      typedef typename Graph::template EdgeMap<Capacity> FlowMap;
    1.87      /// The type of the potential map.
    1.88      typedef typename Graph::template NodeMap<Cost> PotentialMap;
    1.89  
    1.90 -  protected:
    1.91 +  private:
    1.92  
    1.93      /// \brief Special implementation of the \ref Dijkstra algorithm
    1.94 -    /// for finding shortest paths in the residual network of the graph
    1.95 -    /// with respect to the reduced edge costs and modifying the
    1.96 -    /// node potentials according to the distance of the nodes.
    1.97 +    /// for finding shortest paths in the residual network.
    1.98 +    ///
    1.99 +    /// \ref ResidualDijkstra is a special implementation of the
   1.100 +    /// \ref Dijkstra algorithm for finding shortest paths in the
   1.101 +    /// residual network of the graph with respect to the reduced edge
   1.102 +    /// costs and modifying the node potentials according to the
   1.103 +    /// distance of the nodes.
   1.104      class ResidualDijkstra
   1.105      {
   1.106        typedef typename Graph::template NodeMap<Cost> CostNodeMap;
   1.107 @@ -102,75 +99,70 @@
   1.108        typedef typename Graph::template NodeMap<int> HeapCrossRef;
   1.109        typedef BinHeap<Cost, HeapCrossRef> Heap;
   1.110  
   1.111 -    protected:
   1.112 +    private:
   1.113  
   1.114 -      /// The directed graph the algorithm runs on.
   1.115 -      const Graph &graph;
   1.116 +      // The directed graph the algorithm runs on
   1.117 +      const Graph &_graph;
   1.118  
   1.119 -      /// The flow map.
   1.120 -      const FlowMap &flow;
   1.121 -      /// The residual capacity map.
   1.122 -      const CapacityEdgeMap &res_cap;
   1.123 -      /// The cost map.
   1.124 -      const CostMap &cost;
   1.125 -      /// The excess map.
   1.126 -      const SupplyNodeMap &excess;
   1.127 +      // The main maps
   1.128 +      const FlowMap &_flow;
   1.129 +      const CapacityEdgeMap &_res_cap;
   1.130 +      const CostMap &_cost;
   1.131 +      const SupplyNodeMap &_excess;
   1.132 +      PotentialMap &_potential;
   1.133  
   1.134 -      /// The potential map.
   1.135 -      PotentialMap &potential;
   1.136 -
   1.137 -      /// The distance map.
   1.138 -      CostNodeMap dist;
   1.139 -      /// The map of predecessors edges.
   1.140 -      PredMap &pred;
   1.141 -      /// The processed (i.e. permanently labeled) nodes.
   1.142 -      std::vector<Node> proc_nodes;
   1.143 +      // The distance map
   1.144 +      CostNodeMap _dist;
   1.145 +      // The pred edge map
   1.146 +      PredMap &_pred;
   1.147 +      // The processed (i.e. permanently labeled) nodes
   1.148 +      std::vector<Node> _proc_nodes;
   1.149  
   1.150      public:
   1.151  
   1.152        /// The constructor of the class.
   1.153 -      ResidualDijkstra( const Graph &_graph,
   1.154 -                        const FlowMap &_flow,
   1.155 -                        const CapacityEdgeMap &_res_cap,
   1.156 -                        const CostMap &_cost,
   1.157 -                        const SupplyMap &_excess,
   1.158 -                        PotentialMap &_potential,
   1.159 -                        PredMap &_pred ) :
   1.160 -        graph(_graph), flow(_flow), res_cap(_res_cap), cost(_cost),
   1.161 -        excess(_excess), potential(_potential), dist(_graph),
   1.162 -        pred(_pred)
   1.163 +      ResidualDijkstra( const Graph &graph,
   1.164 +                        const FlowMap &flow,
   1.165 +                        const CapacityEdgeMap &res_cap,
   1.166 +                        const CostMap &cost,
   1.167 +                        const SupplyMap &excess,
   1.168 +                        PotentialMap &potential,
   1.169 +                        PredMap &pred ) :
   1.170 +        _graph(graph), _flow(flow), _res_cap(res_cap), _cost(cost),
   1.171 +        _excess(excess), _potential(potential), _dist(graph),
   1.172 +        _pred(pred)
   1.173        {}
   1.174  
   1.175        /// Runs the algorithm from the given source node.
   1.176        Node run(Node s, Capacity delta) {
   1.177 -        HeapCrossRef heap_cross_ref(graph, Heap::PRE_HEAP);
   1.178 +        HeapCrossRef heap_cross_ref(_graph, Heap::PRE_HEAP);
   1.179          Heap heap(heap_cross_ref);
   1.180          heap.push(s, 0);
   1.181 -        pred[s] = INVALID;
   1.182 -        proc_nodes.clear();
   1.183 +        _pred[s] = INVALID;
   1.184 +        _proc_nodes.clear();
   1.185  
   1.186          // Processing nodes
   1.187 -        while (!heap.empty() && excess[heap.top()] > -delta) {
   1.188 +        while (!heap.empty() && _excess[heap.top()] > -delta) {
   1.189            Node u = heap.top(), v;
   1.190 -          Cost d = heap.prio() - potential[u], nd;
   1.191 -          dist[u] = heap.prio();
   1.192 +          Cost d = heap.prio() + _potential[u], nd;
   1.193 +          _dist[u] = heap.prio();
   1.194            heap.pop();
   1.195 -          proc_nodes.push_back(u);
   1.196 +          _proc_nodes.push_back(u);
   1.197  
   1.198            // Traversing outgoing edges
   1.199 -          for (OutEdgeIt e(graph, u); e != INVALID; ++e) {
   1.200 -            if (res_cap[e] >= delta) {
   1.201 -              v = graph.target(e);
   1.202 +          for (OutEdgeIt e(_graph, u); e != INVALID; ++e) {
   1.203 +            if (_res_cap[e] >= delta) {
   1.204 +              v = _graph.target(e);
   1.205                switch(heap.state(v)) {
   1.206                case Heap::PRE_HEAP:
   1.207 -                heap.push(v, d + cost[e] + potential[v]);
   1.208 -                pred[v] = e;
   1.209 +                heap.push(v, d + _cost[e] - _potential[v]);
   1.210 +                _pred[v] = e;
   1.211                  break;
   1.212                case Heap::IN_HEAP:
   1.213 -                nd = d + cost[e] + potential[v];
   1.214 +                nd = d + _cost[e] - _potential[v];
   1.215                  if (nd < heap[v]) {
   1.216                    heap.decrease(v, nd);
   1.217 -                  pred[v] = e;
   1.218 +                  _pred[v] = e;
   1.219                  }
   1.220                  break;
   1.221                case Heap::POST_HEAP:
   1.222 @@ -180,19 +172,19 @@
   1.223            }
   1.224  
   1.225            // Traversing incoming edges
   1.226 -          for (InEdgeIt e(graph, u); e != INVALID; ++e) {
   1.227 -            if (flow[e] >= delta) {
   1.228 -              v = graph.source(e);
   1.229 +          for (InEdgeIt e(_graph, u); e != INVALID; ++e) {
   1.230 +            if (_flow[e] >= delta) {
   1.231 +              v = _graph.source(e);
   1.232                switch(heap.state(v)) {
   1.233                case Heap::PRE_HEAP:
   1.234 -                heap.push(v, d - cost[e] + potential[v]);
   1.235 -                pred[v] = e;
   1.236 +                heap.push(v, d - _cost[e] - _potential[v]);
   1.237 +                _pred[v] = e;
   1.238                  break;
   1.239                case Heap::IN_HEAP:
   1.240 -                nd = d - cost[e] + potential[v];
   1.241 +                nd = d - _cost[e] - _potential[v];
   1.242                  if (nd < heap[v]) {
   1.243                    heap.decrease(v, nd);
   1.244 -                  pred[v] = e;
   1.245 +                  _pred[v] = e;
   1.246                  }
   1.247                  break;
   1.248                case Heap::POST_HEAP:
   1.249 @@ -205,55 +197,53 @@
   1.250  
   1.251          // Updating potentials of processed nodes
   1.252          Node t = heap.top();
   1.253 -        Cost dt = heap.prio();
   1.254 -        for (int i = 0; i < proc_nodes.size(); ++i)
   1.255 -          potential[proc_nodes[i]] -= dist[proc_nodes[i]] - dt;
   1.256 +        Cost t_dist = heap.prio();
   1.257 +        for (int i = 0; i < int(_proc_nodes.size()); ++i)
   1.258 +          _potential[_proc_nodes[i]] += _dist[_proc_nodes[i]] - t_dist;
   1.259  
   1.260          return t;
   1.261        }
   1.262  
   1.263      }; //class ResidualDijkstra
   1.264  
   1.265 -  protected:
   1.266 +  private:
   1.267  
   1.268 -    /// The directed graph the algorithm runs on.
   1.269 -    const Graph &graph;
   1.270 -    /// The original lower bound map.
   1.271 -    const LowerMap *lower;
   1.272 -    /// The modified capacity map.
   1.273 -    CapacityEdgeMap capacity;
   1.274 -    /// The cost map.
   1.275 -    const CostMap &cost;
   1.276 -    /// The modified supply map.
   1.277 -    SupplyNodeMap supply;
   1.278 -    bool valid_supply;
   1.279 +    // The directed graph the algorithm runs on
   1.280 +    const Graph &_graph;
   1.281 +    // The original lower bound map
   1.282 +    const LowerMap *_lower;
   1.283 +    // The modified capacity map
   1.284 +    CapacityEdgeMap _capacity;
   1.285 +    // The original cost map
   1.286 +    const CostMap &_cost;
   1.287 +    // The modified supply map
   1.288 +    SupplyNodeMap _supply;
   1.289 +    bool _valid_supply;
   1.290  
   1.291 -    /// The edge map of the current flow.
   1.292 -    FlowMap flow;
   1.293 -    /// The potential node map.
   1.294 -    PotentialMap potential;
   1.295 +    // Edge map of the current flow
   1.296 +    FlowMap _flow;
   1.297 +    // Node map of the current potentials
   1.298 +    PotentialMap _potential;
   1.299  
   1.300 -    /// The residual capacity map.
   1.301 -    CapacityEdgeMap res_cap;
   1.302 -    /// The excess map.
   1.303 -    SupplyNodeMap excess;
   1.304 -    /// The excess nodes (i.e. the nodes with positive excess).
   1.305 -    std::vector<Node> excess_nodes;
   1.306 -    /// The deficit nodes (i.e. the nodes with negative excess).
   1.307 -    std::vector<Node> deficit_nodes;
   1.308 +    // The residual capacity map
   1.309 +    CapacityEdgeMap _res_cap;
   1.310 +    // The excess map
   1.311 +    SupplyNodeMap _excess;
   1.312 +    // The excess nodes (i.e. nodes with positive excess)
   1.313 +    std::vector<Node> _excess_nodes;
   1.314 +    // The deficit nodes (i.e. nodes with negative excess)
   1.315 +    std::vector<Node> _deficit_nodes;
   1.316  
   1.317 -    /// The scaling status (enabled or disabled).
   1.318 -    ScalingEnum scaling;
   1.319 -    /// The \c delta parameter used for capacity scaling.
   1.320 -    Capacity delta;
   1.321 -    /// The maximum number of phases.
   1.322 -    int phase_num;
   1.323 +    // The delta parameter used for capacity scaling
   1.324 +    Capacity _delta;
   1.325 +    // The maximum number of phases
   1.326 +    int _phase_num;
   1.327  
   1.328 -    /// \brief Implementation of the \ref Dijkstra algorithm for
   1.329 -    /// finding augmenting shortest paths in the residual network.
   1.330 -    ResidualDijkstra dijkstra;
   1.331 -    /// The map of predecessors edges.
   1.332 -    PredMap pred;
   1.333 +    // The pred edge map
   1.334 +    PredMap _pred;
   1.335 +    // Implementation of the Dijkstra algorithm for finding augmenting
   1.336 +    // shortest paths in the residual network
   1.337 +    ResidualDijkstra _dijkstra;
   1.338  
   1.339    public :
   1.340  
   1.341 @@ -261,159 +251,158 @@
   1.342      ///
   1.343      /// General constructor of the class (with lower bounds).
   1.344      ///
   1.345 -    /// \param _graph The directed graph the algorithm runs on.
   1.346 -    /// \param _lower The lower bounds of the edges.
   1.347 -    /// \param _capacity The capacities (upper bounds) of the edges.
   1.348 -    /// \param _cost The cost (length) values of the edges.
   1.349 -    /// \param _supply The supply values of the nodes (signed).
   1.350 -    CapacityScaling( const Graph &_graph,
   1.351 -                     const LowerMap &_lower,
   1.352 -                     const CapacityMap &_capacity,
   1.353 -                     const CostMap &_cost,
   1.354 -                     const SupplyMap &_supply ) :
   1.355 -      graph(_graph), lower(&_lower), capacity(_graph), cost(_cost),
   1.356 -      supply(_graph), flow(_graph, 0), potential(_graph, 0),
   1.357 -      res_cap(_graph), excess(_graph), pred(_graph),
   1.358 -      dijkstra(graph, flow, res_cap, cost, excess, potential, pred)
   1.359 +    /// \param graph The directed graph the algorithm runs on.
   1.360 +    /// \param lower The lower bounds of the edges.
   1.361 +    /// \param capacity The capacities (upper bounds) of the edges.
   1.362 +    /// \param cost The cost (length) values of the edges.
   1.363 +    /// \param supply The supply values of the nodes (signed).
   1.364 +    CapacityScaling( const Graph &graph,
   1.365 +                     const LowerMap &lower,
   1.366 +                     const CapacityMap &capacity,
   1.367 +                     const CostMap &cost,
   1.368 +                     const SupplyMap &supply ) :
   1.369 +      _graph(graph), _lower(&lower), _capacity(graph), _cost(cost),
   1.370 +      _supply(graph), _flow(graph, 0), _potential(graph, 0),
   1.371 +      _res_cap(graph), _excess(graph), _pred(graph),
   1.372 +      _dijkstra(_graph, _flow, _res_cap, _cost, _excess, _potential, _pred)
   1.373      {
   1.374        // Removing non-zero lower bounds
   1.375 -      capacity = subMap(_capacity, _lower);
   1.376 -      res_cap = capacity;
   1.377 +      _capacity = subMap(capacity, lower);
   1.378 +      _res_cap = _capacity;
   1.379        Supply sum = 0;
   1.380 -      for (NodeIt n(graph); n != INVALID; ++n) {
   1.381 -        Supply s = _supply[n];
   1.382 -        for (InEdgeIt e(graph, n); e != INVALID; ++e)
   1.383 -          s += _lower[e];
   1.384 -        for (OutEdgeIt e(graph, n); e != INVALID; ++e)
   1.385 -          s -= _lower[e];
   1.386 -        supply[n] = s;
   1.387 +      for (NodeIt n(_graph); n != INVALID; ++n) {
   1.388 +        Supply s = supply[n];
   1.389 +        for (InEdgeIt e(_graph, n); e != INVALID; ++e)
   1.390 +          s += lower[e];
   1.391 +        for (OutEdgeIt e(_graph, n); e != INVALID; ++e)
   1.392 +          s -= lower[e];
   1.393 +        _supply[n] = s;
   1.394          sum += s;
   1.395        }
   1.396 -      valid_supply = sum == 0;
   1.397 +      _valid_supply = sum == 0;
   1.398      }
   1.399  
   1.400      /// \brief General constructor of the class (without lower bounds).
   1.401      ///
   1.402      /// General constructor of the class (without lower bounds).
   1.403      ///
   1.404 -    /// \param _graph The directed graph the algorithm runs on.
   1.405 -    /// \param _capacity The capacities (upper bounds) of the edges.
   1.406 -    /// \param _cost The cost (length) values of the edges.
   1.407 -    /// \param _supply The supply values of the nodes (signed).
   1.408 -    CapacityScaling( const Graph &_graph,
   1.409 -                     const CapacityMap &_capacity,
   1.410 -                     const CostMap &_cost,
   1.411 -                     const SupplyMap &_supply ) :
   1.412 -      graph(_graph), lower(NULL), capacity(_capacity), cost(_cost),
   1.413 -      supply(_supply), flow(_graph, 0), potential(_graph, 0),
   1.414 -      res_cap(_capacity), excess(_graph), pred(_graph),
   1.415 -      dijkstra(graph, flow, res_cap, cost, excess, potential)
   1.416 +    /// \param graph The directed graph the algorithm runs on.
   1.417 +    /// \param capacity The capacities (upper bounds) of the edges.
   1.418 +    /// \param cost The cost (length) values of the edges.
   1.419 +    /// \param supply The supply values of the nodes (signed).
   1.420 +    CapacityScaling( const Graph &graph,
   1.421 +                     const CapacityMap &capacity,
   1.422 +                     const CostMap &cost,
   1.423 +                     const SupplyMap &supply ) :
   1.424 +      _graph(graph), _lower(NULL), _capacity(capacity), _cost(cost),
   1.425 +      _supply(supply), _flow(graph, 0), _potential(graph, 0),
   1.426 +      _res_cap(capacity), _excess(graph), _pred(graph),
   1.427 +      _dijkstra(_graph, _flow, _res_cap, _cost, _excess, _potential, _pred)
   1.428      {
   1.429        // Checking the sum of supply values
   1.430        Supply sum = 0;
   1.431 -      for (NodeIt n(graph); n != INVALID; ++n) sum += supply[n];
   1.432 -      valid_supply = sum == 0;
   1.433 +      for (NodeIt n(_graph); n != INVALID; ++n) sum += _supply[n];
   1.434 +      _valid_supply = sum == 0;
   1.435      }
   1.436  
   1.437      /// \brief Simple constructor of the class (with lower bounds).
   1.438      ///
   1.439      /// Simple constructor of the class (with lower bounds).
   1.440      ///
   1.441 -    /// \param _graph The directed graph the algorithm runs on.
   1.442 -    /// \param _lower The lower bounds of the edges.
   1.443 -    /// \param _capacity The capacities (upper bounds) of the edges.
   1.444 -    /// \param _cost The cost (length) values of the edges.
   1.445 -    /// \param _s The source node.
   1.446 -    /// \param _t The target node.
   1.447 -    /// \param _flow_value The required amount of flow from node \c _s
   1.448 -    /// to node \c _t (i.e. the supply of \c _s and the demand of \c _t).
   1.449 -    CapacityScaling( const Graph &_graph,
   1.450 -                     const LowerMap &_lower,
   1.451 -                     const CapacityMap &_capacity,
   1.452 -                     const CostMap &_cost,
   1.453 -                     Node _s, Node _t,
   1.454 -                     Supply _flow_value ) :
   1.455 -      graph(_graph), lower(&_lower), capacity(_graph), cost(_cost),
   1.456 -      supply(_graph), flow(_graph, 0), potential(_graph, 0),
   1.457 -      res_cap(_graph), excess(_graph), pred(_graph),
   1.458 -      dijkstra(graph, flow, res_cap, cost, excess, potential)
   1.459 +    /// \param graph The directed graph the algorithm runs on.
   1.460 +    /// \param lower The lower bounds of the edges.
   1.461 +    /// \param capacity The capacities (upper bounds) of the edges.
   1.462 +    /// \param cost The cost (length) values of the edges.
   1.463 +    /// \param s The source node.
   1.464 +    /// \param t The target node.
   1.465 +    /// \param flow_value The required amount of flow from node \c s
   1.466 +    /// to node \c t (i.e. the supply of \c s and the demand of \c t).
   1.467 +    CapacityScaling( const Graph &graph,
   1.468 +                     const LowerMap &lower,
   1.469 +                     const CapacityMap &capacity,
   1.470 +                     const CostMap &cost,
   1.471 +                     Node s, Node t,
   1.472 +                     Supply flow_value ) :
   1.473 +      _graph(graph), _lower(&lower), _capacity(graph), _cost(cost),
   1.474 +      _supply(graph), _flow(graph, 0), _potential(graph, 0),
   1.475 +      _res_cap(graph), _excess(graph), _pred(graph),
   1.476 +      _dijkstra(_graph, _flow, _res_cap, _cost, _excess, _potential, _pred)
   1.477      {
   1.478        // Removing non-zero lower bounds
   1.479 -      capacity = subMap(_capacity, _lower);
   1.480 -      res_cap = capacity;
   1.481 -      for (NodeIt n(graph); n != INVALID; ++n) {
   1.482 -        Supply s = 0;
   1.483 -        if (n == _s) s =  _flow_value;
   1.484 -        if (n == _t) s = -_flow_value;
   1.485 -        for (InEdgeIt e(graph, n); e != INVALID; ++e)
   1.486 -          s += _lower[e];
   1.487 -        for (OutEdgeIt e(graph, n); e != INVALID; ++e)
   1.488 -          s -= _lower[e];
   1.489 -        supply[n] = s;
   1.490 +      _capacity = subMap(capacity, lower);
   1.491 +      _res_cap = _capacity;
   1.492 +      for (NodeIt n(_graph); n != INVALID; ++n) {
   1.493 +        Supply sum = 0;
   1.494 +        if (n == s) sum =  flow_value;
   1.495 +        if (n == t) sum = -flow_value;
   1.496 +        for (InEdgeIt e(_graph, n); e != INVALID; ++e)
   1.497 +          sum += lower[e];
   1.498 +        for (OutEdgeIt e(_graph, n); e != INVALID; ++e)
   1.499 +          sum -= lower[e];
   1.500 +        _supply[n] = sum;
   1.501        }
   1.502 -      valid_supply = true;
   1.503 +      _valid_supply = true;
   1.504      }
   1.505  
   1.506      /// \brief Simple constructor of the class (without lower bounds).
   1.507      ///
   1.508      /// Simple constructor of the class (without lower bounds).
   1.509      ///
   1.510 -    /// \param _graph The directed graph the algorithm runs on.
   1.511 -    /// \param _capacity The capacities (upper bounds) of the edges.
   1.512 -    /// \param _cost The cost (length) values of the edges.
   1.513 -    /// \param _s The source node.
   1.514 -    /// \param _t The target node.
   1.515 -    /// \param _flow_value The required amount of flow from node \c _s
   1.516 -    /// to node \c _t (i.e. the supply of \c _s and the demand of \c _t).
   1.517 -    CapacityScaling( const Graph &_graph,
   1.518 -                     const CapacityMap &_capacity,
   1.519 -                     const CostMap &_cost,
   1.520 -                     Node _s, Node _t,
   1.521 -                     Supply _flow_value ) :
   1.522 -      graph(_graph), lower(NULL), capacity(_capacity), cost(_cost),
   1.523 -      supply(_graph, 0), flow(_graph, 0), potential(_graph, 0),
   1.524 -      res_cap(_capacity), excess(_graph), pred(_graph),
   1.525 -      dijkstra(graph, flow, res_cap, cost, excess, potential)
   1.526 +    /// \param graph The directed graph the algorithm runs on.
   1.527 +    /// \param capacity The capacities (upper bounds) of the edges.
   1.528 +    /// \param cost The cost (length) values of the edges.
   1.529 +    /// \param s The source node.
   1.530 +    /// \param t The target node.
   1.531 +    /// \param flow_value The required amount of flow from node \c s
   1.532 +    /// to node \c t (i.e. the supply of \c s and the demand of \c t).
   1.533 +    CapacityScaling( const Graph &graph,
   1.534 +                     const CapacityMap &capacity,
   1.535 +                     const CostMap &cost,
   1.536 +                     Node s, Node t,
   1.537 +                     Supply flow_value ) :
   1.538 +      _graph(graph), _lower(NULL), _capacity(capacity), _cost(cost),
   1.539 +      _supply(graph, 0), _flow(graph, 0), _potential(graph, 0),
   1.540 +      _res_cap(capacity), _excess(graph), _pred(graph),
   1.541 +      _dijkstra(_graph, _flow, _res_cap, _cost, _excess, _potential, _pred)
   1.542      {
   1.543 -      supply[_s] =  _flow_value;
   1.544 -      supply[_t] = -_flow_value;
   1.545 -      valid_supply = true;
   1.546 +      _supply[s] =  flow_value;
   1.547 +      _supply[t] = -flow_value;
   1.548 +      _valid_supply = true;
   1.549      }
   1.550  
   1.551      /// \brief Runs the algorithm.
   1.552      ///
   1.553      /// Runs the algorithm.
   1.554      ///
   1.555 -    /// \param scaling_mode The scaling mode. In case of WITH_SCALING
   1.556 -    /// capacity scaling is enabled in the algorithm (this is the
   1.557 -    /// default) otherwise it is disabled.
   1.558 +    /// \param scaling Enable or disable capacity scaling.
   1.559      /// If the maximum edge capacity and/or the amount of total supply
   1.560 -    /// is small, the algorithm could be slightly faster without
   1.561 +    /// is rather small, the algorithm could be slightly faster without
   1.562      /// scaling.
   1.563      ///
   1.564      /// \return \c true if a feasible flow can be found.
   1.565 -    bool run(int scaling_mode = WITH_SCALING) {
   1.566 -      return init(scaling_mode) && start();
   1.567 +    bool run(bool scaling = true) {
   1.568 +      return init(scaling) && start();
   1.569      }
   1.570  
   1.571 -    /// \brief Returns a const reference to the flow map.
   1.572 +    /// \brief Returns a const reference to the edge map storing the
   1.573 +    /// found flow.
   1.574      ///
   1.575 -    /// Returns a const reference to the flow map.
   1.576 +    /// Returns a const reference to the edge map storing the found flow.
   1.577      ///
   1.578      /// \pre \ref run() must be called before using this function.
   1.579      const FlowMap& flowMap() const {
   1.580 -      return flow;
   1.581 +      return _flow;
   1.582      }
   1.583  
   1.584 -    /// \brief Returns a const reference to the potential map (the dual
   1.585 -    /// solution).
   1.586 +    /// \brief Returns a const reference to the node map storing the
   1.587 +    /// found potentials (the dual solution).
   1.588      ///
   1.589 -    /// Returns a const reference to the potential map (the dual
   1.590 -    /// solution).
   1.591 +    /// Returns a const reference to the node map storing the found
   1.592 +    /// potentials (the dual solution).
   1.593      ///
   1.594      /// \pre \ref run() must be called before using this function.
   1.595      const PotentialMap& potentialMap() const {
   1.596 -      return potential;
   1.597 +      return _potential;
   1.598      }
   1.599  
   1.600      /// \brief Returns the total cost of the found flow.
   1.601 @@ -424,47 +413,45 @@
   1.602      /// \pre \ref run() must be called before using this function.
   1.603      Cost totalCost() const {
   1.604        Cost c = 0;
   1.605 -      for (EdgeIt e(graph); e != INVALID; ++e)
   1.606 -        c += flow[e] * cost[e];
   1.607 +      for (EdgeIt e(_graph); e != INVALID; ++e)
   1.608 +        c += _flow[e] * _cost[e];
   1.609        return c;
   1.610      }
   1.611  
   1.612 -  protected:
   1.613 +  private:
   1.614  
   1.615      /// Initializes the algorithm.
   1.616 -    bool init(int scaling_mode) {
   1.617 -      if (!valid_supply) return false;
   1.618 -      excess = supply;
   1.619 +    bool init(bool scaling) {
   1.620 +      if (!_valid_supply) return false;
   1.621 +      _excess = _supply;
   1.622  
   1.623        // Initilaizing delta value
   1.624 -      if (scaling_mode == WITH_SCALING) {
   1.625 +      if (scaling) {
   1.626          // With scaling
   1.627          Supply max_sup = 0, max_dem = 0;
   1.628 -        for (NodeIt n(graph); n != INVALID; ++n) {
   1.629 -          if ( supply[n] > max_sup) max_sup =  supply[n];
   1.630 -          if (-supply[n] > max_dem) max_dem = -supply[n];
   1.631 +        for (NodeIt n(_graph); n != INVALID; ++n) {
   1.632 +          if ( _supply[n] > max_sup) max_sup =  _supply[n];
   1.633 +          if (-_supply[n] > max_dem) max_dem = -_supply[n];
   1.634          }
   1.635          if (max_dem < max_sup) max_sup = max_dem;
   1.636 -        phase_num = 0;
   1.637 -        for (delta = 1; 2 * delta <= max_sup; delta *= 2)
   1.638 -          ++phase_num;
   1.639 +        _phase_num = 0;
   1.640 +        for (_delta = 1; 2 * _delta <= max_sup; _delta *= 2)
   1.641 +          ++_phase_num;
   1.642        } else {
   1.643          // Without scaling
   1.644 -        delta = 1;
   1.645 +        _delta = 1;
   1.646        }
   1.647        return true;
   1.648      }
   1.649  
   1.650 -    /// Executes the algorithm.
   1.651      bool start() {
   1.652 -      if (delta > 1)
   1.653 +      if (_delta > 1)
   1.654          return startWithScaling();
   1.655        else
   1.656          return startWithoutScaling();
   1.657      }
   1.658  
   1.659 -    /// \brief Executes the capacity scaling version of the successive
   1.660 -    /// shortest path algorithm.
   1.661 +    /// Executes the capacity scaling algorithm.
   1.662      bool startWithScaling() {
   1.663        // Processing capacity scaling phases
   1.664        Node s, t;
   1.665 @@ -472,39 +459,39 @@
   1.666        int factor = 4;
   1.667        while (true) {
   1.668          // Saturating all edges not satisfying the optimality condition
   1.669 -        for (EdgeIt e(graph); e != INVALID; ++e) {
   1.670 -          Node u = graph.source(e), v = graph.target(e);
   1.671 -          Cost c = cost[e] - potential[u] + potential[v];
   1.672 -          if (c < 0 && res_cap[e] >= delta) {
   1.673 -            excess[u] -= res_cap[e];
   1.674 -            excess[v] += res_cap[e];
   1.675 -            flow[e] = capacity[e];
   1.676 -            res_cap[e] = 0;
   1.677 +        for (EdgeIt e(_graph); e != INVALID; ++e) {
   1.678 +          Node u = _graph.source(e), v = _graph.target(e);
   1.679 +          Cost c = _cost[e] + _potential[u] - _potential[v];
   1.680 +          if (c < 0 && _res_cap[e] >= _delta) {
   1.681 +            _excess[u] -= _res_cap[e];
   1.682 +            _excess[v] += _res_cap[e];
   1.683 +            _flow[e] = _capacity[e];
   1.684 +            _res_cap[e] = 0;
   1.685            }
   1.686 -          else if (c > 0 && flow[e] >= delta) {
   1.687 -            excess[u] += flow[e];
   1.688 -            excess[v] -= flow[e];
   1.689 -            flow[e] = 0;
   1.690 -            res_cap[e] = capacity[e];
   1.691 +          else if (c > 0 && _flow[e] >= _delta) {
   1.692 +            _excess[u] += _flow[e];
   1.693 +            _excess[v] -= _flow[e];
   1.694 +            _flow[e] = 0;
   1.695 +            _res_cap[e] = _capacity[e];
   1.696            }
   1.697          }
   1.698  
   1.699          // Finding excess nodes and deficit nodes
   1.700 -        excess_nodes.clear();
   1.701 -        deficit_nodes.clear();
   1.702 -        for (NodeIt n(graph); n != INVALID; ++n) {
   1.703 -          if (excess[n] >=  delta) excess_nodes.push_back(n);
   1.704 -          if (excess[n] <= -delta) deficit_nodes.push_back(n);
   1.705 +        _excess_nodes.clear();
   1.706 +        _deficit_nodes.clear();
   1.707 +        for (NodeIt n(_graph); n != INVALID; ++n) {
   1.708 +          if (_excess[n] >=  _delta) _excess_nodes.push_back(n);
   1.709 +          if (_excess[n] <= -_delta) _deficit_nodes.push_back(n);
   1.710          }
   1.711          int next_node = 0;
   1.712  
   1.713          // Finding augmenting shortest paths
   1.714 -        while (next_node < excess_nodes.size()) {
   1.715 +        while (next_node < int(_excess_nodes.size())) {
   1.716            // Checking deficit nodes
   1.717 -          if (delta > 1) {
   1.718 +          if (_delta > 1) {
   1.719              bool delta_deficit = false;
   1.720 -            for (int i = 0; i < deficit_nodes.size(); ++i) {
   1.721 -              if (excess[deficit_nodes[i]] <= -delta) {
   1.722 +            for (int i = 0; i < int(_deficit_nodes.size()); ++i) {
   1.723 +              if (_excess[_deficit_nodes[i]] <= -_delta) {
   1.724                  delta_deficit = true;
   1.725                  break;
   1.726                }
   1.727 @@ -513,9 +500,9 @@
   1.728            }
   1.729  
   1.730            // Running Dijkstra
   1.731 -          s = excess_nodes[next_node];
   1.732 -          if ((t = dijkstra.run(s, delta)) == INVALID) {
   1.733 -            if (delta > 1) {
   1.734 +          s = _excess_nodes[next_node];
   1.735 +          if ((t = _dijkstra.run(s, _delta)) == INVALID) {
   1.736 +            if (_delta > 1) {
   1.737                ++next_node;
   1.738                continue;
   1.739              }
   1.740 @@ -523,107 +510,106 @@
   1.741            }
   1.742  
   1.743            // Augmenting along a shortest path from s to t.
   1.744 -          Capacity d = excess[s] < -excess[t] ? excess[s] : -excess[t];
   1.745 +          Capacity d = _excess[s] < -_excess[t] ? _excess[s] : -_excess[t];
   1.746            Node u = t;
   1.747            Edge e;
   1.748 -          if (d > delta) {
   1.749 -            while ((e = pred[u]) != INVALID) {
   1.750 +          if (d > _delta) {
   1.751 +            while ((e = _pred[u]) != INVALID) {
   1.752                Capacity rc;
   1.753 -              if (u == graph.target(e)) {
   1.754 -                rc = res_cap[e];
   1.755 -                u = graph.source(e);
   1.756 +              if (u == _graph.target(e)) {
   1.757 +                rc = _res_cap[e];
   1.758 +                u = _graph.source(e);
   1.759                } else {
   1.760 -                rc = flow[e];
   1.761 -                u = graph.target(e);
   1.762 +                rc = _flow[e];
   1.763 +                u = _graph.target(e);
   1.764                }
   1.765                if (rc < d) d = rc;
   1.766              }
   1.767            }
   1.768            u = t;
   1.769 -          while ((e = pred[u]) != INVALID) {
   1.770 -            if (u == graph.target(e)) {
   1.771 -              flow[e] += d;
   1.772 -              res_cap[e] -= d;
   1.773 -              u = graph.source(e);
   1.774 +          while ((e = _pred[u]) != INVALID) {
   1.775 +            if (u == _graph.target(e)) {
   1.776 +              _flow[e] += d;
   1.777 +              _res_cap[e] -= d;
   1.778 +              u = _graph.source(e);
   1.779              } else {
   1.780 -              flow[e] -= d;
   1.781 -              res_cap[e] += d;
   1.782 -              u = graph.target(e);
   1.783 +              _flow[e] -= d;
   1.784 +              _res_cap[e] += d;
   1.785 +              u = _graph.target(e);
   1.786              }
   1.787            }
   1.788 -          excess[s] -= d;
   1.789 -          excess[t] += d;
   1.790 +          _excess[s] -= d;
   1.791 +          _excess[t] += d;
   1.792  
   1.793 -          if (excess[s] < delta) ++next_node;
   1.794 +          if (_excess[s] < _delta) ++next_node;
   1.795          }
   1.796  
   1.797 -        if (delta == 1) break;
   1.798 -        if (++phase_cnt > phase_num / 4) factor = 2;
   1.799 -        delta = delta <= factor ? 1 : delta / factor;
   1.800 +        if (_delta == 1) break;
   1.801 +        if (++phase_cnt > _phase_num / 4) factor = 2;
   1.802 +        _delta = _delta <= factor ? 1 : _delta / factor;
   1.803        }
   1.804  
   1.805        // Handling non-zero lower bounds
   1.806 -      if (lower) {
   1.807 -        for (EdgeIt e(graph); e != INVALID; ++e)
   1.808 -          flow[e] += (*lower)[e];
   1.809 +      if (_lower) {
   1.810 +        for (EdgeIt e(_graph); e != INVALID; ++e)
   1.811 +          _flow[e] += (*_lower)[e];
   1.812        }
   1.813        return true;
   1.814      }
   1.815  
   1.816 -    /// \brief Executes the successive shortest path algorithm without
   1.817 -    /// capacity scaling.
   1.818 +    /// Executes the successive shortest path algorithm.
   1.819      bool startWithoutScaling() {
   1.820        // Finding excess nodes
   1.821 -      for (NodeIt n(graph); n != INVALID; ++n)
   1.822 -        if (excess[n] > 0) excess_nodes.push_back(n);
   1.823 -      if (excess_nodes.size() == 0) return true;
   1.824 +      for (NodeIt n(_graph); n != INVALID; ++n)
   1.825 +        if (_excess[n] > 0) _excess_nodes.push_back(n);
   1.826 +      if (_excess_nodes.size() == 0) return true;
   1.827        int next_node = 0;
   1.828  
   1.829        // Finding shortest paths
   1.830        Node s, t;
   1.831 -      while ( excess[excess_nodes[next_node]] > 0 ||
   1.832 -              ++next_node < excess_nodes.size() )
   1.833 +      while ( _excess[_excess_nodes[next_node]] > 0 ||
   1.834 +              ++next_node < int(_excess_nodes.size()) )
   1.835        {
   1.836          // Running Dijkstra
   1.837 -        s = excess_nodes[next_node];
   1.838 -        if ((t = dijkstra.run(s, 1)) == INVALID)
   1.839 +        s = _excess_nodes[next_node];
   1.840 +        if ((t = _dijkstra.run(s, 1)) == INVALID)
   1.841            return false;
   1.842  
   1.843          // Augmenting along a shortest path from s to t
   1.844 -        Capacity d = excess[s] < -excess[t] ? excess[s] : -excess[t];
   1.845 +        Capacity d = _excess[s] < -_excess[t] ? _excess[s] : -_excess[t];
   1.846          Node u = t;
   1.847          Edge e;
   1.848 -        while ((e = pred[u]) != INVALID) {
   1.849 +        while ((e = _pred[u]) != INVALID) {
   1.850            Capacity rc;
   1.851 -          if (u == graph.target(e)) {
   1.852 -            rc = res_cap[e];
   1.853 -            u = graph.source(e);
   1.854 +          if (u == _graph.target(e)) {
   1.855 +            rc = _res_cap[e];
   1.856 +            u = _graph.source(e);
   1.857            } else {
   1.858 -            rc = flow[e];
   1.859 -            u = graph.target(e);
   1.860 +            rc = _flow[e];
   1.861 +            u = _graph.target(e);
   1.862            }
   1.863            if (rc < d) d = rc;
   1.864          }
   1.865          u = t;
   1.866 -        while ((e = pred[u]) != INVALID) {
   1.867 -          if (u == graph.target(e)) {
   1.868 -            flow[e] += d;
   1.869 -            res_cap[e] -= d;
   1.870 -            u = graph.source(e);
   1.871 +        while ((e = _pred[u]) != INVALID) {
   1.872 +          if (u == _graph.target(e)) {
   1.873 +            _flow[e] += d;
   1.874 +            _res_cap[e] -= d;
   1.875 +            u = _graph.source(e);
   1.876            } else {
   1.877 -            flow[e] -= d;
   1.878 -            res_cap[e] += d;
   1.879 -            u = graph.target(e);
   1.880 +            _flow[e] -= d;
   1.881 +            _res_cap[e] += d;
   1.882 +            u = _graph.target(e);
   1.883            }
   1.884          }
   1.885 -        excess[s] -= d;
   1.886 -        excess[t] += d;
   1.887 +        _excess[s] -= d;
   1.888 +        _excess[t] += d;
   1.889        }
   1.890  
   1.891        // Handling non-zero lower bounds
   1.892 -      if (lower) {
   1.893 -        for (EdgeIt e(graph); e != INVALID; ++e)
   1.894 -          flow[e] += (*lower)[e];
   1.895 +      if (_lower) {
   1.896 +        for (EdgeIt e(_graph); e != INVALID; ++e)
   1.897 +          _flow[e] += (*_lower)[e];
   1.898        }
   1.899        return true;
   1.900      }