1.1 --- a/lemon/Makefile.am Mon May 07 08:49:57 2007 +0000
1.2 +++ b/lemon/Makefile.am Mon May 07 11:42:18 2007 +0000
1.3 @@ -42,12 +42,14 @@
1.4 lemon/bp_matching.h \
1.5 lemon/bpugraph_adaptor.h \
1.6 lemon/bucket_heap.h \
1.7 + lemon/capacity_scaling.h \
1.8 lemon/circulation.h \
1.9 lemon/color.h \
1.10 lemon/config.h \
1.11 lemon/concept_check.h \
1.12 lemon/counter.h \
1.13 lemon/csp.h \
1.14 + lemon/cycle_canceling.h \
1.15 lemon/dag_shortest_path.h \
1.16 lemon/dfs.h \
1.17 lemon/dijkstra.h \
1.18 @@ -89,10 +91,13 @@
1.19 lemon/matrix_maps.h \
1.20 lemon/max_matching.h \
1.21 lemon/min_cost_arborescence.h \
1.22 + lemon/min_cost_flow.h \
1.23 + lemon/min_cost_max_flow.h \
1.24 lemon/min_mean_cycle.h \
1.25 lemon/mip_glpk.h \
1.26 lemon/mip_cplex.h \
1.27 lemon/nagamochi_ibaraki.h \
1.28 + lemon/network_simplex.h \
1.29 lemon/path.h \
1.30 lemon/path_utils.h \
1.31 lemon/polynomial.h \
2.1 --- /dev/null Thu Jan 01 00:00:00 1970 +0000
2.2 +++ b/lemon/capacity_scaling.h Mon May 07 11:42:18 2007 +0000
2.3 @@ -0,0 +1,680 @@
2.4 +/* -*- C++ -*-
2.5 + *
2.6 + * This file is a part of LEMON, a generic C++ optimization library
2.7 + *
2.8 + * Copyright (C) 2003-2007
2.9 + * Egervary Jeno Kombinatorikus Optimalizalasi Kutatocsoport
2.10 + * (Egervary Research Group on Combinatorial Optimization, EGRES).
2.11 + *
2.12 + * Permission to use, modify and distribute this software is granted
2.13 + * provided that this copyright notice appears in all copies. For
2.14 + * precise terms see the accompanying LICENSE file.
2.15 + *
2.16 + * This software is provided "AS IS" with no warranty of any kind,
2.17 + * express or implied, and with no claim as to its suitability for any
2.18 + * purpose.
2.19 + *
2.20 + */
2.21 +
2.22 +#ifndef LEMON_CAPACITY_SCALING_H
2.23 +#define LEMON_CAPACITY_SCALING_H
2.24 +
2.25 +/// \ingroup min_cost_flow
2.26 +///
2.27 +/// \file
2.28 +/// \brief The capacity scaling algorithm for finding a minimum cost
2.29 +/// flow.
2.30 +
2.31 +#include <vector>
2.32 +#include <lemon/dijkstra.h>
2.33 +#include <lemon/graph_adaptor.h>
2.34 +
2.35 +#define WITH_SCALING
2.36 +
2.37 +namespace lemon {
2.38 +
2.39 + /// \addtogroup min_cost_flow
2.40 + /// @{
2.41 +
2.42 + /// \brief Implementation of the capacity scaling version of the
2.43 + /// succesive shortest path algorithm for finding a minimum cost flow.
2.44 + ///
2.45 + /// \ref lemon::CapacityScaling "CapacityScaling" implements a
2.46 + /// capacity scaling algorithm for finding a minimum cost flow.
2.47 + ///
2.48 + /// \param Graph The directed graph type the algorithm runs on.
2.49 + /// \param LowerMap The type of the lower bound map.
2.50 + /// \param CapacityMap The type of the capacity (upper bound) map.
2.51 + /// \param CostMap The type of the cost (length) map.
2.52 + /// \param SupplyMap The type of the supply map.
2.53 + ///
2.54 + /// \warning
2.55 + /// - Edge capacities and costs should be nonnegative integers.
2.56 + /// However \c CostMap::Value should be signed type.
2.57 + /// - Supply values should be integers.
2.58 + /// - \c LowerMap::Value must be convertible to
2.59 + /// \c CapacityMap::Value and \c CapacityMap::Value must be
2.60 + /// convertible to \c SupplyMap::Value.
2.61 + ///
2.62 + /// \author Peter Kovacs
2.63 +
2.64 +template < typename Graph,
2.65 + typename LowerMap = typename Graph::template EdgeMap<int>,
2.66 + typename CapacityMap = LowerMap,
2.67 + typename CostMap = typename Graph::template EdgeMap<int>,
2.68 + typename SupplyMap = typename Graph::template NodeMap
2.69 + <typename CapacityMap::Value> >
2.70 + class CapacityScaling
2.71 + {
2.72 + typedef typename Graph::Node Node;
2.73 + typedef typename Graph::NodeIt NodeIt;
2.74 + typedef typename Graph::Edge Edge;
2.75 + typedef typename Graph::EdgeIt EdgeIt;
2.76 + typedef typename Graph::InEdgeIt InEdgeIt;
2.77 + typedef typename Graph::OutEdgeIt OutEdgeIt;
2.78 +
2.79 + typedef typename LowerMap::Value Lower;
2.80 + typedef typename CapacityMap::Value Capacity;
2.81 + typedef typename CostMap::Value Cost;
2.82 + typedef typename SupplyMap::Value Supply;
2.83 + typedef typename Graph::template EdgeMap<Capacity> CapacityRefMap;
2.84 + typedef typename Graph::template NodeMap<Supply> SupplyRefMap;
2.85 +
2.86 + typedef ResGraphAdaptor< const Graph, Capacity,
2.87 + CapacityRefMap, CapacityRefMap > ResGraph;
2.88 + typedef typename ResGraph::Node ResNode;
2.89 + typedef typename ResGraph::NodeIt ResNodeIt;
2.90 + typedef typename ResGraph::Edge ResEdge;
2.91 + typedef typename ResGraph::EdgeIt ResEdgeIt;
2.92 +
2.93 + public:
2.94 +
2.95 + /// \brief The type of the flow map.
2.96 + typedef CapacityRefMap FlowMap;
2.97 + /// \brief The type of the potential map.
2.98 + typedef typename Graph::template NodeMap<Cost> PotentialMap;
2.99 +
2.100 + protected:
2.101 +
2.102 + /// \brief Map adaptor class for handling reduced edge costs.
2.103 + class ReducedCostMap : public MapBase<ResEdge, Cost>
2.104 + {
2.105 + private:
2.106 +
2.107 + const ResGraph &gr;
2.108 + const CostMap &cost_map;
2.109 + const PotentialMap &pot_map;
2.110 +
2.111 + public:
2.112 +
2.113 + typedef typename MapBase<ResEdge, Cost>::Value Value;
2.114 + typedef typename MapBase<ResEdge, Cost>::Key Key;
2.115 +
2.116 + ReducedCostMap( const ResGraph &_gr,
2.117 + const CostMap &_cost,
2.118 + const PotentialMap &_pot ) :
2.119 + gr(_gr), cost_map(_cost), pot_map(_pot) {}
2.120 +
2.121 + Value operator[](const Key &e) const {
2.122 + return ResGraph::forward(e) ?
2.123 + cost_map[e] - pot_map[gr.source(e)] + pot_map[gr.target(e)] :
2.124 + -cost_map[e] - pot_map[gr.source(e)] + pot_map[gr.target(e)];
2.125 + }
2.126 +
2.127 + }; //class ReducedCostMap
2.128 +
2.129 + /// \brief Map adaptor for \ref lemon::Dijkstra "Dijkstra" class to
2.130 + /// update node potentials.
2.131 + class PotentialUpdateMap : public MapBase<ResNode, Cost>
2.132 + {
2.133 + private:
2.134 +
2.135 + PotentialMap *pot;
2.136 + typedef std::pair<ResNode, Cost> Pair;
2.137 + std::vector<Pair> data;
2.138 +
2.139 + public:
2.140 +
2.141 + typedef typename MapBase<ResNode, Cost>::Value Value;
2.142 + typedef typename MapBase<ResNode, Cost>::Key Key;
2.143 +
2.144 + void potentialMap(PotentialMap &_pot) {
2.145 + pot = &_pot;
2.146 + }
2.147 +
2.148 + void init() {
2.149 + data.clear();
2.150 + }
2.151 +
2.152 + void set(const Key &n, const Value &v) {
2.153 + data.push_back(Pair(n, v));
2.154 + }
2.155 +
2.156 + void update() {
2.157 + Cost val = data[data.size()-1].second;
2.158 + for (int i = 0; i < data.size()-1; ++i)
2.159 + (*pot)[data[i].first] += val - data[i].second;
2.160 + }
2.161 +
2.162 + }; //class PotentialUpdateMap
2.163 +
2.164 +#ifdef WITH_SCALING
2.165 + /// \brief Map adaptor class for identifing deficit nodes.
2.166 + class DeficitBoolMap : public MapBase<ResNode, bool>
2.167 + {
2.168 + private:
2.169 +
2.170 + const SupplyRefMap &imb;
2.171 + const Capacity δ
2.172 +
2.173 + public:
2.174 +
2.175 + DeficitBoolMap(const SupplyRefMap &_imb, const Capacity &_delta) :
2.176 + imb(_imb), delta(_delta) {}
2.177 +
2.178 + bool operator[](const ResNode &n) const {
2.179 + return imb[n] <= -delta;
2.180 + }
2.181 +
2.182 + }; //class DeficitBoolMap
2.183 +
2.184 + /// \brief Map adaptor class for filtering edges with at least
2.185 + /// \c delta residual capacity
2.186 + class DeltaFilterMap : public MapBase<ResEdge, bool>
2.187 + {
2.188 + private:
2.189 +
2.190 + const ResGraph &gr;
2.191 + const Capacity δ
2.192 +
2.193 + public:
2.194 +
2.195 + typedef typename MapBase<ResEdge, Cost>::Value Value;
2.196 + typedef typename MapBase<ResEdge, Cost>::Key Key;
2.197 +
2.198 + DeltaFilterMap(const ResGraph &_gr, const Capacity &_delta) :
2.199 + gr(_gr), delta(_delta) {}
2.200 +
2.201 + Value operator[](const Key &e) const {
2.202 + return gr.rescap(e) >= delta;
2.203 + }
2.204 +
2.205 + }; //class DeltaFilterMap
2.206 +
2.207 + typedef EdgeSubGraphAdaptor<const ResGraph, const DeltaFilterMap>
2.208 + DeltaResGraph;
2.209 +
2.210 + /// \brief Traits class for \ref lemon::Dijkstra "Dijkstra" class.
2.211 + class ResDijkstraTraits :
2.212 + public DijkstraDefaultTraits<DeltaResGraph, ReducedCostMap>
2.213 + {
2.214 + public:
2.215 +
2.216 + typedef PotentialUpdateMap DistMap;
2.217 +
2.218 + static DistMap *createDistMap(const DeltaResGraph&) {
2.219 + return new DistMap();
2.220 + }
2.221 +
2.222 + }; //class ResDijkstraTraits
2.223 +
2.224 +#else //WITHOUT_CAPACITY_SCALING
2.225 + /// \brief Map adaptor class for identifing deficit nodes.
2.226 + class DeficitBoolMap : public MapBase<ResNode, bool>
2.227 + {
2.228 + private:
2.229 +
2.230 + const SupplyRefMap &imb;
2.231 +
2.232 + public:
2.233 +
2.234 + DeficitBoolMap(const SupplyRefMap &_imb) : imb(_imb) {}
2.235 +
2.236 + bool operator[](const ResNode &n) const {
2.237 + return imb[n] < 0;
2.238 + }
2.239 +
2.240 + }; //class DeficitBoolMap
2.241 +
2.242 + /// \brief Traits class for \ref lemon::Dijkstra "Dijkstra" class.
2.243 + class ResDijkstraTraits :
2.244 + public DijkstraDefaultTraits<ResGraph, ReducedCostMap>
2.245 + {
2.246 + public:
2.247 +
2.248 + typedef PotentialUpdateMap DistMap;
2.249 +
2.250 + static DistMap *createDistMap(const ResGraph&) {
2.251 + return new DistMap();
2.252 + }
2.253 +
2.254 + }; //class ResDijkstraTraits
2.255 +#endif
2.256 +
2.257 + protected:
2.258 +
2.259 + /// \brief The directed graph the algorithm runs on.
2.260 + const Graph &graph;
2.261 + /// \brief The original lower bound map.
2.262 + const LowerMap *lower;
2.263 + /// \brief The modified capacity map.
2.264 + CapacityRefMap capacity;
2.265 + /// \brief The cost map.
2.266 + const CostMap &cost;
2.267 + /// \brief The modified supply map.
2.268 + SupplyRefMap supply;
2.269 + /// \brief The sum of supply values equals zero.
2.270 + bool valid_supply;
2.271 +
2.272 + /// \brief The edge map of the current flow.
2.273 + FlowMap flow;
2.274 + /// \brief The potential node map.
2.275 + PotentialMap potential;
2.276 + /// \brief The residual graph.
2.277 + ResGraph res_graph;
2.278 + /// \brief The reduced cost map.
2.279 + ReducedCostMap red_cost;
2.280 +
2.281 + /// \brief The imbalance map.
2.282 + SupplyRefMap imbalance;
2.283 + /// \brief The excess nodes.
2.284 + std::vector<ResNode> excess_nodes;
2.285 + /// \brief The index of the next excess node.
2.286 + int next_node;
2.287 +
2.288 +#ifdef WITH_SCALING
2.289 + typedef Dijkstra<DeltaResGraph, ReducedCostMap, ResDijkstraTraits>
2.290 + ResDijkstra;
2.291 + /// \brief \ref lemon::Dijkstra "Dijkstra" class for finding
2.292 + /// shortest paths in the residual graph with respect to the
2.293 + /// reduced edge costs.
2.294 + ResDijkstra dijkstra;
2.295 +
2.296 + /// \brief The delta parameter used for capacity scaling.
2.297 + Capacity delta;
2.298 + /// \brief Edge filter map.
2.299 + DeltaFilterMap delta_filter;
2.300 + /// \brief The delta residual graph.
2.301 + DeltaResGraph dres_graph;
2.302 + /// \brief Map for identifing deficit nodes.
2.303 + DeficitBoolMap delta_deficit;
2.304 +
2.305 +#else //WITHOUT_CAPACITY_SCALING
2.306 + typedef Dijkstra<ResGraph, ReducedCostMap, ResDijkstraTraits>
2.307 + ResDijkstra;
2.308 + /// \brief \ref lemon::Dijkstra "Dijkstra" class for finding
2.309 + /// shortest paths in the residual graph with respect to the
2.310 + /// reduced edge costs.
2.311 + ResDijkstra dijkstra;
2.312 + /// \brief Map for identifing deficit nodes.
2.313 + DeficitBoolMap has_deficit;
2.314 +#endif
2.315 +
2.316 + /// \brief Pred map for the \ref lemon::Dijkstra "Dijkstra" class.
2.317 + typename ResDijkstra::PredMap pred;
2.318 + /// \brief Dist map for the \ref lemon::Dijkstra "Dijkstra" class to
2.319 + /// update node potentials.
2.320 + PotentialUpdateMap updater;
2.321 +
2.322 + public :
2.323 +
2.324 + /// \brief General constructor of the class (with lower bounds).
2.325 + ///
2.326 + /// General constructor of the class (with lower bounds).
2.327 + ///
2.328 + /// \param _graph The directed graph the algorithm runs on.
2.329 + /// \param _lower The lower bounds of the edges.
2.330 + /// \param _capacity The capacities (upper bounds) of the edges.
2.331 + /// \param _cost The cost (length) values of the edges.
2.332 + /// \param _supply The supply values of the nodes (signed).
2.333 + CapacityScaling( const Graph &_graph,
2.334 + const LowerMap &_lower,
2.335 + const CapacityMap &_capacity,
2.336 + const CostMap &_cost,
2.337 + const SupplyMap &_supply ) :
2.338 + graph(_graph), lower(&_lower), capacity(_graph), cost(_cost),
2.339 + supply(_graph), flow(_graph, 0), potential(_graph, 0),
2.340 + res_graph(_graph, capacity, flow),
2.341 + red_cost(res_graph, cost, potential), imbalance(_graph),
2.342 +#ifdef WITH_SCALING
2.343 + delta(0), delta_filter(res_graph, delta),
2.344 + dres_graph(res_graph, delta_filter),
2.345 + dijkstra(dres_graph, red_cost), pred(dres_graph),
2.346 + delta_deficit(imbalance, delta)
2.347 +#else //WITHOUT_CAPACITY_SCALING
2.348 + dijkstra(res_graph, red_cost), pred(res_graph),
2.349 + has_deficit(imbalance)
2.350 +#endif
2.351 + {
2.352 + // Removing nonzero lower bounds
2.353 + capacity = subMap(_capacity, _lower);
2.354 + Supply sum = 0;
2.355 + for (NodeIt n(graph); n != INVALID; ++n) {
2.356 + Supply s = _supply[n];
2.357 + for (InEdgeIt e(graph, n); e != INVALID; ++e)
2.358 + s += _lower[e];
2.359 + for (OutEdgeIt e(graph, n); e != INVALID; ++e)
2.360 + s -= _lower[e];
2.361 + supply[n] = imbalance[n] = s;
2.362 + sum += s;
2.363 + }
2.364 + valid_supply = sum == 0;
2.365 + }
2.366 +
2.367 + /// \brief General constructor of the class (without lower bounds).
2.368 + ///
2.369 + /// General constructor of the class (without lower bounds).
2.370 + ///
2.371 + /// \param _graph The directed graph the algorithm runs on.
2.372 + /// \param _capacity The capacities (upper bounds) of the edges.
2.373 + /// \param _cost The cost (length) values of the edges.
2.374 + /// \param _supply The supply values of the nodes (signed).
2.375 + CapacityScaling( const Graph &_graph,
2.376 + const CapacityMap &_capacity,
2.377 + const CostMap &_cost,
2.378 + const SupplyMap &_supply ) :
2.379 + graph(_graph), lower(NULL), capacity(_capacity), cost(_cost),
2.380 + supply(_supply), flow(_graph, 0), potential(_graph, 0),
2.381 + res_graph(_graph, capacity, flow),
2.382 + red_cost(res_graph, cost, potential), imbalance(_graph),
2.383 +#ifdef WITH_SCALING
2.384 + delta(0), delta_filter(res_graph, delta),
2.385 + dres_graph(res_graph, delta_filter),
2.386 + dijkstra(dres_graph, red_cost), pred(dres_graph),
2.387 + delta_deficit(imbalance, delta)
2.388 +#else //WITHOUT_CAPACITY_SCALING
2.389 + dijkstra(res_graph, red_cost), pred(res_graph),
2.390 + has_deficit(imbalance)
2.391 +#endif
2.392 + {
2.393 + // Checking the sum of supply values
2.394 + Supply sum = 0;
2.395 + for (NodeIt n(graph); n != INVALID; ++n) sum += supply[n];
2.396 + valid_supply = sum == 0;
2.397 + }
2.398 +
2.399 + /// \brief Simple constructor of the class (with lower bounds).
2.400 + ///
2.401 + /// Simple constructor of the class (with lower bounds).
2.402 + ///
2.403 + /// \param _graph The directed graph the algorithm runs on.
2.404 + /// \param _lower The lower bounds of the edges.
2.405 + /// \param _capacity The capacities (upper bounds) of the edges.
2.406 + /// \param _cost The cost (length) values of the edges.
2.407 + /// \param _s The source node.
2.408 + /// \param _t The target node.
2.409 + /// \param _flow_value The required amount of flow from node \c _s
2.410 + /// to node \c _t (i.e. the supply of \c _s and the demand of
2.411 + /// \c _t).
2.412 + CapacityScaling( const Graph &_graph,
2.413 + const LowerMap &_lower,
2.414 + const CapacityMap &_capacity,
2.415 + const CostMap &_cost,
2.416 + Node _s, Node _t,
2.417 + Supply _flow_value ) :
2.418 + graph(_graph), lower(&_lower), capacity(_graph), cost(_cost),
2.419 + supply(_graph), flow(_graph, 0), potential(_graph, 0),
2.420 + res_graph(_graph, capacity, flow),
2.421 + red_cost(res_graph, cost, potential), imbalance(_graph),
2.422 +#ifdef WITH_SCALING
2.423 + delta(0), delta_filter(res_graph, delta),
2.424 + dres_graph(res_graph, delta_filter),
2.425 + dijkstra(dres_graph, red_cost), pred(dres_graph),
2.426 + delta_deficit(imbalance, delta)
2.427 +#else //WITHOUT_CAPACITY_SCALING
2.428 + dijkstra(res_graph, red_cost), pred(res_graph),
2.429 + has_deficit(imbalance)
2.430 +#endif
2.431 + {
2.432 + // Removing nonzero lower bounds
2.433 + capacity = subMap(_capacity, _lower);
2.434 + for (NodeIt n(graph); n != INVALID; ++n) {
2.435 + Supply s = 0;
2.436 + if (n == _s) s = _flow_value;
2.437 + if (n == _t) s = -_flow_value;
2.438 + for (InEdgeIt e(graph, n); e != INVALID; ++e)
2.439 + s += _lower[e];
2.440 + for (OutEdgeIt e(graph, n); e != INVALID; ++e)
2.441 + s -= _lower[e];
2.442 + supply[n] = imbalance[n] = s;
2.443 + }
2.444 + valid_supply = true;
2.445 + }
2.446 +
2.447 + /// \brief Simple constructor of the class (without lower bounds).
2.448 + ///
2.449 + /// Simple constructor of the class (without lower bounds).
2.450 + ///
2.451 + /// \param _graph The directed graph the algorithm runs on.
2.452 + /// \param _capacity The capacities (upper bounds) of the edges.
2.453 + /// \param _cost The cost (length) values of the edges.
2.454 + /// \param _s The source node.
2.455 + /// \param _t The target node.
2.456 + /// \param _flow_value The required amount of flow from node \c _s
2.457 + /// to node \c _t (i.e. the supply of \c _s and the demand of
2.458 + /// \c _t).
2.459 + CapacityScaling( const Graph &_graph,
2.460 + const CapacityMap &_capacity,
2.461 + const CostMap &_cost,
2.462 + Node _s, Node _t,
2.463 + Supply _flow_value ) :
2.464 + graph(_graph), lower(NULL), capacity(_capacity), cost(_cost),
2.465 + supply(_graph, 0), flow(_graph, 0), potential(_graph, 0),
2.466 + res_graph(_graph, capacity, flow),
2.467 + red_cost(res_graph, cost, potential), imbalance(_graph),
2.468 +#ifdef WITH_SCALING
2.469 + delta(0), delta_filter(res_graph, delta),
2.470 + dres_graph(res_graph, delta_filter),
2.471 + dijkstra(dres_graph, red_cost), pred(dres_graph),
2.472 + delta_deficit(imbalance, delta)
2.473 +#else //WITHOUT_CAPACITY_SCALING
2.474 + dijkstra(res_graph, red_cost), pred(res_graph),
2.475 + has_deficit(imbalance)
2.476 +#endif
2.477 + {
2.478 + supply[_s] = _flow_value;
2.479 + supply[_t] = -_flow_value;
2.480 + valid_supply = true;
2.481 + }
2.482 +
2.483 + /// \brief Returns a const reference to the flow map.
2.484 + ///
2.485 + /// Returns a const reference to the flow map.
2.486 + ///
2.487 + /// \pre \ref run() must be called before using this function.
2.488 + const FlowMap& flowMap() const {
2.489 + return flow;
2.490 + }
2.491 +
2.492 + /// \brief Returns a const reference to the potential map (the dual
2.493 + /// solution).
2.494 + ///
2.495 + /// Returns a const reference to the potential map (the dual
2.496 + /// solution).
2.497 + ///
2.498 + /// \pre \ref run() must be called before using this function.
2.499 + const PotentialMap& potentialMap() const {
2.500 + return potential;
2.501 + }
2.502 +
2.503 + /// \brief Returns the total cost of the found flow.
2.504 + ///
2.505 + /// Returns the total cost of the found flow. The complexity of the
2.506 + /// function is \f$ O(e) \f$.
2.507 + ///
2.508 + /// \pre \ref run() must be called before using this function.
2.509 + Cost totalCost() const {
2.510 + Cost c = 0;
2.511 + for (EdgeIt e(graph); e != INVALID; ++e)
2.512 + c += flow[e] * cost[e];
2.513 + return c;
2.514 + }
2.515 +
2.516 + /// \brief Runs the successive shortest path algorithm.
2.517 + ///
2.518 + /// Runs the successive shortest path algorithm.
2.519 + ///
2.520 + /// \return \c true if a feasible flow can be found.
2.521 + bool run() {
2.522 + return init() && start();
2.523 + }
2.524 +
2.525 + protected:
2.526 +
2.527 + /// \brief Initializes the algorithm.
2.528 + bool init() {
2.529 + if (!valid_supply) return false;
2.530 +
2.531 + // Initalizing Dijkstra class
2.532 + updater.potentialMap(potential);
2.533 + dijkstra.distMap(updater).predMap(pred);
2.534 +
2.535 +#ifdef WITH_SCALING
2.536 + // Initilaizing delta value
2.537 + Capacity max_cap = 0;
2.538 + for (EdgeIt e(graph); e != INVALID; ++e) {
2.539 + if (capacity[e] > max_cap) max_cap = capacity[e];
2.540 + }
2.541 + for (delta = 1; 2 * delta < max_cap; delta *= 2) ;
2.542 +#endif
2.543 + return true;
2.544 + }
2.545 +
2.546 +#ifdef WITH_SCALING
2.547 + /// \brief Executes the capacity scaling version of the successive
2.548 + /// shortest path algorithm.
2.549 + bool start() {
2.550 + typedef typename DeltaResGraph::EdgeIt DeltaResEdgeIt;
2.551 + typedef typename DeltaResGraph::Edge DeltaResEdge;
2.552 +
2.553 + // Processing capacity scaling phases
2.554 + ResNode s, t;
2.555 + for ( ; delta >= 1; delta = delta < 4 && delta > 1 ?
2.556 + 1 : delta / 4 )
2.557 + {
2.558 + // Saturating edges not satisfying the optimality condition
2.559 + Capacity r;
2.560 + for (DeltaResEdgeIt e(dres_graph); e != INVALID; ++e) {
2.561 + if (red_cost[e] < 0) {
2.562 + res_graph.augment(e, r = res_graph.rescap(e));
2.563 + imbalance[dres_graph.target(e)] += r;
2.564 + imbalance[dres_graph.source(e)] -= r;
2.565 + }
2.566 + }
2.567 +
2.568 + // Finding excess nodes
2.569 + excess_nodes.clear();
2.570 + for (ResNodeIt n(res_graph); n != INVALID; ++n) {
2.571 + if (imbalance[n] >= delta) excess_nodes.push_back(n);
2.572 + }
2.573 + next_node = 0;
2.574 +
2.575 + // Finding successive shortest paths
2.576 + while (next_node < excess_nodes.size()) {
2.577 + // Running Dijkstra
2.578 + s = excess_nodes[next_node];
2.579 + updater.init();
2.580 + dijkstra.init();
2.581 + dijkstra.addSource(s);
2.582 + if ((t = dijkstra.start(delta_deficit)) == INVALID) {
2.583 + if (delta > 1) {
2.584 + ++next_node;
2.585 + continue;
2.586 + }
2.587 + return false;
2.588 + }
2.589 +
2.590 + // Updating node potentials
2.591 + updater.update();
2.592 +
2.593 + // Augment along a shortest path from s to t
2.594 + Capacity d = imbalance[s] < -imbalance[t] ?
2.595 + imbalance[s] : -imbalance[t];
2.596 + ResNode u = t;
2.597 + ResEdge e;
2.598 + if (d > delta) {
2.599 + while ((e = pred[u]) != INVALID) {
2.600 + if (res_graph.rescap(e) < d) d = res_graph.rescap(e);
2.601 + u = dres_graph.source(e);
2.602 + }
2.603 + }
2.604 + u = t;
2.605 + while ((e = pred[u]) != INVALID) {
2.606 + res_graph.augment(e, d);
2.607 + u = dres_graph.source(e);
2.608 + }
2.609 + imbalance[s] -= d;
2.610 + imbalance[t] += d;
2.611 + if (imbalance[s] < delta) ++next_node;
2.612 + }
2.613 + }
2.614 +
2.615 + // Handling nonzero lower bounds
2.616 + if (lower) {
2.617 + for (EdgeIt e(graph); e != INVALID; ++e)
2.618 + flow[e] += (*lower)[e];
2.619 + }
2.620 + return true;
2.621 + }
2.622 +
2.623 +#else //WITHOUT_CAPACITY_SCALING
2.624 + /// \brief Executes the successive shortest path algorithm without
2.625 + /// capacity scaling.
2.626 + bool start() {
2.627 + // Finding excess nodes
2.628 + for (ResNodeIt n(res_graph); n != INVALID; ++n) {
2.629 + if (imbalance[n] > 0) excess_nodes.push_back(n);
2.630 + }
2.631 + if (excess_nodes.size() == 0) return true;
2.632 + next_node = 0;
2.633 +
2.634 + // Finding successive shortest paths
2.635 + ResNode s, t;
2.636 + while ( imbalance[excess_nodes[next_node]] > 0 ||
2.637 + ++next_node < excess_nodes.size() )
2.638 + {
2.639 + // Running Dijkstra
2.640 + s = excess_nodes[next_node];
2.641 + updater.init();
2.642 + dijkstra.init();
2.643 + dijkstra.addSource(s);
2.644 + if ((t = dijkstra.start(has_deficit)) == INVALID)
2.645 + return false;
2.646 +
2.647 + // Updating node potentials
2.648 + updater.update();
2.649 +
2.650 + // Augmenting along a shortest path from s to t
2.651 + Capacity delta = imbalance[s] < -imbalance[t] ?
2.652 + imbalance[s] : -imbalance[t];
2.653 + ResNode u = t;
2.654 + ResEdge e;
2.655 + while ((e = pred[u]) != INVALID) {
2.656 + if (res_graph.rescap(e) < delta) delta = res_graph.rescap(e);
2.657 + u = res_graph.source(e);
2.658 + }
2.659 + u = t;
2.660 + while ((e = pred[u]) != INVALID) {
2.661 + res_graph.augment(e, delta);
2.662 + u = res_graph.source(e);
2.663 + }
2.664 + imbalance[s] -= delta;
2.665 + imbalance[t] += delta;
2.666 + }
2.667 +
2.668 + // Handling nonzero lower bounds
2.669 + if (lower) {
2.670 + for (EdgeIt e(graph); e != INVALID; ++e)
2.671 + flow[e] += (*lower)[e];
2.672 + }
2.673 + return true;
2.674 + }
2.675 +#endif
2.676 +
2.677 + }; //class CapacityScaling
2.678 +
2.679 + ///@}
2.680 +
2.681 +} //namespace lemon
2.682 +
2.683 +#endif //LEMON_CAPACITY_SCALING_H
3.1 --- /dev/null Thu Jan 01 00:00:00 1970 +0000
3.2 +++ b/lemon/cycle_canceling.h Mon May 07 11:42:18 2007 +0000
3.3 @@ -0,0 +1,509 @@
3.4 +/* -*- C++ -*-
3.5 + *
3.6 + * This file is a part of LEMON, a generic C++ optimization library
3.7 + *
3.8 + * Copyright (C) 2003-2007
3.9 + * Egervary Jeno Kombinatorikus Optimalizalasi Kutatocsoport
3.10 + * (Egervary Research Group on Combinatorial Optimization, EGRES).
3.11 + *
3.12 + * Permission to use, modify and distribute this software is granted
3.13 + * provided that this copyright notice appears in all copies. For
3.14 + * precise terms see the accompanying LICENSE file.
3.15 + *
3.16 + * This software is provided "AS IS" with no warranty of any kind,
3.17 + * express or implied, and with no claim as to its suitability for any
3.18 + * purpose.
3.19 + *
3.20 + */
3.21 +
3.22 +#ifndef LEMON_CYCLE_CANCELING_H
3.23 +#define LEMON_CYCLE_CANCELING_H
3.24 +
3.25 +/// \ingroup min_cost_flow
3.26 +///
3.27 +/// \file
3.28 +/// \brief A cycle canceling algorithm for finding a minimum cost flow.
3.29 +
3.30 +#include <vector>
3.31 +#include <lemon/circulation.h>
3.32 +#include <lemon/graph_adaptor.h>
3.33 +
3.34 +/// \brief The used cycle canceling method.
3.35 +#define LIMITED_CYCLE_CANCELING
3.36 +//#define MIN_MEAN_CYCLE_CANCELING
3.37 +
3.38 +#ifdef LIMITED_CYCLE_CANCELING
3.39 + #include <lemon/bellman_ford.h>
3.40 + /// \brief The maximum number of iterations for the first execution
3.41 + /// of the \ref lemon::BellmanFord "Bellman-Ford" algorithm.
3.42 + #define STARTING_LIMIT 2
3.43 + /// \brief The iteration limit for the
3.44 + /// \ref lemon::BellmanFord "Bellman-Ford" algorithm is multiplied by
3.45 + /// <tt>ALPHA_MUL % ALPHA_DIV</tt> in every round.
3.46 + #define ALPHA_MUL 3
3.47 + /// \brief The iteration limit for the
3.48 + /// \ref lemon::BellmanFord "Bellman-Ford" algorithm is multiplied by
3.49 + /// <tt>ALPHA_MUL % ALPHA_DIV</tt> in every round.
3.50 + #define ALPHA_DIV 2
3.51 +
3.52 +//#define _ONLY_ONE_CYCLE_
3.53 +//#define _DEBUG_ITER_
3.54 +#endif
3.55 +
3.56 +#ifdef MIN_MEAN_CYCLE_CANCELING
3.57 + #include <lemon/min_mean_cycle.h>
3.58 + #include <lemon/path.h>
3.59 +#endif
3.60 +
3.61 +namespace lemon {
3.62 +
3.63 + /// \addtogroup min_cost_flow
3.64 + /// @{
3.65 +
3.66 + /// \brief Implementation of a cycle canceling algorithm for finding
3.67 + /// a minimum cost flow.
3.68 + ///
3.69 + /// \ref lemon::CycleCanceling "CycleCanceling" implements a cycle
3.70 + /// canceling algorithm for finding a minimum cost flow.
3.71 + ///
3.72 + /// \param Graph The directed graph type the algorithm runs on.
3.73 + /// \param LowerMap The type of the lower bound map.
3.74 + /// \param CapacityMap The type of the capacity (upper bound) map.
3.75 + /// \param CostMap The type of the cost (length) map.
3.76 + /// \param SupplyMap The type of the supply map.
3.77 + ///
3.78 + /// \warning
3.79 + /// - Edge capacities and costs should be nonnegative integers.
3.80 + /// However \c CostMap::Value should be signed type.
3.81 + /// - Supply values should be integers.
3.82 + /// - \c LowerMap::Value must be convertible to
3.83 + /// \c CapacityMap::Value and \c CapacityMap::Value must be
3.84 + /// convertible to \c SupplyMap::Value.
3.85 + ///
3.86 + /// \author Peter Kovacs
3.87 +
3.88 +template < typename Graph,
3.89 + typename LowerMap = typename Graph::template EdgeMap<int>,
3.90 + typename CapacityMap = LowerMap,
3.91 + typename CostMap = typename Graph::template EdgeMap<int>,
3.92 + typename SupplyMap = typename Graph::template NodeMap
3.93 + <typename CapacityMap::Value> >
3.94 + class CycleCanceling
3.95 + {
3.96 + typedef typename Graph::Node Node;
3.97 + typedef typename Graph::NodeIt NodeIt;
3.98 + typedef typename Graph::Edge Edge;
3.99 + typedef typename Graph::EdgeIt EdgeIt;
3.100 + typedef typename Graph::InEdgeIt InEdgeIt;
3.101 + typedef typename Graph::OutEdgeIt OutEdgeIt;
3.102 +
3.103 + typedef typename LowerMap::Value Lower;
3.104 + typedef typename CapacityMap::Value Capacity;
3.105 + typedef typename CostMap::Value Cost;
3.106 + typedef typename SupplyMap::Value Supply;
3.107 + typedef typename Graph::template EdgeMap<Capacity> CapacityRefMap;
3.108 + typedef typename Graph::template NodeMap<Supply> SupplyRefMap;
3.109 +
3.110 + typedef ResGraphAdaptor< const Graph, Capacity,
3.111 + CapacityRefMap, CapacityRefMap > ResGraph;
3.112 + typedef typename ResGraph::Node ResNode;
3.113 + typedef typename ResGraph::NodeIt ResNodeIt;
3.114 + typedef typename ResGraph::Edge ResEdge;
3.115 + typedef typename ResGraph::EdgeIt ResEdgeIt;
3.116 +
3.117 + public:
3.118 +
3.119 + /// \brief The type of the flow map.
3.120 + typedef CapacityRefMap FlowMap;
3.121 +
3.122 + protected:
3.123 +
3.124 + /// \brief Map adaptor class for demand map.
3.125 + class DemandMap : public MapBase<Node, Supply>
3.126 + {
3.127 + private:
3.128 +
3.129 + const SupplyMap *map;
3.130 +
3.131 + public:
3.132 +
3.133 + typedef typename MapBase<Node, Supply>::Value Value;
3.134 + typedef typename MapBase<Node, Supply>::Key Key;
3.135 +
3.136 + DemandMap(const SupplyMap &_map) : map(&_map) {}
3.137 +
3.138 + Value operator[](const Key &e) const {
3.139 + return -(*map)[e];
3.140 + }
3.141 +
3.142 + }; //class DemandMap
3.143 +
3.144 + /// \brief Map adaptor class for handling residual edge costs.
3.145 + class ResCostMap : public MapBase<ResEdge, Cost>
3.146 + {
3.147 + private:
3.148 +
3.149 + const CostMap &cost_map;
3.150 +
3.151 + public:
3.152 +
3.153 + typedef typename MapBase<ResEdge, Cost>::Value Value;
3.154 + typedef typename MapBase<ResEdge, Cost>::Key Key;
3.155 +
3.156 + ResCostMap(const CostMap &_cost) : cost_map(_cost) {}
3.157 +
3.158 + Value operator[](const Key &e) const {
3.159 + return ResGraph::forward(e) ? cost_map[e] : -cost_map[e];
3.160 + }
3.161 +
3.162 + }; //class ResCostMap
3.163 +
3.164 + protected:
3.165 +
3.166 + /// \brief The directed graph the algorithm runs on.
3.167 + const Graph &graph;
3.168 + /// \brief The original lower bound map.
3.169 + const LowerMap *lower;
3.170 + /// \brief The modified capacity map.
3.171 + CapacityRefMap capacity;
3.172 + /// \brief The cost map.
3.173 + const CostMap &cost;
3.174 + /// \brief The modified supply map.
3.175 + SupplyRefMap supply;
3.176 + /// \brief The modified demand map.
3.177 + DemandMap demand;
3.178 + /// \brief The sum of supply values equals zero.
3.179 + bool valid_supply;
3.180 +
3.181 + /// \brief The current flow.
3.182 + FlowMap flow;
3.183 + /// \brief The residual graph.
3.184 + ResGraph res_graph;
3.185 + /// \brief The residual cost map.
3.186 + ResCostMap res_cost;
3.187 +
3.188 + public :
3.189 +
3.190 + /// \brief General constructor of the class (with lower bounds).
3.191 + ///
3.192 + /// General constructor of the class (with lower bounds).
3.193 + ///
3.194 + /// \param _graph The directed graph the algorithm runs on.
3.195 + /// \param _lower The lower bounds of the edges.
3.196 + /// \param _capacity The capacities (upper bounds) of the edges.
3.197 + /// \param _cost The cost (length) values of the edges.
3.198 + /// \param _supply The supply values of the nodes (signed).
3.199 + CycleCanceling( const Graph &_graph,
3.200 + const LowerMap &_lower,
3.201 + const CapacityMap &_capacity,
3.202 + const CostMap &_cost,
3.203 + const SupplyMap &_supply ) :
3.204 + graph(_graph), lower(&_lower), capacity(_graph), cost(_cost),
3.205 + supply(_graph), demand(supply), flow(_graph, 0),
3.206 + res_graph(_graph, capacity, flow), res_cost(cost)
3.207 + {
3.208 + // Removing nonzero lower bounds
3.209 + capacity = subMap(_capacity, _lower);
3.210 + Supply sum = 0;
3.211 + for (NodeIt n(graph); n != INVALID; ++n) {
3.212 + Supply s = _supply[n];
3.213 + for (InEdgeIt e(graph, n); e != INVALID; ++e)
3.214 + s += _lower[e];
3.215 + for (OutEdgeIt e(graph, n); e != INVALID; ++e)
3.216 + s -= _lower[e];
3.217 + sum += (supply[n] = s);
3.218 + }
3.219 + valid_supply = sum == 0;
3.220 + }
3.221 +
3.222 + /// \brief General constructor of the class (without lower bounds).
3.223 + ///
3.224 + /// General constructor of the class (without lower bounds).
3.225 + ///
3.226 + /// \param _graph The directed graph the algorithm runs on.
3.227 + /// \param _capacity The capacities (upper bounds) of the edges.
3.228 + /// \param _cost The cost (length) values of the edges.
3.229 + /// \param _supply The supply values of the nodes (signed).
3.230 + CycleCanceling( const Graph &_graph,
3.231 + const CapacityMap &_capacity,
3.232 + const CostMap &_cost,
3.233 + const SupplyMap &_supply ) :
3.234 + graph(_graph), lower(NULL), capacity(_capacity), cost(_cost),
3.235 + supply(_supply), demand(supply), flow(_graph, 0),
3.236 + res_graph(_graph, capacity, flow), res_cost(cost)
3.237 + {
3.238 + // Checking the sum of supply values
3.239 + Supply sum = 0;
3.240 + for (NodeIt n(graph); n != INVALID; ++n) sum += supply[n];
3.241 + valid_supply = sum == 0;
3.242 + }
3.243 +
3.244 +
3.245 + /// \brief Simple constructor of the class (with lower bounds).
3.246 + ///
3.247 + /// Simple constructor of the class (with lower bounds).
3.248 + ///
3.249 + /// \param _graph The directed graph the algorithm runs on.
3.250 + /// \param _lower The lower bounds of the edges.
3.251 + /// \param _capacity The capacities (upper bounds) of the edges.
3.252 + /// \param _cost The cost (length) values of the edges.
3.253 + /// \param _s The source node.
3.254 + /// \param _t The target node.
3.255 + /// \param _flow_value The required amount of flow from node \c _s
3.256 + /// to node \c _t (i.e. the supply of \c _s and the demand of
3.257 + /// \c _t).
3.258 + CycleCanceling( const Graph &_graph,
3.259 + const LowerMap &_lower,
3.260 + const CapacityMap &_capacity,
3.261 + const CostMap &_cost,
3.262 + Node _s, Node _t,
3.263 + Supply _flow_value ) :
3.264 + graph(_graph), lower(&_lower), capacity(_graph), cost(_cost),
3.265 + supply(_graph), demand(supply), flow(_graph, 0),
3.266 + res_graph(_graph, capacity, flow), res_cost(cost)
3.267 + {
3.268 + // Removing nonzero lower bounds
3.269 + capacity = subMap(_capacity, _lower);
3.270 + for (NodeIt n(graph); n != INVALID; ++n) {
3.271 + Supply s = 0;
3.272 + if (n == _s) s = _flow_value;
3.273 + if (n == _t) s = -_flow_value;
3.274 + for (InEdgeIt e(graph, n); e != INVALID; ++e)
3.275 + s += _lower[e];
3.276 + for (OutEdgeIt e(graph, n); e != INVALID; ++e)
3.277 + s -= _lower[e];
3.278 + supply[n] = s;
3.279 + }
3.280 + valid_supply = true;
3.281 + }
3.282 +
3.283 + /// \brief Simple constructor of the class (without lower bounds).
3.284 + ///
3.285 + /// Simple constructor of the class (without lower bounds).
3.286 + ///
3.287 + /// \param _graph The directed graph the algorithm runs on.
3.288 + /// \param _capacity The capacities (upper bounds) of the edges.
3.289 + /// \param _cost The cost (length) values of the edges.
3.290 + /// \param _s The source node.
3.291 + /// \param _t The target node.
3.292 + /// \param _flow_value The required amount of flow from node \c _s
3.293 + /// to node \c _t (i.e. the supply of \c _s and the demand of
3.294 + /// \c _t).
3.295 + CycleCanceling( const Graph &_graph,
3.296 + const CapacityMap &_capacity,
3.297 + const CostMap &_cost,
3.298 + Node _s, Node _t,
3.299 + Supply _flow_value ) :
3.300 + graph(_graph), lower(NULL), capacity(_capacity), cost(_cost),
3.301 + supply(_graph, 0), demand(supply), flow(_graph, 0),
3.302 + res_graph(_graph, capacity, flow), res_cost(cost)
3.303 + {
3.304 + supply[_s] = _flow_value;
3.305 + supply[_t] = -_flow_value;
3.306 + valid_supply = true;
3.307 + }
3.308 +
3.309 + /// \brief Returns a const reference to the flow map.
3.310 + ///
3.311 + /// Returns a const reference to the flow map.
3.312 + ///
3.313 + /// \pre \ref run() must be called before using this function.
3.314 + const FlowMap& flowMap() const {
3.315 + return flow;
3.316 + }
3.317 +
3.318 + /// \brief Returns the total cost of the found flow.
3.319 + ///
3.320 + /// Returns the total cost of the found flow. The complexity of the
3.321 + /// function is \f$ O(e) \f$.
3.322 + ///
3.323 + /// \pre \ref run() must be called before using this function.
3.324 + Cost totalCost() const {
3.325 + Cost c = 0;
3.326 + for (EdgeIt e(graph); e != INVALID; ++e)
3.327 + c += flow[e] * cost[e];
3.328 + return c;
3.329 + }
3.330 +
3.331 + /// \brief Runs the algorithm.
3.332 + ///
3.333 + /// Runs the algorithm.
3.334 + ///
3.335 + /// \return \c true if a feasible flow can be found.
3.336 + bool run() {
3.337 + return init() && start();
3.338 + }
3.339 +
3.340 + protected:
3.341 +
3.342 + /// \brief Initializes the algorithm.
3.343 + bool init() {
3.344 + // Checking the sum of supply values
3.345 + Supply sum = 0;
3.346 + for (NodeIt n(graph); n != INVALID; ++n) sum += supply[n];
3.347 + if (sum != 0) return false;
3.348 +
3.349 + // Finding a feasible flow
3.350 + Circulation< Graph, Capacity, FlowMap, ConstMap<Edge, Capacity>,
3.351 + CapacityRefMap, DemandMap >
3.352 + circulation( graph, constMap<Edge>((Capacity)0),
3.353 + capacity, demand, flow );
3.354 + return circulation.run() == -1;
3.355 + }
3.356 +
3.357 +#ifdef LIMITED_CYCLE_CANCELING
3.358 + /// \brief Executes a cycle canceling algorithm using
3.359 + /// \ref lemon::BellmanFord "Bellman-Ford" algorithm with limited
3.360 + /// iteration count.
3.361 + bool start() {
3.362 + typename BellmanFord<ResGraph, ResCostMap>::PredMap pred(res_graph);
3.363 + typename ResGraph::template NodeMap<int> visited(res_graph);
3.364 + std::vector<ResEdge> cycle;
3.365 + int node_num = countNodes(graph);
3.366 +
3.367 +#ifdef _DEBUG_ITER_
3.368 + int cycle_num = 0;
3.369 +#endif
3.370 + int length_bound = STARTING_LIMIT;
3.371 + bool optimal = false;
3.372 + while (!optimal) {
3.373 + BellmanFord<ResGraph, ResCostMap> bf(res_graph, res_cost);
3.374 + bf.predMap(pred);
3.375 + bf.init(0);
3.376 + int iter_num = 0;
3.377 + bool cycle_found = false;
3.378 + while (!cycle_found) {
3.379 + int curr_iter_num = iter_num + length_bound <= node_num ?
3.380 + length_bound : node_num - iter_num;
3.381 + iter_num += curr_iter_num;
3.382 + int real_iter_num = curr_iter_num;
3.383 + for (int i = 0; i < curr_iter_num; ++i) {
3.384 + if (bf.processNextWeakRound()) {
3.385 + real_iter_num = i;
3.386 + break;
3.387 + }
3.388 + }
3.389 + if (real_iter_num < curr_iter_num) {
3.390 + optimal = true;
3.391 + break;
3.392 + } else {
3.393 + // Searching for node disjoint negative cycles
3.394 + for (ResNodeIt n(res_graph); n != INVALID; ++n)
3.395 + visited[n] = 0;
3.396 + int id = 0;
3.397 + for (ResNodeIt n(res_graph); n != INVALID; ++n) {
3.398 + if (visited[n] > 0) continue;
3.399 + visited[n] = ++id;
3.400 + ResNode u = pred[n] == INVALID ?
3.401 + INVALID : res_graph.source(pred[n]);
3.402 + while (u != INVALID && visited[u] == 0) {
3.403 + visited[u] = id;
3.404 + u = pred[u] == INVALID ?
3.405 + INVALID : res_graph.source(pred[u]);
3.406 + }
3.407 + if (u != INVALID && visited[u] == id) {
3.408 + // Finding the negative cycle
3.409 + cycle_found = true;
3.410 + cycle.clear();
3.411 + ResEdge e = pred[u];
3.412 + cycle.push_back(e);
3.413 + Capacity d = res_graph.rescap(e);
3.414 + while (res_graph.source(e) != u) {
3.415 + cycle.push_back(e = pred[res_graph.source(e)]);
3.416 + if (res_graph.rescap(e) < d)
3.417 + d = res_graph.rescap(e);
3.418 + }
3.419 +#ifdef _DEBUG_ITER_
3.420 + ++cycle_num;
3.421 +#endif
3.422 + // Augmenting along the cycle
3.423 + for (int i = 0; i < cycle.size(); ++i)
3.424 + res_graph.augment(cycle[i], d);
3.425 +#ifdef _ONLY_ONE_CYCLE_
3.426 + break;
3.427 +#endif
3.428 + }
3.429 + }
3.430 + }
3.431 +
3.432 + if (!cycle_found)
3.433 + length_bound = length_bound * ALPHA_MUL / ALPHA_DIV;
3.434 + }
3.435 + }
3.436 +
3.437 +#ifdef _DEBUG_ITER_
3.438 + std::cout << "Limited cycle canceling algorithm finished. "
3.439 + << "Found " << cycle_num << " negative cycles."
3.440 + << std::endl;
3.441 +#endif
3.442 +
3.443 + // Handling nonzero lower bounds
3.444 + if (lower) {
3.445 + for (EdgeIt e(graph); e != INVALID; ++e)
3.446 + flow[e] += (*lower)[e];
3.447 + }
3.448 + return true;
3.449 + }
3.450 +#endif
3.451 +
3.452 +#ifdef MIN_MEAN_CYCLE_CANCELING
3.453 + /// \brief Executes the minimum mean cycle canceling algorithm
3.454 + /// using \ref lemon::MinMeanCycle "MinMeanCycle" class.
3.455 + bool start() {
3.456 + typedef Path<ResGraph> ResPath;
3.457 + MinMeanCycle<ResGraph, ResCostMap> mmc(res_graph, res_cost);
3.458 + ResPath cycle;
3.459 +
3.460 +#ifdef _DEBUG_ITER_
3.461 + int cycle_num = 0;
3.462 +#endif
3.463 + mmc.cyclePath(cycle).init();
3.464 + if (mmc.findMinMean()) {
3.465 + while (mmc.cycleLength() < 0) {
3.466 +#ifdef _DEBUG_ITER_
3.467 + ++iter;
3.468 +#endif
3.469 + // Finding the cycle
3.470 + mmc.findCycle();
3.471 +
3.472 + // Finding the largest flow amount that can be augmented
3.473 + // along the cycle
3.474 + Capacity delta = 0;
3.475 + for (typename ResPath::EdgeIt e(cycle); e != INVALID; ++e) {
3.476 + if (delta == 0 || res_graph.rescap(e) < delta)
3.477 + delta = res_graph.rescap(e);
3.478 + }
3.479 +
3.480 + // Augmenting along the cycle
3.481 + for (typename ResPath::EdgeIt e(cycle); e != INVALID; ++e)
3.482 + res_graph.augment(e, delta);
3.483 +
3.484 + // Finding the minimum cycle mean for the modified residual
3.485 + // graph
3.486 + mmc.reset();
3.487 + if (!mmc.findMinMean()) break;
3.488 + }
3.489 + }
3.490 +
3.491 +#ifdef _DEBUG_ITER_
3.492 + std::cout << "Minimum mean cycle canceling algorithm finished. "
3.493 + << "Found " << cycle_num << " negative cycles."
3.494 + << std::endl;
3.495 +#endif
3.496 +
3.497 + // Handling nonzero lower bounds
3.498 + if (lower) {
3.499 + for (EdgeIt e(graph); e != INVALID; ++e)
3.500 + flow[e] += (*lower)[e];
3.501 + }
3.502 + return true;
3.503 + }
3.504 +#endif
3.505 +
3.506 + }; //class CycleCanceling
3.507 +
3.508 + ///@}
3.509 +
3.510 +} //namespace lemon
3.511 +
3.512 +#endif //LEMON_CYCLE_CANCELING_H
4.1 --- /dev/null Thu Jan 01 00:00:00 1970 +0000
4.2 +++ b/lemon/min_cost_flow.h Mon May 07 11:42:18 2007 +0000
4.3 @@ -0,0 +1,127 @@
4.4 +/* -*- C++ -*-
4.5 + *
4.6 + * This file is a part of LEMON, a generic C++ optimization library
4.7 + *
4.8 + * Copyright (C) 2003-2007
4.9 + * Egervary Jeno Kombinatorikus Optimalizalasi Kutatocsoport
4.10 + * (Egervary Research Group on Combinatorial Optimization, EGRES).
4.11 + *
4.12 + * Permission to use, modify and distribute this software is granted
4.13 + * provided that this copyright notice appears in all copies. For
4.14 + * precise terms see the accompanying LICENSE file.
4.15 + *
4.16 + * This software is provided "AS IS" with no warranty of any kind,
4.17 + * express or implied, and with no claim as to its suitability for any
4.18 + * purpose.
4.19 + *
4.20 + */
4.21 +
4.22 +#ifndef LEMON_MIN_COST_FLOW_H
4.23 +#define LEMON_MIN_COST_FLOW_H
4.24 +
4.25 +/// \ingroup min_cost_flow
4.26 +///
4.27 +/// \file
4.28 +/// \brief An efficient algorithm for finding a minimum cost flow.
4.29 +
4.30 +#include <lemon/network_simplex.h>
4.31 +
4.32 +namespace lemon {
4.33 +
4.34 + /// \addtogroup min_cost_flow
4.35 + /// @{
4.36 +
4.37 + /// \brief An efficient algorithm for finding a minimum cost flow.
4.38 + ///
4.39 + /// \ref lemon::MinCostFlow "MinCostFlow" implements an efficient
4.40 + /// algorithm for finding a minimum cost flow.
4.41 + ///
4.42 + /// \note \ref lemon::MinCostFlow "MinCostFlow" is just an alias for
4.43 + /// \ref lemon::NetworkSimplex "NetworkSimplex", wich is the most
4.44 + /// efficient implementation for the minimum cost flow problem in the
4.45 + /// Lemon library according to our benchmark tests.
4.46 + ///
4.47 + /// \note There are three implementations for the minimum cost flow
4.48 + /// problem, that can be used in the same way.
4.49 + /// - \ref lemon::CapacityScaling "CapacityScaling"
4.50 + /// - \ref lemon::CycleCanceling "CycleCanceling"
4.51 + /// - \ref lemon::NetworkSimplex "NetworkSimplex"
4.52 + ///
4.53 + /// \param Graph The directed graph type the algorithm runs on.
4.54 + /// \param LowerMap The type of the lower bound map.
4.55 + /// \param CapacityMap The type of the capacity (upper bound) map.
4.56 + /// \param CostMap The type of the cost (length) map.
4.57 + /// \param SupplyMap The type of the supply map.
4.58 + ///
4.59 + /// \warning
4.60 + /// - Edge capacities and costs should be nonnegative integers.
4.61 + /// However \c CostMap::Value should be signed type.
4.62 + /// - Supply values should be integers.
4.63 + /// - \c LowerMap::Value must be convertible to
4.64 + /// \c CapacityMap::Value and \c CapacityMap::Value must be
4.65 + /// convertible to \c SupplyMap::Value.
4.66 + ///
4.67 + /// \author Peter Kovacs
4.68 +
4.69 +template < typename Graph,
4.70 + typename LowerMap = typename Graph::template EdgeMap<int>,
4.71 + typename CapacityMap = LowerMap,
4.72 + typename CostMap = typename Graph::template EdgeMap<int>,
4.73 + typename SupplyMap = typename Graph::template NodeMap
4.74 + <typename CapacityMap::Value> >
4.75 + class MinCostFlow :
4.76 + public NetworkSimplex< Graph,
4.77 + LowerMap,
4.78 + CapacityMap,
4.79 + CostMap,
4.80 + SupplyMap >
4.81 + {
4.82 + typedef NetworkSimplex< Graph, LowerMap, CapacityMap,
4.83 + CostMap, SupplyMap >
4.84 + MinCostFlowImpl;
4.85 + typedef typename Graph::Node Node;
4.86 + typedef typename SupplyMap::Value Supply;
4.87 +
4.88 + public:
4.89 +
4.90 + /// \brief General constructor of the class (with lower bounds).
4.91 + MinCostFlow( const Graph &_graph,
4.92 + const LowerMap &_lower,
4.93 + const CapacityMap &_capacity,
4.94 + const CostMap &_cost,
4.95 + const SupplyMap &_supply ) :
4.96 + MinCostFlowImpl(_graph, _lower, _capacity, _cost, _supply) {}
4.97 +
4.98 + /// \brief General constructor of the class (without lower bounds).
4.99 + MinCostFlow( const Graph &_graph,
4.100 + const CapacityMap &_capacity,
4.101 + const CostMap &_cost,
4.102 + const SupplyMap &_supply ) :
4.103 + MinCostFlowImpl(_graph, _capacity, _cost, _supply) {}
4.104 +
4.105 + /// \brief Simple constructor of the class (with lower bounds).
4.106 + MinCostFlow( const Graph &_graph,
4.107 + const LowerMap &_lower,
4.108 + const CapacityMap &_capacity,
4.109 + const CostMap &_cost,
4.110 + Node _s, Node _t,
4.111 + Supply _flow_value ) :
4.112 + MinCostFlowImpl( _graph, _lower, _capacity, _cost,
4.113 + _s, _t, _flow_value ) {}
4.114 +
4.115 + /// \brief Simple constructor of the class (without lower bounds).
4.116 + MinCostFlow( const Graph &_graph,
4.117 + const CapacityMap &_capacity,
4.118 + const CostMap &_cost,
4.119 + Node _s, Node _t,
4.120 + Supply _flow_value ) :
4.121 + MinCostFlowImpl( _graph, _capacity, _cost,
4.122 + _s, _t, _flow_value ) {}
4.123 +
4.124 + }; //class MinCostFlow
4.125 +
4.126 + ///@}
4.127 +
4.128 +} //namespace lemon
4.129 +
4.130 +#endif //LEMON_MIN_COST_FLOW_H
5.1 --- /dev/null Thu Jan 01 00:00:00 1970 +0000
5.2 +++ b/lemon/min_cost_max_flow.h Mon May 07 11:42:18 2007 +0000
5.3 @@ -0,0 +1,156 @@
5.4 +/* -*- C++ -*-
5.5 + *
5.6 + * This file is a part of LEMON, a generic C++ optimization library
5.7 + *
5.8 + * Copyright (C) 2003-2007
5.9 + * Egervary Jeno Kombinatorikus Optimalizalasi Kutatocsoport
5.10 + * (Egervary Research Group on Combinatorial Optimization, EGRES).
5.11 + *
5.12 + * Permission to use, modify and distribute this software is granted
5.13 + * provided that this copyright notice appears in all copies. For
5.14 + * precise terms see the accompanying LICENSE file.
5.15 + *
5.16 + * This software is provided "AS IS" with no warranty of any kind,
5.17 + * express or implied, and with no claim as to its suitability for any
5.18 + * purpose.
5.19 + *
5.20 + */
5.21 +
5.22 +#ifndef LEMON_MIN_COST_MAX_FLOW_H
5.23 +#define LEMON_MIN_COST_MAX_FLOW_H
5.24 +
5.25 +/// \ingroup min_cost_flow
5.26 +///
5.27 +/// \file
5.28 +/// \brief An efficient algorithm for finding a minimum cost maximum
5.29 +/// flow.
5.30 +
5.31 +#include <lemon/preflow.h>
5.32 +#include <lemon/network_simplex.h>
5.33 +#include <lemon/maps.h>
5.34 +
5.35 +namespace lemon {
5.36 +
5.37 + /// \addtogroup min_cost_flow
5.38 + /// @{
5.39 +
5.40 + /// \brief An efficient algorithm for finding a minimum cost maximum
5.41 + /// flow.
5.42 + ///
5.43 + /// \ref lemon::MinCostFlow "MinCostMaxFlow" implements an efficient
5.44 + /// algorithm for finding a maximum flow having minimal total cost
5.45 + /// from a given source node to a given target node in a directed
5.46 + /// graph.
5.47 + ///
5.48 + /// \note \ref lemon::MinCostMaxFlow "MinCostMaxFlow" uses
5.49 + /// \ref lemon::Preflow "Preflow" algorithm for finding the maximum
5.50 + /// flow value and \ref lemon::NetworkSimplex "NetworkSimplex"
5.51 + /// algorithm for finding a minimum cost flow of that value.
5.52 + ///
5.53 + /// \param Graph The directed graph type the algorithm runs on.
5.54 + /// \param CapacityMap The type of the capacity (upper bound) map.
5.55 + /// \param CostMap The type of the cost (length) map.
5.56 + ///
5.57 + /// \warning
5.58 + /// - Edge capacities and costs should be nonnegative integers.
5.59 + /// However \c CostMap::Value should be signed type.
5.60 + ///
5.61 + /// \author Peter Kovacs
5.62 +
5.63 +template < typename Graph,
5.64 + typename CapacityMap = typename Graph::template EdgeMap<int>,
5.65 + typename CostMap = typename Graph::template EdgeMap<int> >
5.66 + class MinCostMaxFlow
5.67 + {
5.68 + typedef typename Graph::Node Node;
5.69 + typedef typename Graph::Edge Edge;
5.70 +
5.71 + typedef typename CapacityMap::Value Capacity;
5.72 + typedef typename Graph::template NodeMap<Capacity> SupplyMap;
5.73 + typedef NetworkSimplex< Graph, CapacityMap, CapacityMap,
5.74 + CostMap, SupplyMap >
5.75 + MinCostFlowImpl;
5.76 +
5.77 + public:
5.78 +
5.79 + /// \brief The type of the flow map.
5.80 + typedef typename Graph::template EdgeMap<Capacity> FlowMap;
5.81 +
5.82 + private:
5.83 +
5.84 + /// \brief The directed graph the algorithm runs on.
5.85 + const Graph &graph;
5.86 + /// \brief The modified capacity map.
5.87 + const CapacityMap &capacity;
5.88 + /// \brief The cost map.
5.89 + const CostMap &cost;
5.90 + /// \brief The source node.
5.91 + Node source;
5.92 + /// \brief The target node.
5.93 + Node target;
5.94 + /// \brief The edge map of the found flow.
5.95 + FlowMap flow;
5.96 +
5.97 + typedef Preflow<Graph, Capacity, CapacityMap, FlowMap> PreflowImpl;
5.98 + /// \brief \ref lemon::Preflow "Preflow" class for finding the
5.99 + /// maximum flow value.
5.100 + PreflowImpl preflow;
5.101 +
5.102 + public:
5.103 +
5.104 + /// \brief The constructor of the class.
5.105 + ///
5.106 + /// The constructor of the class.
5.107 + ///
5.108 + /// \param _graph The directed graph the algorithm runs on.
5.109 + /// \param _capacity The capacities (upper bounds) of the edges.
5.110 + /// \param _cost The cost (length) values of the edges.
5.111 + /// \param _s The source node.
5.112 + /// \param _t The target node.
5.113 + MinCostMaxFlow( const Graph &_graph,
5.114 + const CapacityMap &_capacity,
5.115 + const CostMap &_cost,
5.116 + Node _s, Node _t ) :
5.117 + graph(_graph), capacity(_capacity), cost(_cost),
5.118 + source(_s), target(_t), flow(_graph),
5.119 + preflow(_graph, _s, _t, _capacity, flow)
5.120 + {}
5.121 +
5.122 + /// \brief Returns a const reference to the flow map.
5.123 + ///
5.124 + /// Returns a const reference to the flow map.
5.125 + ///
5.126 + /// \pre \ref run() must be called before using this function.
5.127 + const FlowMap& flowMap() const {
5.128 + return flow;
5.129 + }
5.130 +
5.131 + /// \brief Returns the total cost of the found flow.
5.132 + ///
5.133 + /// Returns the total cost of the found flow. The complexity of the
5.134 + /// function is \f$ O(e) \f$.
5.135 + ///
5.136 + /// \pre \ref run() must be called before using this function.
5.137 + Cost totalCost() const {
5.138 + Cost c = 0;
5.139 + for (EdgeIt e(graph); e != INVALID; ++e)
5.140 + c += flow[e] * cost[e];
5.141 + return c;
5.142 + }
5.143 +
5.144 + /// \brief Runs the algorithm.
5.145 + void run() {
5.146 + preflow.phase1();
5.147 + MinCostFlowImpl mcf_impl( graph, capacity, cost,
5.148 + source, target, preflow.flowValue() );
5.149 + mcf_impl.run();
5.150 + flow = mcf_impl.flowMap();
5.151 + }
5.152 +
5.153 + }; //class MinCostMaxFlow
5.154 +
5.155 + ///@}
5.156 +
5.157 +} //namespace lemon
5.158 +
5.159 +#endif //LEMON_MIN_COST_MAX_FLOW_H
6.1 --- /dev/null Thu Jan 01 00:00:00 1970 +0000
6.2 +++ b/lemon/network_simplex.h Mon May 07 11:42:18 2007 +0000
6.3 @@ -0,0 +1,945 @@
6.4 +/* -*- C++ -*-
6.5 + *
6.6 + * This file is a part of LEMON, a generic C++ optimization library
6.7 + *
6.8 + * Copyright (C) 2003-2007
6.9 + * Egervary Jeno Kombinatorikus Optimalizalasi Kutatocsoport
6.10 + * (Egervary Research Group on Combinatorial Optimization, EGRES).
6.11 + *
6.12 + * Permission to use, modify and distribute this software is granted
6.13 + * provided that this copyright notice appears in all copies. For
6.14 + * precise terms see the accompanying LICENSE file.
6.15 + *
6.16 + * This software is provided "AS IS" with no warranty of any kind,
6.17 + * express or implied, and with no claim as to its suitability for any
6.18 + * purpose.
6.19 + *
6.20 + */
6.21 +
6.22 +#ifndef LEMON_NETWORK_SIMPLEX_H
6.23 +#define LEMON_NETWORK_SIMPLEX_H
6.24 +
6.25 +/// \ingroup min_cost_flow
6.26 +///
6.27 +/// \file
6.28 +/// \brief The network simplex algorithm for finding a minimum cost
6.29 +/// flow.
6.30 +
6.31 +#include <limits>
6.32 +#include <lemon/smart_graph.h>
6.33 +#include <lemon/graph_utils.h>
6.34 +
6.35 +/// \brief The pivot rule used in the algorithm.
6.36 +#define EDGE_BLOCK_PIVOT
6.37 +//#define FIRST_ELIGIBLE_PIVOT
6.38 +//#define BEST_ELIGIBLE_PIVOT
6.39 +//#define CANDIDATE_LIST_PIVOT
6.40 +//#define SORTED_LIST_PIVOT
6.41 +
6.42 +/// \brief State constant for edges at their lower bounds.
6.43 +#define LOWER 1
6.44 +/// \brief State constant for edges in the spanning tree.
6.45 +#define TREE 0
6.46 +/// \brief State constant for edges at their upper bounds.
6.47 +#define UPPER -1
6.48 +
6.49 +#ifdef EDGE_BLOCK_PIVOT
6.50 + /// \brief Number of blocks for the "Edge Block" pivot rule.
6.51 + #define BLOCK_NUM 100
6.52 + /// \brief Lower bound for the number of edges to use "Edge Block"
6.53 + // pivot rule instead of "First Eligible" pivot rule.
6.54 + #define MIN_BOUND 1000
6.55 +#endif
6.56 +
6.57 +#ifdef CANDIDATE_LIST_PIVOT
6.58 + #include <list>
6.59 + /// \brief The maximum length of the edge list for the
6.60 + /// "Candidate List" pivot rule.
6.61 + #define LIST_LENGTH 100
6.62 + /// \brief The maximum number of minor iterations between two major
6.63 + /// itarations.
6.64 + #define MINOR_LIMIT 50
6.65 +#endif
6.66 +
6.67 +#ifdef SORTED_LIST_PIVOT
6.68 + #include <deque>
6.69 + #include <algorithm>
6.70 + /// \brief The maximum length of the edge list for the
6.71 + /// "Sorted List" pivot rule.
6.72 + #define LIST_LENGTH 500
6.73 + #define LOWER_DIV 4
6.74 +#endif
6.75 +
6.76 +//#define _DEBUG_ITER_
6.77 +
6.78 +namespace lemon {
6.79 +
6.80 + /// \addtogroup min_cost_flow
6.81 + /// @{
6.82 +
6.83 + /// \brief Implementation of the network simplex algorithm for
6.84 + /// finding a minimum cost flow.
6.85 + ///
6.86 + /// \ref lemon::NetworkSimplex "NetworkSimplex" implements the
6.87 + /// network simplex algorithm for finding a minimum cost flow.
6.88 + ///
6.89 + /// \param Graph The directed graph type the algorithm runs on.
6.90 + /// \param LowerMap The type of the lower bound map.
6.91 + /// \param CapacityMap The type of the capacity (upper bound) map.
6.92 + /// \param CostMap The type of the cost (length) map.
6.93 + /// \param SupplyMap The type of the supply map.
6.94 + ///
6.95 + /// \warning
6.96 + /// - Edge capacities and costs should be nonnegative integers.
6.97 + /// However \c CostMap::Value should be signed type.
6.98 + /// - Supply values should be integers.
6.99 + /// - \c LowerMap::Value must be convertible to
6.100 + /// \c CapacityMap::Value and \c CapacityMap::Value must be
6.101 + /// convertible to \c SupplyMap::Value.
6.102 + ///
6.103 + /// \author Peter Kovacs
6.104 +
6.105 +template < typename Graph,
6.106 + typename LowerMap = typename Graph::template EdgeMap<int>,
6.107 + typename CapacityMap = LowerMap,
6.108 + typename CostMap = typename Graph::template EdgeMap<int>,
6.109 + typename SupplyMap = typename Graph::template NodeMap
6.110 + <typename CapacityMap::Value> >
6.111 + class NetworkSimplex
6.112 + {
6.113 + typedef typename LowerMap::Value Lower;
6.114 + typedef typename CapacityMap::Value Capacity;
6.115 + typedef typename CostMap::Value Cost;
6.116 + typedef typename SupplyMap::Value Supply;
6.117 +
6.118 + typedef SmartGraph SGraph;
6.119 + typedef typename SGraph::Node Node;
6.120 + typedef typename SGraph::NodeIt NodeIt;
6.121 + typedef typename SGraph::Edge Edge;
6.122 + typedef typename SGraph::EdgeIt EdgeIt;
6.123 + typedef typename SGraph::InEdgeIt InEdgeIt;
6.124 + typedef typename SGraph::OutEdgeIt OutEdgeIt;
6.125 +
6.126 + typedef typename SGraph::template EdgeMap<Lower> SLowerMap;
6.127 + typedef typename SGraph::template EdgeMap<Capacity> SCapacityMap;
6.128 + typedef typename SGraph::template EdgeMap<Cost> SCostMap;
6.129 + typedef typename SGraph::template NodeMap<Supply> SSupplyMap;
6.130 + typedef typename SGraph::template NodeMap<Cost> SPotentialMap;
6.131 +
6.132 + typedef typename SGraph::template NodeMap<int> IntNodeMap;
6.133 + typedef typename SGraph::template NodeMap<bool> BoolNodeMap;
6.134 + typedef typename SGraph::template NodeMap<Node> NodeNodeMap;
6.135 + typedef typename SGraph::template NodeMap<Edge> EdgeNodeMap;
6.136 + typedef typename SGraph::template EdgeMap<int> IntEdgeMap;
6.137 +
6.138 + typedef typename Graph::template NodeMap<Node> NodeRefMap;
6.139 + typedef typename Graph::template EdgeMap<Edge> EdgeRefMap;
6.140 +
6.141 + public:
6.142 +
6.143 + /// \brief The type of the flow map.
6.144 + typedef typename Graph::template EdgeMap<Capacity> FlowMap;
6.145 + /// \brief The type of the potential map.
6.146 + typedef typename Graph::template NodeMap<Cost> PotentialMap;
6.147 +
6.148 + protected:
6.149 +
6.150 + /// \brief Map adaptor class for handling reduced edge costs.
6.151 + class ReducedCostMap : public MapBase<Edge, Cost>
6.152 + {
6.153 + private:
6.154 +
6.155 + const SGraph &gr;
6.156 + const SCostMap &cost_map;
6.157 + const SPotentialMap &pot_map;
6.158 +
6.159 + public:
6.160 +
6.161 + typedef typename MapBase<Edge, Cost>::Value Value;
6.162 + typedef typename MapBase<Edge, Cost>::Key Key;
6.163 +
6.164 + ReducedCostMap( const SGraph &_gr,
6.165 + const SCostMap &_cm,
6.166 + const SPotentialMap &_pm ) :
6.167 + gr(_gr), cost_map(_cm), pot_map(_pm) {}
6.168 +
6.169 + Value operator[](const Key &e) const {
6.170 + return cost_map[e] - pot_map[gr.source(e)] + pot_map[gr.target(e)];
6.171 + }
6.172 +
6.173 + }; //class ReducedCostMap
6.174 +
6.175 + protected:
6.176 +
6.177 + /// \brief The directed graph the algorithm runs on.
6.178 + SGraph graph;
6.179 + /// \brief The original graph.
6.180 + const Graph &graph_ref;
6.181 + /// \brief The original lower bound map.
6.182 + const LowerMap *lower;
6.183 + /// \brief The capacity map.
6.184 + SCapacityMap capacity;
6.185 + /// \brief The cost map.
6.186 + SCostMap cost;
6.187 + /// \brief The supply map.
6.188 + SSupplyMap supply;
6.189 + /// \brief The reduced cost map.
6.190 + ReducedCostMap red_cost;
6.191 + /// \brief The sum of supply values equals zero.
6.192 + bool valid_supply;
6.193 +
6.194 + /// \brief The edge map of the current flow.
6.195 + SCapacityMap flow;
6.196 + /// \brief The edge map of the found flow on the original graph.
6.197 + FlowMap flow_result;
6.198 + /// \brief The potential node map.
6.199 + SPotentialMap potential;
6.200 + /// \brief The potential node map on the original graph.
6.201 + PotentialMap potential_result;
6.202 +
6.203 + /// \brief Node reference for the original graph.
6.204 + NodeRefMap node_ref;
6.205 + /// \brief Edge reference for the original graph.
6.206 + EdgeRefMap edge_ref;
6.207 +
6.208 + /// \brief The depth node map of the spanning tree structure.
6.209 + IntNodeMap depth;
6.210 + /// \brief The parent node map of the spanning tree structure.
6.211 + NodeNodeMap parent;
6.212 + /// \brief The pred_edge node map of the spanning tree structure.
6.213 + EdgeNodeMap pred_edge;
6.214 + /// \brief The thread node map of the spanning tree structure.
6.215 + NodeNodeMap thread;
6.216 + /// \brief The forward node map of the spanning tree structure.
6.217 + BoolNodeMap forward;
6.218 + /// \brief The state edge map.
6.219 + IntEdgeMap state;
6.220 +
6.221 +
6.222 +#ifdef EDGE_BLOCK_PIVOT
6.223 + /// \brief The size of blocks for the "Edge Block" pivot rule.
6.224 + int block_size;
6.225 +#endif
6.226 +#ifdef CANDIDATE_LIST_PIVOT
6.227 + /// \brief The list of candidate edges for the "Candidate List"
6.228 + /// pivot rule.
6.229 + std::list<Edge> candidates;
6.230 + /// \brief The number of minor iterations.
6.231 + int minor_count;
6.232 +#endif
6.233 +#ifdef SORTED_LIST_PIVOT
6.234 + /// \brief The list of candidate edges for the "Sorted List"
6.235 + /// pivot rule.
6.236 + std::deque<Edge> candidates;
6.237 +#endif
6.238 +
6.239 + // Root node of the starting spanning tree.
6.240 + Node root;
6.241 + // The entering edge of the current pivot iteration.
6.242 + Edge in_edge;
6.243 + // Temporary nodes used in the current pivot iteration.
6.244 + Node join, u_in, v_in, u_out, v_out;
6.245 + Node right, first, second, last;
6.246 + Node stem, par_stem, new_stem;
6.247 + // The maximum augment amount along the cycle in the current pivot
6.248 + // iteration.
6.249 + Capacity delta;
6.250 +
6.251 + public :
6.252 +
6.253 + /// \brief General constructor of the class (with lower bounds).
6.254 + ///
6.255 + /// General constructor of the class (with lower bounds).
6.256 + ///
6.257 + /// \param _graph The directed graph the algorithm runs on.
6.258 + /// \param _lower The lower bounds of the edges.
6.259 + /// \param _capacity The capacities (upper bounds) of the edges.
6.260 + /// \param _cost The cost (length) values of the edges.
6.261 + /// \param _supply The supply values of the nodes (signed).
6.262 + NetworkSimplex( const Graph &_graph,
6.263 + const LowerMap &_lower,
6.264 + const CapacityMap &_capacity,
6.265 + const CostMap &_cost,
6.266 + const SupplyMap &_supply ) :
6.267 + graph_ref(_graph), lower(&_lower), capacity(graph), cost(graph),
6.268 + supply(graph), flow(graph), flow_result(_graph), potential(graph),
6.269 + potential_result(_graph), depth(graph), parent(graph),
6.270 + pred_edge(graph), thread(graph), forward(graph), state(graph),
6.271 + node_ref(graph_ref), edge_ref(graph_ref),
6.272 + red_cost(graph, cost, potential)
6.273 + {
6.274 + // Checking the sum of supply values
6.275 + Supply sum = 0;
6.276 + for (typename Graph::NodeIt n(graph_ref); n != INVALID; ++n)
6.277 + sum += _supply[n];
6.278 + if (!(valid_supply = sum == 0)) return;
6.279 +
6.280 + // Copying graph_ref to graph
6.281 + copyGraph(graph, graph_ref)
6.282 + .edgeMap(cost, _cost)
6.283 + .nodeRef(node_ref)
6.284 + .edgeRef(edge_ref)
6.285 + .run();
6.286 +
6.287 + // Removing nonzero lower bounds
6.288 + for (typename Graph::EdgeIt e(graph_ref); e != INVALID; ++e) {
6.289 + capacity[edge_ref[e]] = _capacity[e] - _lower[e];
6.290 + }
6.291 + for (typename Graph::NodeIt n(graph_ref); n != INVALID; ++n) {
6.292 + Supply s = _supply[n];
6.293 + for (typename Graph::InEdgeIt e(graph_ref, n); e != INVALID; ++e)
6.294 + s += _lower[e];
6.295 + for (typename Graph::OutEdgeIt e(graph_ref, n); e != INVALID; ++e)
6.296 + s -= _lower[e];
6.297 + supply[node_ref[n]] = s;
6.298 + }
6.299 + }
6.300 +
6.301 + /// \brief General constructor of the class (without lower bounds).
6.302 + ///
6.303 + /// General constructor of the class (without lower bounds).
6.304 + ///
6.305 + /// \param _graph The directed graph the algorithm runs on.
6.306 + /// \param _capacity The capacities (upper bounds) of the edges.
6.307 + /// \param _cost The cost (length) values of the edges.
6.308 + /// \param _supply The supply values of the nodes (signed).
6.309 + NetworkSimplex( const Graph &_graph,
6.310 + const CapacityMap &_capacity,
6.311 + const CostMap &_cost,
6.312 + const SupplyMap &_supply ) :
6.313 + graph_ref(_graph), lower(NULL), capacity(graph), cost(graph),
6.314 + supply(graph), flow(graph), flow_result(_graph), potential(graph),
6.315 + potential_result(_graph), depth(graph), parent(graph),
6.316 + pred_edge(graph), thread(graph), forward(graph), state(graph),
6.317 + node_ref(graph_ref), edge_ref(graph_ref),
6.318 + red_cost(graph, cost, potential)
6.319 + {
6.320 + // Checking the sum of supply values
6.321 + Supply sum = 0;
6.322 + for (typename Graph::NodeIt n(graph_ref); n != INVALID; ++n)
6.323 + sum += _supply[n];
6.324 + if (!(valid_supply = sum == 0)) return;
6.325 +
6.326 + // Copying graph_ref to graph
6.327 + copyGraph(graph, graph_ref)
6.328 + .edgeMap(capacity, _capacity)
6.329 + .edgeMap(cost, _cost)
6.330 + .nodeMap(supply, _supply)
6.331 + .nodeRef(node_ref)
6.332 + .edgeRef(edge_ref)
6.333 + .run();
6.334 + }
6.335 +
6.336 + /// \brief Simple constructor of the class (with lower bounds).
6.337 + ///
6.338 + /// Simple constructor of the class (with lower bounds).
6.339 + ///
6.340 + /// \param _graph The directed graph the algorithm runs on.
6.341 + /// \param _lower The lower bounds of the edges.
6.342 + /// \param _capacity The capacities (upper bounds) of the edges.
6.343 + /// \param _cost The cost (length) values of the edges.
6.344 + /// \param _s The source node.
6.345 + /// \param _t The target node.
6.346 + /// \param _flow_value The required amount of flow from node \c _s
6.347 + /// to node \c _t (i.e. the supply of \c _s and the demand of
6.348 + /// \c _t).
6.349 + NetworkSimplex( const Graph &_graph,
6.350 + const LowerMap &_lower,
6.351 + const CapacityMap &_capacity,
6.352 + const CostMap &_cost,
6.353 + typename Graph::Node _s,
6.354 + typename Graph::Node _t,
6.355 + typename SupplyMap::Value _flow_value ) :
6.356 + graph_ref(_graph), lower(&_lower), capacity(graph), cost(graph),
6.357 + supply(graph), flow(graph), flow_result(_graph), potential(graph),
6.358 + potential_result(_graph), depth(graph), parent(graph),
6.359 + pred_edge(graph), thread(graph), forward(graph), state(graph),
6.360 + node_ref(graph_ref), edge_ref(graph_ref),
6.361 + red_cost(graph, cost, potential)
6.362 + {
6.363 + // Copying graph_ref to graph
6.364 + copyGraph(graph, graph_ref)
6.365 + .edgeMap(cost, _cost)
6.366 + .nodeRef(node_ref)
6.367 + .edgeRef(edge_ref)
6.368 + .run();
6.369 +
6.370 + // Removing nonzero lower bounds
6.371 + for (typename Graph::EdgeIt e(graph_ref); e != INVALID; ++e) {
6.372 + capacity[edge_ref[e]] = _capacity[e] - _lower[e];
6.373 + }
6.374 + for (typename Graph::NodeIt n(graph_ref); n != INVALID; ++n) {
6.375 + Supply s = 0;
6.376 + if (n == _s) s = _flow_value;
6.377 + if (n == _t) s = -_flow_value;
6.378 + for (typename Graph::InEdgeIt e(graph_ref, n); e != INVALID; ++e)
6.379 + s += _lower[e];
6.380 + for (typename Graph::OutEdgeIt e(graph_ref, n); e != INVALID; ++e)
6.381 + s -= _lower[e];
6.382 + supply[node_ref[n]] = s;
6.383 + }
6.384 + valid_supply = true;
6.385 + }
6.386 +
6.387 + /// \brief Simple constructor of the class (without lower bounds).
6.388 + ///
6.389 + /// Simple constructor of the class (without lower bounds).
6.390 + ///
6.391 + /// \param _graph The directed graph the algorithm runs on.
6.392 + /// \param _capacity The capacities (upper bounds) of the edges.
6.393 + /// \param _cost The cost (length) values of the edges.
6.394 + /// \param _s The source node.
6.395 + /// \param _t The target node.
6.396 + /// \param _flow_value The required amount of flow from node \c _s
6.397 + /// to node \c _t (i.e. the supply of \c _s and the demand of
6.398 + /// \c _t).
6.399 + NetworkSimplex( const Graph &_graph,
6.400 + const CapacityMap &_capacity,
6.401 + const CostMap &_cost,
6.402 + typename Graph::Node _s,
6.403 + typename Graph::Node _t,
6.404 + typename SupplyMap::Value _flow_value ) :
6.405 + graph_ref(_graph), lower(NULL), capacity(graph), cost(graph),
6.406 + supply(graph, 0), flow(graph), flow_result(_graph), potential(graph),
6.407 + potential_result(_graph), depth(graph), parent(graph),
6.408 + pred_edge(graph), thread(graph), forward(graph), state(graph),
6.409 + node_ref(graph_ref), edge_ref(graph_ref),
6.410 + red_cost(graph, cost, potential)
6.411 + {
6.412 + // Copying graph_ref to graph
6.413 + copyGraph(graph, graph_ref)
6.414 + .edgeMap(capacity, _capacity)
6.415 + .edgeMap(cost, _cost)
6.416 + .nodeRef(node_ref)
6.417 + .edgeRef(edge_ref)
6.418 + .run();
6.419 + supply[node_ref[_s]] = _flow_value;
6.420 + supply[node_ref[_t]] = -_flow_value;
6.421 + valid_supply = true;
6.422 + }
6.423 +
6.424 + /// \brief Returns a const reference to the flow map.
6.425 + ///
6.426 + /// Returns a const reference to the flow map.
6.427 + ///
6.428 + /// \pre \ref run() must be called before using this function.
6.429 + const FlowMap& flowMap() const {
6.430 + return flow_result;
6.431 + }
6.432 +
6.433 + /// \brief Returns a const reference to the potential map (the dual
6.434 + /// solution).
6.435 + ///
6.436 + /// Returns a const reference to the potential map (the dual
6.437 + /// solution).
6.438 + ///
6.439 + /// \pre \ref run() must be called before using this function.
6.440 + const PotentialMap& potentialMap() const {
6.441 + return potential_result;
6.442 + }
6.443 +
6.444 + /// \brief Returns the total cost of the found flow.
6.445 + ///
6.446 + /// Returns the total cost of the found flow. The complexity of the
6.447 + /// function is \f$ O(e) \f$.
6.448 + ///
6.449 + /// \pre \ref run() must be called before using this function.
6.450 + Cost totalCost() const {
6.451 + Cost c = 0;
6.452 + for (typename Graph::EdgeIt e(graph_ref); e != INVALID; ++e)
6.453 + c += flow_result[e] * cost[edge_ref[e]];
6.454 + return c;
6.455 + }
6.456 +
6.457 + /// \brief Runs the algorithm.
6.458 + ///
6.459 + /// Runs the algorithm.
6.460 + ///
6.461 + /// \return \c true if a feasible flow can be found.
6.462 + bool run() {
6.463 + return init() && start();
6.464 + }
6.465 +
6.466 + protected:
6.467 +
6.468 + /// \brief Extends the underlaying graph and initializes all the
6.469 + /// node and edge maps.
6.470 + bool init() {
6.471 + if (!valid_supply) return false;
6.472 +
6.473 + // Initializing state and flow maps
6.474 + for (EdgeIt e(graph); e != INVALID; ++e) {
6.475 + flow[e] = 0;
6.476 + state[e] = LOWER;
6.477 + }
6.478 +
6.479 + // Adding an artificial root node to the graph
6.480 + root = graph.addNode();
6.481 + parent[root] = INVALID;
6.482 + pred_edge[root] = INVALID;
6.483 + depth[root] = supply[root] = potential[root] = 0;
6.484 +
6.485 + // Adding artificial edges to the graph and initializing the node
6.486 + // maps of the spanning tree data structure
6.487 + Supply sum = 0;
6.488 + Node last = root;
6.489 + Edge e;
6.490 + Cost max_cost = std::numeric_limits<Cost>::max() / 4;
6.491 + for (NodeIt u(graph); u != INVALID; ++u) {
6.492 + if (u == root) continue;
6.493 + thread[last] = u;
6.494 + last = u;
6.495 + parent[u] = root;
6.496 + depth[u] = 1;
6.497 + sum += supply[u];
6.498 + if (supply[u] >= 0) {
6.499 + e = graph.addEdge(u, root);
6.500 + flow[e] = supply[u];
6.501 + forward[u] = true;
6.502 + potential[u] = max_cost;
6.503 + } else {
6.504 + e = graph.addEdge(root, u);
6.505 + flow[e] = -supply[u];
6.506 + forward[u] = false;
6.507 + potential[u] = -max_cost;
6.508 + }
6.509 + cost[e] = max_cost;
6.510 + capacity[e] = std::numeric_limits<Capacity>::max();
6.511 + state[e] = TREE;
6.512 + pred_edge[u] = e;
6.513 + }
6.514 + thread[last] = root;
6.515 +
6.516 +#ifdef EDGE_BLOCK_PIVOT
6.517 + // Initializing block_size for the edge block pivot rule
6.518 + int edge_num = countEdges(graph);
6.519 + block_size = edge_num > MIN_BOUND ? edge_num / BLOCK_NUM + 1 : 1;
6.520 +#endif
6.521 +#ifdef CANDIDATE_LIST_PIVOT
6.522 + minor_count = 0;
6.523 +#endif
6.524 +
6.525 + return sum == 0;
6.526 + }
6.527 +
6.528 +#ifdef FIRST_ELIGIBLE_PIVOT
6.529 + /// \brief Finds entering edge according to the "First Eligible"
6.530 + /// pivot rule.
6.531 + bool findEnteringEdge(EdgeIt &next_edge) {
6.532 + for (EdgeIt e = next_edge; e != INVALID; ++e) {
6.533 + if (state[e] * red_cost[e] < 0) {
6.534 + in_edge = e;
6.535 + next_edge = ++e;
6.536 + return true;
6.537 + }
6.538 + }
6.539 + for (EdgeIt e(graph); e != next_edge; ++e) {
6.540 + if (state[e] * red_cost[e] < 0) {
6.541 + in_edge = e;
6.542 + next_edge = ++e;
6.543 + return true;
6.544 + }
6.545 + }
6.546 + return false;
6.547 + }
6.548 +#endif
6.549 +
6.550 +#ifdef BEST_ELIGIBLE_PIVOT
6.551 + /// \brief Finds entering edge according to the "Best Eligible"
6.552 + /// pivot rule.
6.553 + bool findEnteringEdge() {
6.554 + Cost min = 0;
6.555 + for (EdgeIt e(graph); e != INVALID; ++e) {
6.556 + if (state[e] * red_cost[e] < min) {
6.557 + min = state[e] * red_cost[e];
6.558 + in_edge = e;
6.559 + }
6.560 + }
6.561 + return min < 0;
6.562 + }
6.563 +#endif
6.564 +
6.565 +#ifdef EDGE_BLOCK_PIVOT
6.566 + /// \brief Finds entering edge according to the "Edge Block"
6.567 + /// pivot rule.
6.568 + bool findEnteringEdge(EdgeIt &next_edge) {
6.569 + if (block_size == 1) {
6.570 + // Performing first eligible selection
6.571 + for (EdgeIt e = next_edge; e != INVALID; ++e) {
6.572 + if (state[e] * red_cost[e] < 0) {
6.573 + in_edge = e;
6.574 + next_edge = ++e;
6.575 + return true;
6.576 + }
6.577 + }
6.578 + for (EdgeIt e(graph); e != next_edge; ++e) {
6.579 + if (state[e] * red_cost[e] < 0) {
6.580 + in_edge = e;
6.581 + next_edge = ++e;
6.582 + return true;
6.583 + }
6.584 + }
6.585 + return false;
6.586 + } else {
6.587 + // Performing edge block selection
6.588 + Cost curr, min = 0;
6.589 + EdgeIt min_edge(graph);
6.590 + int cnt = 0;
6.591 + for (EdgeIt e = next_edge; e != INVALID; ++e) {
6.592 + if ((curr = state[e] * red_cost[e]) < min) {
6.593 + min = curr;
6.594 + min_edge = e;
6.595 + }
6.596 + if (++cnt == block_size) {
6.597 + if (min < 0) break;
6.598 + cnt = 0;
6.599 + }
6.600 + }
6.601 + if (!(min < 0)) {
6.602 + for (EdgeIt e(graph); e != next_edge; ++e) {
6.603 + if ((curr = state[e] * red_cost[e]) < min) {
6.604 + min = curr;
6.605 + min_edge = e;
6.606 + }
6.607 + if (++cnt == block_size) {
6.608 + if (min < 0) break;
6.609 + cnt = 0;
6.610 + }
6.611 + }
6.612 + }
6.613 + in_edge = min_edge;
6.614 + if ((next_edge = ++min_edge) == INVALID)
6.615 + next_edge = EdgeIt(graph);
6.616 + return min < 0;
6.617 + }
6.618 + }
6.619 +#endif
6.620 +
6.621 +#ifdef CANDIDATE_LIST_PIVOT
6.622 + /// \brief Functor class for removing non-eligible edges from the
6.623 + /// candidate list.
6.624 + class RemoveFunc
6.625 + {
6.626 + private:
6.627 + const IntEdgeMap &st;
6.628 + const ReducedCostMap &rc;
6.629 + public:
6.630 + RemoveFunc(const IntEdgeMap &_st, const ReducedCostMap &_rc) :
6.631 + st(_st), rc(_rc) {}
6.632 + bool operator()(const Edge &e) {
6.633 + return st[e] * rc[e] >= 0;
6.634 + }
6.635 + };
6.636 +
6.637 + /// \brief Finds entering edge according to the "Candidate List"
6.638 + /// pivot rule.
6.639 + bool findEnteringEdge() {
6.640 + static RemoveFunc remove_func(state, red_cost);
6.641 + typedef typename std::list<Edge>::iterator ListIt;
6.642 +
6.643 + candidates.remove_if(remove_func);
6.644 + if (minor_count >= MINOR_LIMIT || candidates.size() == 0) {
6.645 + // Major iteration
6.646 + for (EdgeIt e(graph); e != INVALID; ++e) {
6.647 + if (state[e] * red_cost[e] < 0) {
6.648 + candidates.push_back(e);
6.649 + if (candidates.size() == LIST_LENGTH) break;
6.650 + }
6.651 + }
6.652 + if (candidates.size() == 0) return false;
6.653 + }
6.654 +
6.655 + // Minor iteration
6.656 + ++minor_count;
6.657 + Cost min = 0;
6.658 + for (ListIt it = candidates.begin(); it != candidates.end(); ++it) {
6.659 + if (state[*it] * red_cost[*it] < min) {
6.660 + min = state[*it] * red_cost[*it];
6.661 + in_edge = *it;
6.662 + }
6.663 + }
6.664 + return true;
6.665 + }
6.666 +#endif
6.667 +
6.668 +#ifdef SORTED_LIST_PIVOT
6.669 + /// \brief Functor class to compare edges during sort of the
6.670 + /// candidate list.
6.671 + class SortFunc
6.672 + {
6.673 + private:
6.674 + const IntEdgeMap &st;
6.675 + const ReducedCostMap &rc;
6.676 + public:
6.677 + SortFunc(const IntEdgeMap &_st, const ReducedCostMap &_rc) :
6.678 + st(_st), rc(_rc) {}
6.679 + bool operator()(const Edge &e1, const Edge &e2) {
6.680 + return st[e1] * rc[e1] < st[e2] * rc[e2];
6.681 + }
6.682 + };
6.683 +
6.684 + /// \brief Finds entering edge according to the "Sorted List"
6.685 + /// pivot rule.
6.686 + bool findEnteringEdge() {
6.687 + static SortFunc sort_func(state, red_cost);
6.688 +
6.689 + // Minor iteration
6.690 + while (candidates.size() > 0) {
6.691 + in_edge = candidates.front();
6.692 + candidates.pop_front();
6.693 + if (state[in_edge] * red_cost[in_edge] < 0) return true;
6.694 + }
6.695 +
6.696 + // Major iteration
6.697 + Cost curr, min = 0;
6.698 + for (EdgeIt e(graph); e != INVALID; ++e) {
6.699 + if ((curr = state[e] * red_cost[e]) < min / LOWER_DIV) {
6.700 + candidates.push_back(e);
6.701 + if (curr < min) min = curr;
6.702 + if (candidates.size() >= LIST_LENGTH) break;
6.703 + }
6.704 + }
6.705 + if (candidates.size() == 0) return false;
6.706 + sort(candidates.begin(), candidates.end(), sort_func);
6.707 + return true;
6.708 + }
6.709 +#endif
6.710 +
6.711 + /// \brief Finds the join node.
6.712 + Node findJoinNode() {
6.713 + // Finding the join node
6.714 + Node u = graph.source(in_edge);
6.715 + Node v = graph.target(in_edge);
6.716 + while (u != v) {
6.717 + if (depth[u] == depth[v]) {
6.718 + u = parent[u];
6.719 + v = parent[v];
6.720 + }
6.721 + else if (depth[u] > depth[v]) u = parent[u];
6.722 + else v = parent[v];
6.723 + }
6.724 + return u;
6.725 + }
6.726 +
6.727 + /// \brief Finds the leaving edge of the cycle. Returns \c true if
6.728 + /// the leaving edge is not the same as the entering edge.
6.729 + bool findLeavingEdge() {
6.730 + // Initializing first and second nodes according to the direction
6.731 + // of the cycle
6.732 + if (state[in_edge] == LOWER) {
6.733 + first = graph.source(in_edge);
6.734 + second = graph.target(in_edge);
6.735 + } else {
6.736 + first = graph.target(in_edge);
6.737 + second = graph.source(in_edge);
6.738 + }
6.739 + delta = capacity[in_edge];
6.740 + bool result = false;
6.741 + Capacity d;
6.742 + Edge e;
6.743 +
6.744 + // Searching the cycle along the path form the first node to the
6.745 + // root node
6.746 + for (Node u = first; u != join; u = parent[u]) {
6.747 + e = pred_edge[u];
6.748 + d = forward[u] ? flow[e] : capacity[e] - flow[e];
6.749 + if (d < delta) {
6.750 + delta = d;
6.751 + u_out = u;
6.752 + u_in = first;
6.753 + v_in = second;
6.754 + result = true;
6.755 + }
6.756 + }
6.757 + // Searching the cycle along the path form the second node to the
6.758 + // root node
6.759 + for (Node u = second; u != join; u = parent[u]) {
6.760 + e = pred_edge[u];
6.761 + d = forward[u] ? capacity[e] - flow[e] : flow[e];
6.762 + if (d <= delta) {
6.763 + delta = d;
6.764 + u_out = u;
6.765 + u_in = second;
6.766 + v_in = first;
6.767 + result = true;
6.768 + }
6.769 + }
6.770 + return result;
6.771 + }
6.772 +
6.773 + /// \brief Changes flow and state edge maps.
6.774 + void changeFlows(bool change) {
6.775 + // Augmenting along the cycle
6.776 + if (delta > 0) {
6.777 + Capacity val = state[in_edge] * delta;
6.778 + flow[in_edge] += val;
6.779 + for (Node u = graph.source(in_edge); u != join; u = parent[u]) {
6.780 + flow[pred_edge[u]] += forward[u] ? -val : val;
6.781 + }
6.782 + for (Node u = graph.target(in_edge); u != join; u = parent[u]) {
6.783 + flow[pred_edge[u]] += forward[u] ? val : -val;
6.784 + }
6.785 + }
6.786 + // Updating the state of the entering and leaving edges
6.787 + if (change) {
6.788 + state[in_edge] = TREE;
6.789 + state[pred_edge[u_out]] =
6.790 + (flow[pred_edge[u_out]] == 0) ? LOWER : UPPER;
6.791 + } else {
6.792 + state[in_edge] = -state[in_edge];
6.793 + }
6.794 + }
6.795 +
6.796 + /// \brief Updates thread and parent node maps.
6.797 + void updateThreadParent() {
6.798 + Node u;
6.799 + v_out = parent[u_out];
6.800 +
6.801 + // Handling the case when join and v_out coincide
6.802 + bool par_first = false;
6.803 + if (join == v_out) {
6.804 + for (u = join; u != u_in && u != v_in; u = thread[u]) ;
6.805 + if (u == v_in) {
6.806 + par_first = true;
6.807 + while (thread[u] != u_out) u = thread[u];
6.808 + first = u;
6.809 + }
6.810 + }
6.811 +
6.812 + // Finding the last successor of u_in (u) and the node after it
6.813 + // (right) according to the thread index
6.814 + for (u = u_in; depth[thread[u]] > depth[u_in]; u = thread[u]) ;
6.815 + right = thread[u];
6.816 + if (thread[v_in] == u_out) {
6.817 + for (last = u; depth[last] > depth[u_out]; last = thread[last]) ;
6.818 + if (last == u_out) last = thread[last];
6.819 + }
6.820 + else last = thread[v_in];
6.821 +
6.822 + // Updating stem nodes
6.823 + thread[v_in] = stem = u_in;
6.824 + par_stem = v_in;
6.825 + while (stem != u_out) {
6.826 + thread[u] = new_stem = parent[stem];
6.827 +
6.828 + // Finding the node just before the stem node (u) according to
6.829 + // the original thread index
6.830 + for (u = new_stem; thread[u] != stem; u = thread[u]) ;
6.831 + thread[u] = right;
6.832 +
6.833 + // Changing the parent node of stem and shifting stem and
6.834 + // par_stem nodes
6.835 + parent[stem] = par_stem;
6.836 + par_stem = stem;
6.837 + stem = new_stem;
6.838 +
6.839 + // Finding the last successor of stem (u) and the node after it
6.840 + // (right) according to the thread index
6.841 + for (u = stem; depth[thread[u]] > depth[stem]; u = thread[u]) ;
6.842 + right = thread[u];
6.843 + }
6.844 + parent[u_out] = par_stem;
6.845 + thread[u] = last;
6.846 +
6.847 + if (join == v_out && par_first) {
6.848 + if (first != v_in) thread[first] = right;
6.849 + } else {
6.850 + for (u = v_out; thread[u] != u_out; u = thread[u]) ;
6.851 + thread[u] = right;
6.852 + }
6.853 + }
6.854 +
6.855 + /// \brief Updates pred_edge and forward node maps.
6.856 + void updatePredEdge() {
6.857 + Node u = u_out, v;
6.858 + while (u != u_in) {
6.859 + v = parent[u];
6.860 + pred_edge[u] = pred_edge[v];
6.861 + forward[u] = !forward[v];
6.862 + u = v;
6.863 + }
6.864 + pred_edge[u_in] = in_edge;
6.865 + forward[u_in] = (u_in == graph.source(in_edge));
6.866 + }
6.867 +
6.868 + /// \brief Updates depth and potential node maps.
6.869 + void updateDepthPotential() {
6.870 + depth[u_in] = depth[v_in] + 1;
6.871 + potential[u_in] = forward[u_in] ?
6.872 + potential[v_in] + cost[pred_edge[u_in]] :
6.873 + potential[v_in] - cost[pred_edge[u_in]];
6.874 +
6.875 + Node u = thread[u_in], v;
6.876 + while (true) {
6.877 + v = parent[u];
6.878 + if (v == INVALID) break;
6.879 + depth[u] = depth[v] + 1;
6.880 + potential[u] = forward[u] ?
6.881 + potential[v] + cost[pred_edge[u]] :
6.882 + potential[v] - cost[pred_edge[u]];
6.883 + if (depth[u] <= depth[v_in]) break;
6.884 + u = thread[u];
6.885 + }
6.886 + }
6.887 +
6.888 + /// \brief Executes the algorithm.
6.889 + bool start() {
6.890 + // Processing pivots
6.891 +#ifdef _DEBUG_ITER_
6.892 + int iter_num = 0;
6.893 +#endif
6.894 +#if defined(FIRST_ELIGIBLE_PIVOT) || defined(EDGE_BLOCK_PIVOT)
6.895 + EdgeIt next_edge(graph);
6.896 + while (findEnteringEdge(next_edge))
6.897 +#else
6.898 + while (findEnteringEdge())
6.899 +#endif
6.900 + {
6.901 + join = findJoinNode();
6.902 + bool change = findLeavingEdge();
6.903 + changeFlows(change);
6.904 + if (change) {
6.905 + updateThreadParent();
6.906 + updatePredEdge();
6.907 + updateDepthPotential();
6.908 + }
6.909 +#ifdef _DEBUG_ITER_
6.910 + ++iter_num;
6.911 +#endif
6.912 + }
6.913 +
6.914 +#ifdef _DEBUG_ITER_
6.915 + t_iter.stop();
6.916 + std::cout << "Network Simplex algorithm finished. " << iter_num
6.917 + << " pivot iterations performed.";
6.918 +#endif
6.919 +
6.920 + // Checking if the flow amount equals zero on all the
6.921 + // artificial edges
6.922 + for (InEdgeIt e(graph, root); e != INVALID; ++e)
6.923 + if (flow[e] > 0) return false;
6.924 + for (OutEdgeIt e(graph, root); e != INVALID; ++e)
6.925 + if (flow[e] > 0) return false;
6.926 +
6.927 + // Copying flow values to flow_result
6.928 + if (lower) {
6.929 + for (typename Graph::EdgeIt e(graph_ref); e != INVALID; ++e)
6.930 + flow_result[e] = (*lower)[e] + flow[edge_ref[e]];
6.931 + } else {
6.932 + for (typename Graph::EdgeIt e(graph_ref); e != INVALID; ++e)
6.933 + flow_result[e] = flow[edge_ref[e]];
6.934 + }
6.935 + // Copying potential values to potential_result
6.936 + for (typename Graph::NodeIt n(graph_ref); n != INVALID; ++n)
6.937 + potential_result[n] = potential[node_ref[n]];
6.938 +
6.939 + return true;
6.940 + }
6.941 +
6.942 + }; //class NetworkSimplex
6.943 +
6.944 + ///@}
6.945 +
6.946 +} //namespace lemon
6.947 +
6.948 +#endif //LEMON_NETWORK_SIMPLEX_H