COIN-OR::LEMON - Graph Library

Ticket #180: 180-cas2-49cf636d96c5.patch

File 180-cas2-49cf636d96c5.patch, 45.0 KB (added by Peter Kovacs, 15 years ago)
  • lemon/capacity_scaling.h

    # HG changeset patch
    # User Peter Kovacs <kpeter@inf.elte.hu>
    # Date 1252679803 -7200
    # Node ID 49cf636d96c5e100d4d617fdad0fce997ec93bc4
    # Parent  317a0e41f3d5defc8f9aea733c56a77cd22ba1ca
    Fully rework CapacityScaling (#180)
    
      - Use the new interface similarly to NetworkSimplex.
      - Rework the implementation using an efficient internal structure
        for handling the residual network. This improvement made the
        code much faster (up to 2-5 times faster on large graphs).
      - Handle GEQ supply type (LEQ is not supported).
      - Extend the documentation.
    
    diff --git a/lemon/capacity_scaling.h b/lemon/capacity_scaling.h
    a b  
    1919#ifndef LEMON_CAPACITY_SCALING_H
    2020#define LEMON_CAPACITY_SCALING_H
    2121
    22 /// \ingroup min_cost_flow
     22/// \ingroup min_cost_flow_algs
    2323///
    2424/// \file
    25 /// \brief Capacity scaling algorithm for finding a minimum cost flow.
     25/// \brief Capacity Scaling algorithm for finding a minimum cost flow.
    2626
    2727#include <vector>
     28#include <limits>
     29#include <lemon/core.h>
    2830#include <lemon/bin_heap.h>
    2931
    3032namespace lemon {
    3133
    32   /// \addtogroup min_cost_flow
     34  /// \addtogroup min_cost_flow_algs
    3335  /// @{
    3436
    35   /// \brief Implementation of the capacity scaling algorithm for
    36   /// finding a minimum cost flow.
     37  /// \brief Implementation of the Capacity Scaling algorithm for
     38  /// finding a \ref min_cost_flow "minimum cost flow".
    3739  ///
    3840  /// \ref CapacityScaling implements the capacity scaling version
    39   /// of the successive shortest path algorithm for finding a minimum
    40   /// cost flow.
     41  /// of the successive shortest path algorithm for finding a
     42  /// \ref min_cost_flow "minimum cost flow". It is an efficient dual
     43  /// solution method.
    4144  ///
    42   /// \tparam Digraph The digraph type the algorithm runs on.
    43   /// \tparam LowerMap The type of the lower bound map.
    44   /// \tparam CapacityMap The type of the capacity (upper bound) map.
    45   /// \tparam CostMap The type of the cost (length) map.
    46   /// \tparam SupplyMap The type of the supply map.
     45  /// Most of the parameters of the problem (except for the digraph)
     46  /// can be given using separate functions, and the algorithm can be
     47  /// executed using the \ref run() function. If some parameters are not
     48  /// specified, then default values will be used.
    4749  ///
    48   /// \warning
    49   /// - Arc capacities and costs should be \e non-negative \e integers.
    50   /// - Supply values should be \e signed \e integers.
    51   /// - The value types of the maps should be convertible to each other.
    52   /// - \c CostMap::Value must be signed type.
     50  /// \tparam GR The digraph type the algorithm runs on.
     51  /// \tparam V The value type used for flow amounts, capacity bounds
     52  /// and supply values in the algorithm. By default it is \c int.
     53  /// \tparam C The value type used for costs and potentials in the
     54  /// algorithm. By default it is the same as \c V.
    5355  ///
    54   /// \author Peter Kovacs
    55   template < typename Digraph,
    56              typename LowerMap = typename Digraph::template ArcMap<int>,
    57              typename CapacityMap = typename Digraph::template ArcMap<int>,
    58              typename CostMap = typename Digraph::template ArcMap<int>,
    59              typename SupplyMap = typename Digraph::template NodeMap<int> >
     56  /// \warning Both value types must be signed and all input data must
     57  /// be integer.
     58  /// \warning This implementation can handle only non-negative arc costs.
     59  template <typename GR, typename V = int, typename C = V>
    6060  class CapacityScaling
    6161  {
    62     TEMPLATE_DIGRAPH_TYPEDEFS(Digraph);
     62  public:
    6363
    64     typedef typename CapacityMap::Value Capacity;
    65     typedef typename CostMap::Value Cost;
    66     typedef typename SupplyMap::Value Supply;
    67     typedef typename Digraph::template ArcMap<Capacity> CapacityArcMap;
    68     typedef typename Digraph::template NodeMap<Supply> SupplyNodeMap;
    69     typedef typename Digraph::template NodeMap<Arc> PredMap;
     64    /// The type of the flow amounts, capacity bounds and supply values
     65    typedef V Value;
     66    /// The type of the arc costs
     67    typedef C Cost;
    7068
    7169  public:
    7270
    73     /// The type of the flow map.
    74     typedef typename Digraph::template ArcMap<Capacity> FlowMap;
    75     /// The type of the potential map.
    76     typedef typename Digraph::template NodeMap<Cost> PotentialMap;
     71    /// \brief Problem type constants for the \c run() function.
     72    ///
     73    /// Enum type containing the problem type constants that can be
     74    /// returned by the \ref run() function of the algorithm.
     75    enum ProblemType {
     76      /// The problem has no feasible solution (flow).
     77      INFEASIBLE,
     78      /// The problem has optimal solution (i.e. it is feasible and
     79      /// bounded), and the algorithm has found optimal flow and node
     80      /// potentials (primal and dual solutions).
     81      OPTIMAL,
     82      /// The objective function of the problem is unbounded, i.e.
     83      /// there is a directed cycle having negative total cost and
     84      /// infinite upper bound.
     85      UNBOUNDED
     86    };
     87 
     88  private:
     89
     90    TEMPLATE_DIGRAPH_TYPEDEFS(GR);
     91
     92    typedef std::vector<Arc> ArcVector;
     93    typedef std::vector<Node> NodeVector;
     94    typedef std::vector<int> IntVector;
     95    typedef std::vector<bool> BoolVector;
     96    typedef std::vector<Value> ValueVector;
     97    typedef std::vector<Cost> CostVector;
    7798
    7899  private:
    79100
    80     /// \brief Special implementation of the \ref Dijkstra algorithm
    81     /// for finding shortest paths in the residual network.
     101    // Data related to the underlying digraph
     102    const GR &_graph;
     103    int _node_num;
     104    int _arc_num;
     105    int _res_arc_num;
     106    int _root;
     107
     108    // Parameters of the problem
     109    bool _have_lower;
     110    Value _sum_supply;
     111
     112    // Data structures for storing the digraph
     113    IntNodeMap _node_id;
     114    IntArcMap _arc_idf;
     115    IntArcMap _arc_idb;
     116    IntVector _first_out;
     117    BoolVector _forward;
     118    IntVector _source;
     119    IntVector _target;
     120    IntVector _reverse;
     121
     122    // Node and arc data
     123    ValueVector _lower;
     124    ValueVector _upper;
     125    CostVector _cost;
     126    ValueVector _supply;
     127
     128    ValueVector _res_cap;
     129    CostVector _pi;
     130    ValueVector _excess;
     131    IntVector _excess_nodes;
     132    IntVector _deficit_nodes;
     133
     134    Value _delta;
     135    int _phase_num;
     136    IntVector _pred;
     137
     138  public:
     139 
     140    /// \brief Constant for infinite upper bounds (capacities).
    82141    ///
    83     /// \ref ResidualDijkstra is a special implementation of the
    84     /// \ref Dijkstra algorithm for finding shortest paths in the
    85     /// residual network of the digraph with respect to the reduced arc
    86     /// costs and modifying the node potentials according to the
    87     /// distance of the nodes.
     142    /// Constant for infinite upper bounds (capacities).
     143    /// It is \c std::numeric_limits<Value>::infinity() if available,
     144    /// \c std::numeric_limits<Value>::max() otherwise.
     145    const Value INF;
     146
     147  private:
     148
     149    // Special implementation of the Dijkstra algorithm for finding
     150    // shortest paths in the residual network of the digraph with
     151    // respect to the reduced arc costs and modifying the node
     152    // potentials according to the found distance labels.
    88153    class ResidualDijkstra
    89154    {
    90       typedef typename Digraph::template NodeMap<int> HeapCrossRef;
     155      typedef RangeMap<int> HeapCrossRef;
    91156      typedef BinHeap<Cost, HeapCrossRef> Heap;
    92157
    93158    private:
    94159
    95       // The digraph the algorithm runs on
    96       const Digraph &_graph;
    97 
    98       // The main maps
    99       const FlowMap &_flow;
    100       const CapacityArcMap &_res_cap;
    101       const CostMap &_cost;
    102       const SupplyNodeMap &_excess;
    103       PotentialMap &_potential;
    104 
    105       // The distance map
    106       PotentialMap _dist;
    107       // The pred arc map
    108       PredMap &_pred;
    109       // The processed (i.e. permanently labeled) nodes
    110       std::vector<Node> _proc_nodes;
    111 
     160      int _node_num;
     161      const IntVector &_first_out;
     162      const IntVector &_target;
     163      const CostVector &_cost;
     164      const ValueVector &_res_cap;
     165      const ValueVector &_excess;
     166      CostVector &_pi;
     167      IntVector &_pred;
     168     
     169      IntVector _proc_nodes;
     170      CostVector _dist;
     171     
    112172    public:
    113173
    114       /// Constructor.
    115       ResidualDijkstra( const Digraph &digraph,
    116                         const FlowMap &flow,
    117                         const CapacityArcMap &res_cap,
    118                         const CostMap &cost,
    119                         const SupplyMap &excess,
    120                         PotentialMap &potential,
    121                         PredMap &pred ) :
    122         _graph(digraph), _flow(flow), _res_cap(res_cap), _cost(cost),
    123         _excess(excess), _potential(potential), _dist(digraph),
    124         _pred(pred)
     174      ResidualDijkstra(CapacityScaling& cs) :
     175        _node_num(cs._node_num), _first_out(cs._first_out),
     176        _target(cs._target), _cost(cs._cost), _res_cap(cs._res_cap),
     177        _excess(cs._excess), _pi(cs._pi), _pred(cs._pred),
     178        _dist(cs._node_num)
    125179      {}
    126180
    127       /// Run the algorithm from the given source node.
    128       Node run(Node s, Capacity delta = 1) {
    129         HeapCrossRef heap_cross_ref(_graph, Heap::PRE_HEAP);
     181      int run(int s, Value delta = 1) {
     182        HeapCrossRef heap_cross_ref(_node_num, Heap::PRE_HEAP);
    130183        Heap heap(heap_cross_ref);
    131184        heap.push(s, 0);
    132         _pred[s] = INVALID;
     185        _pred[s] = -1;
    133186        _proc_nodes.clear();
    134187
    135         // Processing nodes
     188        // Process nodes
    136189        while (!heap.empty() && _excess[heap.top()] > -delta) {
    137           Node u = heap.top(), v;
    138           Cost d = heap.prio() + _potential[u], nd;
     190          int u = heap.top(), v;
     191          Cost d = heap.prio() + _pi[u], dn;
    139192          _dist[u] = heap.prio();
     193          _proc_nodes.push_back(u);
    140194          heap.pop();
    141           _proc_nodes.push_back(u);
    142195
    143           // Traversing outgoing arcs
    144           for (OutArcIt e(_graph, u); e != INVALID; ++e) {
    145             if (_res_cap[e] >= delta) {
    146               v = _graph.target(e);
    147               switch(heap.state(v)) {
     196          // Traverse outgoing residual arcs
     197          for (int a = _first_out[u]; a != _first_out[u+1]; ++a) {
     198            if (_res_cap[a] < delta) continue;
     199            v = _target[a];
     200            switch (heap.state(v)) {
    148201              case Heap::PRE_HEAP:
    149                 heap.push(v, d + _cost[e] - _potential[v]);
    150                 _pred[v] = e;
     202                heap.push(v, d + _cost[a] - _pi[v]);
     203                _pred[v] = a;
    151204                break;
    152205              case Heap::IN_HEAP:
    153                 nd = d + _cost[e] - _potential[v];
    154                 if (nd < heap[v]) {
    155                   heap.decrease(v, nd);
    156                   _pred[v] = e;
     206                dn = d + _cost[a] - _pi[v];
     207                if (dn < heap[v]) {
     208                  heap.decrease(v, dn);
     209                  _pred[v] = a;
    157210                }
    158211                break;
    159212              case Heap::POST_HEAP:
    160213                break;
    161               }
    162             }
    163           }
    164 
    165           // Traversing incoming arcs
    166           for (InArcIt e(_graph, u); e != INVALID; ++e) {
    167             if (_flow[e] >= delta) {
    168               v = _graph.source(e);
    169               switch(heap.state(v)) {
    170               case Heap::PRE_HEAP:
    171                 heap.push(v, d - _cost[e] - _potential[v]);
    172                 _pred[v] = e;
    173                 break;
    174               case Heap::IN_HEAP:
    175                 nd = d - _cost[e] - _potential[v];
    176                 if (nd < heap[v]) {
    177                   heap.decrease(v, nd);
    178                   _pred[v] = e;
    179                 }
    180                 break;
    181               case Heap::POST_HEAP:
    182                 break;
    183               }
    184214            }
    185215          }
    186216        }
    187         if (heap.empty()) return INVALID;
     217        if (heap.empty()) return -1;
    188218
    189         // Updating potentials of processed nodes
    190         Node t = heap.top();
    191         Cost t_dist = heap.prio();
    192         for (int i = 0; i < int(_proc_nodes.size()); ++i)
    193           _potential[_proc_nodes[i]] += _dist[_proc_nodes[i]] - t_dist;
     219        // Update potentials of processed nodes
     220        int t = heap.top();
     221        Cost dt = heap.prio();
     222        for (int i = 0; i < int(_proc_nodes.size()); ++i) {
     223          _pi[_proc_nodes[i]] += _dist[_proc_nodes[i]] - dt;
     224        }
    194225
    195226        return t;
    196227      }
    197228
    198229    }; //class ResidualDijkstra
    199230
    200   private:
    201 
    202     // The digraph the algorithm runs on
    203     const Digraph &_graph;
    204     // The original lower bound map
    205     const LowerMap *_lower;
    206     // The modified capacity map
    207     CapacityArcMap _capacity;
    208     // The original cost map
    209     const CostMap &_cost;
    210     // The modified supply map
    211     SupplyNodeMap _supply;
    212     bool _valid_supply;
    213 
    214     // Arc map of the current flow
    215     FlowMap *_flow;
    216     bool _local_flow;
    217     // Node map of the current potentials
    218     PotentialMap *_potential;
    219     bool _local_potential;
    220 
    221     // The residual capacity map
    222     CapacityArcMap _res_cap;
    223     // The excess map
    224     SupplyNodeMap _excess;
    225     // The excess nodes (i.e. nodes with positive excess)
    226     std::vector<Node> _excess_nodes;
    227     // The deficit nodes (i.e. nodes with negative excess)
    228     std::vector<Node> _deficit_nodes;
    229 
    230     // The delta parameter used for capacity scaling
    231     Capacity _delta;
    232     // The maximum number of phases
    233     int _phase_num;
    234 
    235     // The pred arc map
    236     PredMap _pred;
    237     // Implementation of the Dijkstra algorithm for finding augmenting
    238     // shortest paths in the residual network
    239     ResidualDijkstra *_dijkstra;
    240 
    241231  public:
    242232
    243     /// \brief General constructor (with lower bounds).
     233    /// \brief Constructor.
    244234    ///
    245     /// General constructor (with lower bounds).
     235    /// The constructor of the class.
    246236    ///
    247     /// \param digraph The digraph the algorithm runs on.
    248     /// \param lower The lower bounds of the arcs.
    249     /// \param capacity The capacities (upper bounds) of the arcs.
    250     /// \param cost The cost (length) values of the arcs.
    251     /// \param supply The supply values of the nodes (signed).
    252     CapacityScaling( const Digraph &digraph,
    253                      const LowerMap &lower,
    254                      const CapacityMap &capacity,
    255                      const CostMap &cost,
    256                      const SupplyMap &supply ) :
    257       _graph(digraph), _lower(&lower), _capacity(digraph), _cost(cost),
    258       _supply(digraph), _flow(NULL), _local_flow(false),
    259       _potential(NULL), _local_potential(false),
    260       _res_cap(digraph), _excess(digraph), _pred(digraph), _dijkstra(NULL)
     237    /// \param graph The digraph the algorithm runs on.
     238    CapacityScaling(const GR& graph) :
     239      _graph(graph), _node_id(graph), _arc_idf(graph), _arc_idb(graph),
     240      INF(std::numeric_limits<Value>::has_infinity ?
     241          std::numeric_limits<Value>::infinity() :
     242          std::numeric_limits<Value>::max())
    261243    {
    262       Supply sum = 0;
    263       for (NodeIt n(_graph); n != INVALID; ++n) {
    264         _supply[n] = supply[n];
    265         _excess[n] = supply[n];
    266         sum += supply[n];
     244      // Check the value types
     245      LEMON_ASSERT(std::numeric_limits<Value>::is_signed,
     246        "The flow type of CapacityScaling must be signed");
     247      LEMON_ASSERT(std::numeric_limits<Cost>::is_signed,
     248        "The cost type of CapacityScaling must be signed");
     249
     250      // Resize vectors
     251      _node_num = countNodes(_graph);
     252      _arc_num = countArcs(_graph);
     253      _res_arc_num = 2 * (_arc_num + _node_num);
     254      _root = _node_num;
     255      ++_node_num;
     256
     257      _first_out.resize(_node_num + 1);
     258      _forward.resize(_res_arc_num);
     259      _source.resize(_res_arc_num);
     260      _target.resize(_res_arc_num);
     261      _reverse.resize(_res_arc_num);
     262
     263      _lower.resize(_res_arc_num);
     264      _upper.resize(_res_arc_num);
     265      _cost.resize(_res_arc_num);
     266      _supply.resize(_node_num);
     267     
     268      _res_cap.resize(_res_arc_num);
     269      _pi.resize(_node_num);
     270      _excess.resize(_node_num);
     271      _pred.resize(_node_num);
     272
     273      // Copy the graph
     274      int i = 0, j = 0, k = 2 * _arc_num + _node_num - 1;
     275      for (NodeIt n(_graph); n != INVALID; ++n, ++i) {
     276        _node_id[n] = i;
    267277      }
    268       _valid_supply = sum == 0;
     278      i = 0;
     279      for (NodeIt n(_graph); n != INVALID; ++n, ++i) {
     280        _first_out[i] = j;
     281        for (OutArcIt a(_graph, n); a != INVALID; ++a, ++j) {
     282          _arc_idf[a] = j;
     283          _forward[j] = true;
     284          _source[j] = i;
     285          _target[j] = _node_id[_graph.runningNode(a)];
     286        }
     287        for (InArcIt a(_graph, n); a != INVALID; ++a, ++j) {
     288          _arc_idb[a] = j;
     289          _forward[j] = false;
     290          _source[j] = i;
     291          _target[j] = _node_id[_graph.runningNode(a)];
     292        }
     293        _forward[j] = false;
     294        _source[j] = i;
     295        _target[j] = _root;
     296        _reverse[j] = k;
     297        _forward[k] = true;
     298        _source[k] = _root;
     299        _target[k] = i;
     300        _reverse[k] = j;
     301        ++j; ++k;
     302      }
     303      _first_out[i] = j;
     304      _first_out[_node_num] = k;
    269305      for (ArcIt a(_graph); a != INVALID; ++a) {
    270         _capacity[a] = capacity[a];
    271         _res_cap[a] = capacity[a];
     306        int fi = _arc_idf[a];
     307        int bi = _arc_idb[a];
     308        _reverse[fi] = bi;
     309        _reverse[bi] = fi;
    272310      }
    273 
    274       // Remove non-zero lower bounds
    275       typename LowerMap::Value lcap;
    276       for (ArcIt e(_graph); e != INVALID; ++e) {
    277         if ((lcap = lower[e]) != 0) {
    278           _capacity[e] -= lcap;
    279           _res_cap[e] -= lcap;
    280           _supply[_graph.source(e)] -= lcap;
    281           _supply[_graph.target(e)] += lcap;
    282           _excess[_graph.source(e)] -= lcap;
    283           _excess[_graph.target(e)] += lcap;
    284         }
    285       }
    286     }
    287 /*
    288     /// \brief General constructor (without lower bounds).
    289     ///
    290     /// General constructor (without lower bounds).
    291     ///
    292     /// \param digraph The digraph the algorithm runs on.
    293     /// \param capacity The capacities (upper bounds) of the arcs.
    294     /// \param cost The cost (length) values of the arcs.
    295     /// \param supply The supply values of the nodes (signed).
    296     CapacityScaling( const Digraph &digraph,
    297                      const CapacityMap &capacity,
    298                      const CostMap &cost,
    299                      const SupplyMap &supply ) :
    300       _graph(digraph), _lower(NULL), _capacity(capacity), _cost(cost),
    301       _supply(supply), _flow(NULL), _local_flow(false),
    302       _potential(NULL), _local_potential(false),
    303       _res_cap(capacity), _excess(supply), _pred(digraph), _dijkstra(NULL)
    304     {
    305       // Check the sum of supply values
    306       Supply sum = 0;
    307       for (NodeIt n(_graph); n != INVALID; ++n) sum += _supply[n];
    308       _valid_supply = sum == 0;
     311     
     312      // Reset parameters
     313      reset();
    309314    }
    310315
    311     /// \brief Simple constructor (with lower bounds).
     316    /// \name Parameters
     317    /// The parameters of the algorithm can be specified using these
     318    /// functions.
     319
     320    /// @{
     321
     322    /// \brief Set the lower bounds on the arcs.
    312323    ///
    313     /// Simple constructor (with lower bounds).
     324    /// This function sets the lower bounds on the arcs.
     325    /// If it is not used before calling \ref run(), the lower bounds
     326    /// will be set to zero on all arcs.
    314327    ///
    315     /// \param digraph The digraph the algorithm runs on.
    316     /// \param lower The lower bounds of the arcs.
    317     /// \param capacity The capacities (upper bounds) of the arcs.
    318     /// \param cost The cost (length) values of the arcs.
    319     /// \param s The source node.
    320     /// \param t The target node.
    321     /// \param flow_value The required amount of flow from node \c s
    322     /// to node \c t (i.e. the supply of \c s and the demand of \c t).
    323     CapacityScaling( const Digraph &digraph,
    324                      const LowerMap &lower,
    325                      const CapacityMap &capacity,
    326                      const CostMap &cost,
    327                      Node s, Node t,
    328                      Supply flow_value ) :
    329       _graph(digraph), _lower(&lower), _capacity(capacity), _cost(cost),
    330       _supply(digraph, 0), _flow(NULL), _local_flow(false),
    331       _potential(NULL), _local_potential(false),
    332       _res_cap(capacity), _excess(digraph, 0), _pred(digraph), _dijkstra(NULL)
    333     {
    334       // Remove non-zero lower bounds
    335       _supply[s] = _excess[s] =  flow_value;
    336       _supply[t] = _excess[t] = -flow_value;
    337       typename LowerMap::Value lcap;
    338       for (ArcIt e(_graph); e != INVALID; ++e) {
    339         if ((lcap = lower[e]) != 0) {
    340           _capacity[e] -= lcap;
    341           _res_cap[e] -= lcap;
    342           _supply[_graph.source(e)] -= lcap;
    343           _supply[_graph.target(e)] += lcap;
    344           _excess[_graph.source(e)] -= lcap;
    345           _excess[_graph.target(e)] += lcap;
    346         }
     328    /// \param map An arc map storing the lower bounds.
     329    /// Its \c Value type must be convertible to the \c Value type
     330    /// of the algorithm.
     331    ///
     332    /// \return <tt>(*this)</tt>
     333    template <typename LowerMap>
     334    CapacityScaling& lowerMap(const LowerMap& map) {
     335      _have_lower = true;
     336      for (ArcIt a(_graph); a != INVALID; ++a) {
     337        _lower[_arc_idf[a]] = map[a];
     338        _lower[_arc_idb[a]] = map[a];
    347339      }
    348       _valid_supply = true;
    349     }
    350 
    351     /// \brief Simple constructor (without lower bounds).
    352     ///
    353     /// Simple constructor (without lower bounds).
    354     ///
    355     /// \param digraph The digraph the algorithm runs on.
    356     /// \param capacity The capacities (upper bounds) of the arcs.
    357     /// \param cost The cost (length) values of the arcs.
    358     /// \param s The source node.
    359     /// \param t The target node.
    360     /// \param flow_value The required amount of flow from node \c s
    361     /// to node \c t (i.e. the supply of \c s and the demand of \c t).
    362     CapacityScaling( const Digraph &digraph,
    363                      const CapacityMap &capacity,
    364                      const CostMap &cost,
    365                      Node s, Node t,
    366                      Supply flow_value ) :
    367       _graph(digraph), _lower(NULL), _capacity(capacity), _cost(cost),
    368       _supply(digraph, 0), _flow(NULL), _local_flow(false),
    369       _potential(NULL), _local_potential(false),
    370       _res_cap(capacity), _excess(digraph, 0), _pred(digraph), _dijkstra(NULL)
    371     {
    372       _supply[s] = _excess[s] =  flow_value;
    373       _supply[t] = _excess[t] = -flow_value;
    374       _valid_supply = true;
    375     }
    376 */
    377     /// Destructor.
    378     ~CapacityScaling() {
    379       if (_local_flow) delete _flow;
    380       if (_local_potential) delete _potential;
    381       delete _dijkstra;
    382     }
    383 
    384     /// \brief Set the flow map.
    385     ///
    386     /// Set the flow map.
    387     ///
    388     /// \return \c (*this)
    389     CapacityScaling& flowMap(FlowMap &map) {
    390       if (_local_flow) {
    391         delete _flow;
    392         _local_flow = false;
    393       }
    394       _flow = &map;
    395340      return *this;
    396341    }
    397342
    398     /// \brief Set the potential map.
     343    /// \brief Set the upper bounds (capacities) on the arcs.
    399344    ///
    400     /// Set the potential map.
     345    /// This function sets the upper bounds (capacities) on the arcs.
     346    /// If it is not used before calling \ref run(), the upper bounds
     347    /// will be set to \ref INF on all arcs (i.e. the flow value will be
     348    /// unbounded from above on each arc).
    401349    ///
    402     /// \return \c (*this)
    403     CapacityScaling& potentialMap(PotentialMap &map) {
    404       if (_local_potential) {
    405         delete _potential;
    406         _local_potential = false;
     350    /// \param map An arc map storing the upper bounds.
     351    /// Its \c Value type must be convertible to the \c Value type
     352    /// of the algorithm.
     353    ///
     354    /// \return <tt>(*this)</tt>
     355    template<typename UpperMap>
     356    CapacityScaling& upperMap(const UpperMap& map) {
     357      for (ArcIt a(_graph); a != INVALID; ++a) {
     358        _upper[_arc_idf[a]] = map[a];
    407359      }
    408       _potential = &map;
    409360      return *this;
    410361    }
    411362
     363    /// \brief Set the costs of the arcs.
     364    ///
     365    /// This function sets the costs of the arcs.
     366    /// If it is not used before calling \ref run(), the costs
     367    /// will be set to \c 1 on all arcs.
     368    ///
     369    /// \param map An arc map storing the costs.
     370    /// Its \c Value type must be convertible to the \c Cost type
     371    /// of the algorithm.
     372    ///
     373    /// \return <tt>(*this)</tt>
     374    template<typename CostMap>
     375    CapacityScaling& costMap(const CostMap& map) {
     376      for (ArcIt a(_graph); a != INVALID; ++a) {
     377        _cost[_arc_idf[a]] =  map[a];
     378        _cost[_arc_idb[a]] = -map[a];
     379      }
     380      return *this;
     381    }
     382
     383    /// \brief Set the supply values of the nodes.
     384    ///
     385    /// This function sets the supply values of the nodes.
     386    /// If neither this function nor \ref stSupply() is used before
     387    /// calling \ref run(), the supply of each node will be set to zero.
     388    ///
     389    /// \param map A node map storing the supply values.
     390    /// Its \c Value type must be convertible to the \c Value type
     391    /// of the algorithm.
     392    ///
     393    /// \return <tt>(*this)</tt>
     394    template<typename SupplyMap>
     395    CapacityScaling& supplyMap(const SupplyMap& map) {
     396      for (NodeIt n(_graph); n != INVALID; ++n) {
     397        _supply[_node_id[n]] = map[n];
     398      }
     399      return *this;
     400    }
     401
     402    /// \brief Set single source and target nodes and a supply value.
     403    ///
     404    /// This function sets a single source node and a single target node
     405    /// and the required flow value.
     406    /// If neither this function nor \ref supplyMap() is used before
     407    /// calling \ref run(), the supply of each node will be set to zero.
     408    ///
     409    /// Using this function has the same effect as using \ref supplyMap()
     410    /// with such a map in which \c k is assigned to \c s, \c -k is
     411    /// assigned to \c t and all other nodes have zero supply value.
     412    ///
     413    /// \param s The source node.
     414    /// \param t The target node.
     415    /// \param k The required amount of flow from node \c s to node \c t
     416    /// (i.e. the supply of \c s and the demand of \c t).
     417    ///
     418    /// \return <tt>(*this)</tt>
     419    CapacityScaling& stSupply(const Node& s, const Node& t, Value k) {
     420      for (int i = 0; i != _node_num; ++i) {
     421        _supply[i] = 0;
     422      }
     423      _supply[_node_id[s]] =  k;
     424      _supply[_node_id[t]] = -k;
     425      return *this;
     426    }
     427   
     428    /// @}
     429
    412430    /// \name Execution control
    413431
    414432    /// @{
     
    416434    /// \brief Run the algorithm.
    417435    ///
    418436    /// This function runs the algorithm.
     437    /// The paramters can be specified using functions \ref lowerMap(),
     438    /// \ref upperMap(), \ref costMap(), \ref supplyMap(), \ref stSupply().
     439    /// For example,
     440    /// \code
     441    ///   CapacityScaling<ListDigraph> cs(graph);
     442    ///   cs.lowerMap(lower).upperMap(upper).costMap(cost)
     443    ///     .supplyMap(sup).run();
     444    /// \endcode
     445    ///
     446    /// This function can be called more than once. All the parameters
     447    /// that have been given are kept for the next call, unless
     448    /// \ref reset() is called, thus only the modified parameters
     449    /// have to be set again. See \ref reset() for examples.
     450    /// However the underlying digraph must not be modified after this
     451    /// class have been constructed, since it copies the digraph.
    419452    ///
    420453    /// \param scaling Enable or disable capacity scaling.
    421     /// If the maximum arc capacity and/or the amount of total supply
     454    /// If the maximum upper bound and/or the amount of total supply
    422455    /// is rather small, the algorithm could be slightly faster without
    423456    /// scaling.
    424457    ///
    425     /// \return \c true if a feasible flow can be found.
    426     bool run(bool scaling = true) {
    427       return init(scaling) && start();
     458    /// \return \c INFEASIBLE if no feasible flow exists,
     459    /// \n \c OPTIMAL if the problem has optimal solution
     460    /// (i.e. it is feasible and bounded), and the algorithm has found
     461    /// optimal flow and node potentials (primal and dual solutions),
     462    /// \n \c UNBOUNDED if the objective function of the problem is
     463    /// unbounded, i.e. there is a directed cycle having negative total
     464    /// cost and infinite upper bound.
     465    ///
     466    /// \see ProblemType
     467    ProblemType run(bool scaling = true) {
     468      if (!init(scaling)) return INFEASIBLE;
     469      return start();
     470    }
     471
     472    /// \brief Reset all the parameters that have been given before.
     473    ///
     474    /// This function resets all the paramaters that have been given
     475    /// before using functions \ref lowerMap(), \ref upperMap(),
     476    /// \ref costMap(), \ref supplyMap(), \ref stSupply().
     477    ///
     478    /// It is useful for multiple run() calls. If this function is not
     479    /// used, all the parameters given before are kept for the next
     480    /// \ref run() call.
     481    /// However the underlying digraph must not be modified after this
     482    /// class have been constructed, since it copies and extends the graph.
     483    ///
     484    /// For example,
     485    /// \code
     486    ///   CapacityScaling<ListDigraph> cs(graph);
     487    ///
     488    ///   // First run
     489    ///   cs.lowerMap(lower).upperMap(upper).costMap(cost)
     490    ///     .supplyMap(sup).run();
     491    ///
     492    ///   // Run again with modified cost map (reset() is not called,
     493    ///   // so only the cost map have to be set again)
     494    ///   cost[e] += 100;
     495    ///   cs.costMap(cost).run();
     496    ///
     497    ///   // Run again from scratch using reset()
     498    ///   // (the lower bounds will be set to zero on all arcs)
     499    ///   cs.reset();
     500    ///   cs.upperMap(capacity).costMap(cost)
     501    ///     .supplyMap(sup).run();
     502    /// \endcode
     503    ///
     504    /// \return <tt>(*this)</tt>
     505    CapacityScaling& reset() {
     506      for (int i = 0; i != _node_num; ++i) {
     507        _supply[i] = 0;
     508      }
     509      for (int j = 0; j != _res_arc_num; ++j) {
     510        _lower[j] = 0;
     511        _upper[j] = INF;
     512        _cost[j] = _forward[j] ? 1 : -1;
     513      }
     514      _have_lower = false;
     515      return *this;
    428516    }
    429517
    430518    /// @}
     
    432520    /// \name Query Functions
    433521    /// The results of the algorithm can be obtained using these
    434522    /// functions.\n
    435     /// \ref lemon::CapacityScaling::run() "run()" must be called before
    436     /// using them.
     523    /// The \ref run() function must be called before using them.
    437524
    438525    /// @{
    439526
    440     /// \brief Return a const reference to the arc map storing the
    441     /// found flow.
     527    /// \brief Return the total cost of the found flow.
    442528    ///
    443     /// Return a const reference to the arc map storing the found flow.
     529    /// This function returns the total cost of the found flow.
     530    /// Its complexity is O(e).
     531    ///
     532    /// \note The return type of the function can be specified as a
     533    /// template parameter. For example,
     534    /// \code
     535    ///   cs.totalCost<double>();
     536    /// \endcode
     537    /// It is useful if the total cost cannot be stored in the \c Cost
     538    /// type of the algorithm, which is the default return type of the
     539    /// function.
    444540    ///
    445541    /// \pre \ref run() must be called before using this function.
    446     const FlowMap& flowMap() const {
    447       return *_flow;
     542    template <typename Number>
     543    Number totalCost() const {
     544      Number c = 0;
     545      for (ArcIt a(_graph); a != INVALID; ++a) {
     546        int i = _arc_idb[a];
     547        c += static_cast<Number>(_res_cap[i]) *
     548             (-static_cast<Number>(_cost[i]));
     549      }
     550      return c;
    448551    }
    449552
    450     /// \brief Return a const reference to the node map storing the
    451     /// found potentials (the dual solution).
    452     ///
    453     /// Return a const reference to the node map storing the found
    454     /// potentials (the dual solution).
    455     ///
    456     /// \pre \ref run() must be called before using this function.
    457     const PotentialMap& potentialMap() const {
    458       return *_potential;
     553#ifndef DOXYGEN
     554    Cost totalCost() const {
     555      return totalCost<Cost>();
    459556    }
     557#endif
    460558
    461559    /// \brief Return the flow on the given arc.
    462560    ///
    463     /// Return the flow on the given arc.
     561    /// This function returns the flow on the given arc.
    464562    ///
    465563    /// \pre \ref run() must be called before using this function.
    466     Capacity flow(const Arc& arc) const {
    467       return (*_flow)[arc];
     564    Value flow(const Arc& a) const {
     565      return _res_cap[_arc_idb[a]];
    468566    }
    469567
    470     /// \brief Return the potential of the given node.
     568    /// \brief Return the flow map (the primal solution).
    471569    ///
    472     /// Return the potential of the given node.
     570    /// This function copies the flow value on each arc into the given
     571    /// map. The \c Value type of the algorithm must be convertible to
     572    /// the \c Value type of the map.
    473573    ///
    474574    /// \pre \ref run() must be called before using this function.
    475     Cost potential(const Node& node) const {
    476       return (*_potential)[node];
     575    template <typename FlowMap>
     576    void flowMap(FlowMap &map) const {
     577      for (ArcIt a(_graph); a != INVALID; ++a) {
     578        map.set(a, _res_cap[_arc_idb[a]]);
     579      }
    477580    }
    478581
    479     /// \brief Return the total cost of the found flow.
     582    /// \brief Return the potential (dual value) of the given node.
    480583    ///
    481     /// Return the total cost of the found flow. The complexity of the
    482     /// function is \f$ O(e) \f$.
     584    /// This function returns the potential (dual value) of the
     585    /// given node.
    483586    ///
    484587    /// \pre \ref run() must be called before using this function.
    485     Cost totalCost() const {
    486       Cost c = 0;
    487       for (ArcIt e(_graph); e != INVALID; ++e)
    488         c += (*_flow)[e] * _cost[e];
    489       return c;
     588    Cost potential(const Node& n) const {
     589      return _pi[_node_id[n]];
     590    }
     591
     592    /// \brief Return the potential map (the dual solution).
     593    ///
     594    /// This function copies the potential (dual value) of each node
     595    /// into the given map.
     596    /// The \c Cost type of the algorithm must be convertible to the
     597    /// \c Value type of the map.
     598    ///
     599    /// \pre \ref run() must be called before using this function.
     600    template <typename PotentialMap>
     601    void potentialMap(PotentialMap &map) const {
     602      for (NodeIt n(_graph); n != INVALID; ++n) {
     603        map.set(n, _pi[_node_id[n]]);
     604      }
    490605    }
    491606
    492607    /// @}
    493608
    494609  private:
    495610
    496     /// Initialize the algorithm.
     611    // Initialize the algorithm
    497612    bool init(bool scaling) {
    498       if (!_valid_supply) return false;
     613      if (_node_num == 0) return false;
    499614
    500       // Initializing maps
    501       if (!_flow) {
    502         _flow = new FlowMap(_graph);
    503         _local_flow = true;
     615      // Check the sum of supply values
     616      _sum_supply = 0;
     617      for (int i = 0; i != _root; ++i) {
     618        _sum_supply += _supply[i];
    504619      }
    505       if (!_potential) {
    506         _potential = new PotentialMap(_graph);
    507         _local_potential = true;
     620      if (_sum_supply > 0) return false;
     621     
     622      // Initialize maps
     623      for (int i = 0; i != _root; ++i) {
     624        _pi[i] = 0;
     625        _excess[i] = _supply[i];
    508626      }
    509       for (ArcIt e(_graph); e != INVALID; ++e) (*_flow)[e] = 0;
    510       for (NodeIt n(_graph); n != INVALID; ++n) (*_potential)[n] = 0;
    511627
    512       _dijkstra = new ResidualDijkstra( _graph, *_flow, _res_cap, _cost,
    513                                         _excess, *_potential, _pred );
     628      // Remove non-zero lower bounds
     629      if (_have_lower) {
     630        for (int i = 0; i != _root; ++i) {
     631          for (int j = _first_out[i]; j != _first_out[i+1]; ++j) {
     632            if (_forward[j]) {
     633              Value c = _lower[j];
     634              if (c >= 0) {
     635                _res_cap[j] = _upper[j] < INF ? _upper[j] - c : INF;
     636              } else {
     637                _res_cap[j] = _upper[j] < INF + c ? _upper[j] - c : INF;
     638              }
     639              _excess[i] -= c;
     640              _excess[_target[j]] += c;
     641            } else {
     642              _res_cap[j] = 0;
     643            }
     644          }
     645        }
     646      } else {
     647        for (int j = 0; j != _res_arc_num; ++j) {
     648          _res_cap[j] = _forward[j] ? _upper[j] : 0;
     649        }
     650      }
     651     
     652      // Handle GEQ supply type
     653      if (_sum_supply < 0) {
     654        _pi[_root] = 0;
     655        _excess[_root] = -_sum_supply;
     656        for (int a = _first_out[_root]; a != _res_arc_num; ++a) {
     657          int u = _target[a];
     658          if (_excess[u] < 0) {
     659            _res_cap[a] = -_excess[u] + 1;
     660          } else {
     661            _res_cap[a] = 1;
     662          }
     663          _res_cap[_reverse[a]] = 0;
     664          _cost[a] = 0;
     665          _cost[_reverse[a]] = 0;
     666        }
     667      } else {
     668        _pi[_root] = 0;
     669        _excess[_root] = 0;
     670        for (int a = _first_out[_root]; a != _res_arc_num; ++a) {
     671          _res_cap[a] = 1;
     672          _res_cap[_reverse[a]] = 0;
     673          _cost[a] = 0;
     674          _cost[_reverse[a]] = 0;
     675        }
     676      }
    514677
    515       // Initializing delta value
     678      // Initialize delta value
    516679      if (scaling) {
    517680        // With scaling
    518         Supply max_sup = 0, max_dem = 0;
    519         for (NodeIt n(_graph); n != INVALID; ++n) {
    520           if ( _supply[n] > max_sup) max_sup =  _supply[n];
    521           if (-_supply[n] > max_dem) max_dem = -_supply[n];
     681        Value max_sup = 0, max_dem = 0;
     682        for (int i = 0; i != _node_num; ++i) {
     683          if ( _excess[i] > max_sup) max_sup =  _excess[i];
     684          if (-_excess[i] > max_dem) max_dem = -_excess[i];
    522685        }
    523         Capacity max_cap = 0;
    524         for (ArcIt e(_graph); e != INVALID; ++e) {
    525           if (_capacity[e] > max_cap) max_cap = _capacity[e];
     686        Value max_cap = 0;
     687        for (int j = 0; j != _res_arc_num; ++j) {
     688          if (_res_cap[j] > max_cap) max_cap = _res_cap[j];
    526689        }
    527690        max_sup = std::min(std::min(max_sup, max_dem), max_cap);
    528691        _phase_num = 0;
     
    536699      return true;
    537700    }
    538701
    539     bool start() {
     702    ProblemType start() {
     703      // Execute the algorithm
     704      ProblemType pt;
    540705      if (_delta > 1)
    541         return startWithScaling();
     706        pt = startWithScaling();
    542707      else
    543         return startWithoutScaling();
     708        pt = startWithoutScaling();
     709
     710      // Handle non-zero lower bounds
     711      if (_have_lower) {
     712        for (int j = 0; j != _res_arc_num - _node_num + 1; ++j) {
     713          if (!_forward[j]) _res_cap[j] += _lower[j];
     714        }
     715      }
     716
     717      // Shift potentials if necessary
     718      Cost pr = _pi[_root];
     719      if (_sum_supply < 0 || pr > 0) {
     720        for (int i = 0; i != _node_num; ++i) {
     721          _pi[i] -= pr;
     722        }       
     723      }
     724     
     725      return pt;
    544726    }
    545727
    546     /// Execute the capacity scaling algorithm.
    547     bool startWithScaling() {
    548       // Processing capacity scaling phases
    549       Node s, t;
     728    // Execute the capacity scaling algorithm
     729    ProblemType startWithScaling() {
     730      // Process capacity scaling phases
     731      int s, t;
    550732      int phase_cnt = 0;
    551733      int factor = 4;
     734      ResidualDijkstra _dijkstra(*this);
    552735      while (true) {
    553         // Saturating all arcs not satisfying the optimality condition
    554         for (ArcIt e(_graph); e != INVALID; ++e) {
    555           Node u = _graph.source(e), v = _graph.target(e);
    556           Cost c = _cost[e] + (*_potential)[u] - (*_potential)[v];
    557           if (c < 0 && _res_cap[e] >= _delta) {
    558             _excess[u] -= _res_cap[e];
    559             _excess[v] += _res_cap[e];
    560             (*_flow)[e] = _capacity[e];
    561             _res_cap[e] = 0;
    562           }
    563           else if (c > 0 && (*_flow)[e] >= _delta) {
    564             _excess[u] += (*_flow)[e];
    565             _excess[v] -= (*_flow)[e];
    566             (*_flow)[e] = 0;
    567             _res_cap[e] = _capacity[e];
     736        // Saturate all arcs not satisfying the optimality condition
     737        for (int u = 0; u != _node_num; ++u) {
     738          for (int a = _first_out[u]; a != _first_out[u+1]; ++a) {
     739            int v = _target[a];
     740            Cost c = _cost[a] + _pi[u] - _pi[v];
     741            Value rc = _res_cap[a];
     742            if (c < 0 && rc >= _delta) {
     743              _excess[u] -= rc;
     744              _excess[v] += rc;
     745              _res_cap[a] = 0;
     746              _res_cap[_reverse[a]] += rc;
     747            }
    568748          }
    569749        }
    570750
    571         // Finding excess nodes and deficit nodes
     751        // Find excess nodes and deficit nodes
    572752        _excess_nodes.clear();
    573753        _deficit_nodes.clear();
    574         for (NodeIt n(_graph); n != INVALID; ++n) {
    575           if (_excess[n] >=  _delta) _excess_nodes.push_back(n);
    576           if (_excess[n] <= -_delta) _deficit_nodes.push_back(n);
     754        for (int u = 0; u != _node_num; ++u) {
     755          if (_excess[u] >=  _delta) _excess_nodes.push_back(u);
     756          if (_excess[u] <= -_delta) _deficit_nodes.push_back(u);
    577757        }
    578758        int next_node = 0, next_def_node = 0;
    579759
    580         // Finding augmenting shortest paths
     760        // Find augmenting shortest paths
    581761        while (next_node < int(_excess_nodes.size())) {
    582           // Checking deficit nodes
     762          // Check deficit nodes
    583763          if (_delta > 1) {
    584764            bool delta_deficit = false;
    585765            for ( ; next_def_node < int(_deficit_nodes.size());
     
    592772            if (!delta_deficit) break;
    593773          }
    594774
    595           // Running Dijkstra
     775          // Run Dijkstra in the residual network
    596776          s = _excess_nodes[next_node];
    597           if ((t = _dijkstra->run(s, _delta)) == INVALID) {
     777          if ((t = _dijkstra.run(s, _delta)) == -1) {
    598778            if (_delta > 1) {
    599779              ++next_node;
    600780              continue;
    601781            }
    602             return false;
     782            return INFEASIBLE;
    603783          }
    604784
    605           // Augmenting along a shortest path from s to t.
    606           Capacity d = std::min(_excess[s], -_excess[t]);
    607           Node u = t;
    608           Arc e;
     785          // Augment along a shortest path from s to t
     786          Value d = std::min(_excess[s], -_excess[t]);
     787          int u = t;
     788          int a;
    609789          if (d > _delta) {
    610             while ((e = _pred[u]) != INVALID) {
    611               Capacity rc;
    612               if (u == _graph.target(e)) {
    613                 rc = _res_cap[e];
    614                 u = _graph.source(e);
    615               } else {
    616                 rc = (*_flow)[e];
    617                 u = _graph.target(e);
    618               }
    619               if (rc < d) d = rc;
     790            while ((a = _pred[u]) != -1) {
     791              if (_res_cap[a] < d) d = _res_cap[a];
     792              u = _source[a];
    620793            }
    621794          }
    622795          u = t;
    623           while ((e = _pred[u]) != INVALID) {
    624             if (u == _graph.target(e)) {
    625               (*_flow)[e] += d;
    626               _res_cap[e] -= d;
    627               u = _graph.source(e);
    628             } else {
    629               (*_flow)[e] -= d;
    630               _res_cap[e] += d;
    631               u = _graph.target(e);
    632             }
     796          while ((a = _pred[u]) != -1) {
     797            _res_cap[a] -= d;
     798            _res_cap[_reverse[a]] += d;
     799            u = _source[a];
    633800          }
    634801          _excess[s] -= d;
    635802          _excess[t] += d;
     
    638805        }
    639806
    640807        if (_delta == 1) break;
    641         if (++phase_cnt > _phase_num / 4) factor = 2;
     808        if (++phase_cnt == _phase_num / 4) factor = 2;
    642809        _delta = _delta <= factor ? 1 : _delta / factor;
    643810      }
    644811
    645       // Handling non-zero lower bounds
    646       if (_lower) {
    647         for (ArcIt e(_graph); e != INVALID; ++e)
    648           (*_flow)[e] += (*_lower)[e];
    649       }
    650       return true;
     812      return OPTIMAL;
    651813    }
    652814
    653     /// Execute the successive shortest path algorithm.
    654     bool startWithoutScaling() {
    655       // Finding excess nodes
    656       for (NodeIt n(_graph); n != INVALID; ++n)
    657         if (_excess[n] > 0) _excess_nodes.push_back(n);
    658       if (_excess_nodes.size() == 0) return true;
     815    // Execute the successive shortest path algorithm
     816    ProblemType startWithoutScaling() {
     817      // Find excess nodes
     818      _excess_nodes.clear();
     819      for (int i = 0; i != _node_num; ++i) {
     820        if (_excess[i] > 0) _excess_nodes.push_back(i);
     821      }
     822      if (_excess_nodes.size() == 0) return OPTIMAL;
    659823      int next_node = 0;
    660824
    661       // Finding shortest paths
    662       Node s, t;
     825      // Find shortest paths
     826      int s, t;
     827      ResidualDijkstra _dijkstra(*this);
    663828      while ( _excess[_excess_nodes[next_node]] > 0 ||
    664829              ++next_node < int(_excess_nodes.size()) )
    665830      {
    666         // Running Dijkstra
     831        // Run Dijkstra in the residual network
    667832        s = _excess_nodes[next_node];
    668         if ((t = _dijkstra->run(s)) == INVALID) return false;
     833        if ((t = _dijkstra.run(s)) == -1) return INFEASIBLE;
    669834
    670         // Augmenting along a shortest path from s to t
    671         Capacity d = std::min(_excess[s], -_excess[t]);
    672         Node u = t;
    673         Arc e;
     835        // Augment along a shortest path from s to t
     836        Value d = std::min(_excess[s], -_excess[t]);
     837        int u = t;
     838        int a;
    674839        if (d > 1) {
    675           while ((e = _pred[u]) != INVALID) {
    676             Capacity rc;
    677             if (u == _graph.target(e)) {
    678               rc = _res_cap[e];
    679               u = _graph.source(e);
    680             } else {
    681               rc = (*_flow)[e];
    682               u = _graph.target(e);
    683             }
    684             if (rc < d) d = rc;
     840          while ((a = _pred[u]) != -1) {
     841            if (_res_cap[a] < d) d = _res_cap[a];
     842            u = _source[a];
    685843          }
    686844        }
    687845        u = t;
    688         while ((e = _pred[u]) != INVALID) {
    689           if (u == _graph.target(e)) {
    690             (*_flow)[e] += d;
    691             _res_cap[e] -= d;
    692             u = _graph.source(e);
    693           } else {
    694             (*_flow)[e] -= d;
    695             _res_cap[e] += d;
    696             u = _graph.target(e);
    697           }
     846        while ((a = _pred[u]) != -1) {
     847          _res_cap[a] -= d;
     848          _res_cap[_reverse[a]] += d;
     849          u = _source[a];
    698850        }
    699851        _excess[s] -= d;
    700852        _excess[t] += d;
    701853      }
    702854
    703       // Handling non-zero lower bounds
    704       if (_lower) {
    705         for (ArcIt e(_graph); e != INVALID; ++e)
    706           (*_flow)[e] += (*_lower)[e];
    707       }
    708       return true;
     855      return OPTIMAL;
    709856    }
    710857
    711858  }; //class CapacityScaling