Queries are now handled by a static graph which means less RAM usage and faster queries.
This commit is contained in:
parent
18b278fe1d
commit
fa5a042071
@ -25,7 +25,7 @@ or see http://www.gnu.org/licenses/agpl.txt.
|
|||||||
#include <deque>
|
#include <deque>
|
||||||
|
|
||||||
#include "BinaryHeap.h"
|
#include "BinaryHeap.h"
|
||||||
#include "DynamicGraph.h"
|
//#include "DynamicGraph.h"
|
||||||
#include "../typedefs.h"
|
#include "../typedefs.h"
|
||||||
|
|
||||||
struct _HeapData {
|
struct _HeapData {
|
||||||
@ -35,12 +35,12 @@ struct _HeapData {
|
|||||||
|
|
||||||
typedef BinaryHeap< NodeID, int, int, _HeapData, MapStorage< NodeID, unsigned > > _Heap;
|
typedef BinaryHeap< NodeID, int, int, _HeapData, MapStorage< NodeID, unsigned > > _Heap;
|
||||||
|
|
||||||
template<typename EdgeData, typename KDTST = NodeInformationHelpDesk>
|
template<typename EdgeData, typename GraphT, typename KDTST = NodeInformationHelpDesk>
|
||||||
class SearchEngine {
|
class SearchEngine {
|
||||||
private:
|
private:
|
||||||
const DynamicGraph<EdgeData> * _graph;
|
const GraphT * _graph;
|
||||||
public:
|
public:
|
||||||
SearchEngine(DynamicGraph<EdgeData> * g, KDTST * k) : _graph(g), kdtree(k) {}
|
SearchEngine(GraphT * g, KDTST * k) : _graph(g), kdtree(k) {}
|
||||||
~SearchEngine() {}
|
~SearchEngine() {}
|
||||||
|
|
||||||
NodeInfo& getNodeInfo(NodeID id) const
|
NodeInfo& getNodeInfo(NodeID id) const
|
||||||
@ -136,7 +136,7 @@ private:
|
|||||||
_forwardHeap->DeleteAll();
|
_forwardHeap->DeleteAll();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
for ( typename DynamicGraph<EdgeData>::EdgeIterator edge = _graph->BeginEdges( node ); edge < _graph->EndEdges(node); edge++ ) {
|
for ( typename GraphT::EdgeIterator edge = _graph->BeginEdges( node ); edge < _graph->EndEdges(node); edge++ ) {
|
||||||
const NodeID to = _graph->GetTarget(edge);
|
const NodeID to = _graph->GetTarget(edge);
|
||||||
const int edgeWeight = _graph->GetEdgeData(edge).distance;
|
const int edgeWeight = _graph->GetEdgeData(edge).distance;
|
||||||
|
|
||||||
@ -163,9 +163,9 @@ private:
|
|||||||
bool _UnpackEdge( const NodeID source, const NodeID target, std::vector< NodeID >* path ) {
|
bool _UnpackEdge( const NodeID source, const NodeID target, std::vector< NodeID >* path ) {
|
||||||
assert(source != target);
|
assert(source != target);
|
||||||
//find edge first.
|
//find edge first.
|
||||||
typename DynamicGraph<EdgeData>::EdgeIterator smallestEdge = SPECIAL_EDGEID;
|
typename GraphT::EdgeIterator smallestEdge = SPECIAL_EDGEID;
|
||||||
EdgeWeight smallestWeight = UINT_MAX;
|
EdgeWeight smallestWeight = UINT_MAX;
|
||||||
for(typename DynamicGraph<EdgeData>::EdgeIterator eit = _graph->BeginEdges(source); eit < _graph->EndEdges(source); eit++)
|
for(typename GraphT::EdgeIterator eit = _graph->BeginEdges(source); eit < _graph->EndEdges(source); eit++)
|
||||||
{
|
{
|
||||||
//const NodeID target = GetTarget(edge);
|
//const NodeID target = GetTarget(edge);
|
||||||
const EdgeWeight weight = _graph->GetEdgeData(eit).distance;
|
const EdgeWeight weight = _graph->GetEdgeData(eit).distance;
|
||||||
@ -178,7 +178,7 @@ private:
|
|||||||
}
|
}
|
||||||
if(smallestEdge == SPECIAL_EDGEID)
|
if(smallestEdge == SPECIAL_EDGEID)
|
||||||
{
|
{
|
||||||
for(typename DynamicGraph<EdgeData>::EdgeIterator eit = _graph->BeginEdges(target); eit < _graph->EndEdges(target); eit++)
|
for(typename GraphT::EdgeIterator eit = _graph->BeginEdges(target); eit < _graph->EndEdges(target); eit++)
|
||||||
{
|
{
|
||||||
//const NodeID target = GetTarget(edge);
|
//const NodeID target = GetTarget(edge);
|
||||||
const EdgeWeight weight = _graph->GetEdgeData(eit).distance;
|
const EdgeWeight weight = _graph->GetEdgeData(eit).distance;
|
||||||
|
@ -16,23 +16,43 @@ You should have received a copy of the GNU Affero General Public License
|
|||||||
along with this program; if not, write to the Free Software
|
along with this program; if not, write to the Free Software
|
||||||
Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||||
or see http://www.gnu.org/licenses/agpl.txt.
|
or see http://www.gnu.org/licenses/agpl.txt.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef _NODE_COORDS_H
|
#ifndef _NODE_COORDS_H
|
||||||
#define _NODE_COORDS_H
|
#define _NODE_COORDS_H
|
||||||
|
|
||||||
|
#include <limits>
|
||||||
|
|
||||||
template<typename NodeT>
|
template<typename NodeT>
|
||||||
struct NodeCoords {
|
struct NodeCoords {
|
||||||
|
typedef unsigned key_type;
|
||||||
|
|
||||||
|
|
||||||
NodeCoords(int _lat, int _lon, NodeT _id) : lat(_lat), lon(_lon), id(_id) {}
|
NodeCoords(int _lat, int _lon, NodeT _id) : lat(_lat), lon(_lon), id(_id) {}
|
||||||
NodeCoords() : lat(UINT_MAX), lon(UINT_MAX), id(UINT_MAX) {}
|
NodeCoords() : lat(UINT_MAX), lon(UINT_MAX), id(UINT_MAX) {}
|
||||||
int lat;
|
int lat;
|
||||||
int lon;
|
int lon;
|
||||||
unsigned int id;
|
unsigned int id;
|
||||||
|
|
||||||
|
static NodeCoords<NodeT> min_value()
|
||||||
|
{
|
||||||
|
return NodeCoords<NodeT>(0,0,numeric_limits<NodeT>::min());
|
||||||
|
}
|
||||||
|
static NodeCoords<NodeT> max_value()
|
||||||
|
{
|
||||||
|
return NodeCoords<NodeT>(numeric_limits<int>::max(), numeric_limits<int>::max(), numeric_limits<NodeT>::max());
|
||||||
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
template<typename NodeT>
|
||||||
|
bool operator < (const NodeCoords<NodeT> & a, const NodeCoords<NodeT> & b)
|
||||||
|
{
|
||||||
|
return a.id < b.id;
|
||||||
|
}
|
||||||
|
|
||||||
struct duplet
|
struct duplet
|
||||||
{
|
{
|
||||||
typedef int value_type;
|
typedef int value_type;
|
||||||
|
|
||||||
inline value_type operator[](int const N) const { return d[N]; }
|
inline value_type operator[](int const N) const { return d[N]; }
|
||||||
@ -59,7 +79,7 @@ struct duplet
|
|||||||
}
|
}
|
||||||
unsigned int id;
|
unsigned int id;
|
||||||
value_type d[2];
|
value_type d[2];
|
||||||
};
|
};
|
||||||
|
|
||||||
inline double return_dup( duplet d, int k ) { return d[k]; }
|
inline double return_dup( duplet d, int k ) { return d[k]; }
|
||||||
|
|
||||||
|
151
DataStructures/StaticGraph.h
Normal file
151
DataStructures/StaticGraph.h
Normal file
@ -0,0 +1,151 @@
|
|||||||
|
/*
|
||||||
|
open source routing machine
|
||||||
|
Copyright (C) Dennis Luxen, others 2010
|
||||||
|
|
||||||
|
This program is free software; you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU AFFERO General Public License as published by
|
||||||
|
the Free Software Foundation; either version 3 of the License, or
|
||||||
|
any later version.
|
||||||
|
|
||||||
|
This program is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU Affero General Public License
|
||||||
|
along with this program; if not, write to the Free Software
|
||||||
|
Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||||
|
or see http://www.gnu.org/licenses/agpl.txt.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef STATICGRAPH_H_INCLUDED
|
||||||
|
#define STATICGRAPH_H_INCLUDED
|
||||||
|
|
||||||
|
#include <vector>
|
||||||
|
#include <algorithm>
|
||||||
|
|
||||||
|
#include "../typedefs.h"
|
||||||
|
|
||||||
|
template< typename EdgeData>
|
||||||
|
class StaticGraph {
|
||||||
|
public:
|
||||||
|
typedef NodeID NodeIterator;
|
||||||
|
typedef NodeID EdgeIterator;
|
||||||
|
|
||||||
|
class InputEdge {
|
||||||
|
public:
|
||||||
|
EdgeData data;
|
||||||
|
NodeIterator source;
|
||||||
|
NodeIterator target;
|
||||||
|
bool operator<( const InputEdge& right ) const {
|
||||||
|
if ( source != right.source )
|
||||||
|
return source < right.source;
|
||||||
|
return target < right.target;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
StaticGraph( int nodes, std::vector< InputEdge > &graph ) {
|
||||||
|
|
||||||
|
std::sort( graph.begin(), graph.end() );
|
||||||
|
_numNodes = nodes;
|
||||||
|
_numEdges = ( EdgeIterator ) graph.size();
|
||||||
|
_nodes.resize( _numNodes + 1);
|
||||||
|
EdgeIterator edge = 0;
|
||||||
|
EdgeIterator position = 0;
|
||||||
|
for ( NodeIterator node = 0; node <= _numNodes; ++node ) {
|
||||||
|
EdgeIterator lastEdge = edge;
|
||||||
|
while ( edge < _numEdges && graph[edge].source == node ) {
|
||||||
|
++edge;
|
||||||
|
}
|
||||||
|
_nodes[node].firstEdge = position; //=edge
|
||||||
|
// _nodes[node].edges = edge - lastEdge;
|
||||||
|
// _nodes[node].size = edge - lastEdge;
|
||||||
|
position += edge - lastEdge; //remove
|
||||||
|
}
|
||||||
|
_edges.resize( position ); //(edge)
|
||||||
|
edge = 0;
|
||||||
|
for ( NodeIterator node = 0; node < _numNodes; ++node ) {
|
||||||
|
// for ( EdgeIterator i = _nodes[node].firstEdge, e = _nodes[node].firstEdge + _nodes[node].edges; i != e; ++i ) {
|
||||||
|
for ( EdgeIterator i = _nodes[node].firstEdge, e = _nodes[node+1].firstEdge; i != e; ++i ) {
|
||||||
|
_edges[i].target = graph[edge].target;
|
||||||
|
_edges[i].data = graph[edge].data;
|
||||||
|
assert(_edges[i].data.distance > 0);
|
||||||
|
edge++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
unsigned GetNumberOfNodes() const {
|
||||||
|
return _numNodes;
|
||||||
|
}
|
||||||
|
|
||||||
|
unsigned GetNumberOfEdges() const {
|
||||||
|
return _numEdges;
|
||||||
|
}
|
||||||
|
|
||||||
|
unsigned GetOutDegree( const NodeIterator &n ) const {
|
||||||
|
return _nodes[n].edges;
|
||||||
|
}
|
||||||
|
|
||||||
|
NodeIterator GetTarget( const EdgeIterator &e ) const {
|
||||||
|
return NodeIterator( _edges[e].target );
|
||||||
|
}
|
||||||
|
|
||||||
|
EdgeData &GetEdgeData( const EdgeIterator &e ) {
|
||||||
|
return _edges[e].data;
|
||||||
|
}
|
||||||
|
const EdgeData &GetEdgeData( const EdgeIterator &e ) const {
|
||||||
|
return _edges[e].data;
|
||||||
|
}
|
||||||
|
|
||||||
|
EdgeIterator BeginEdges( const NodeIterator &n ) const {
|
||||||
|
//assert( EndEdges( n ) - EdgeIterator( _nodes[n].firstEdge ) <= 100 );
|
||||||
|
return EdgeIterator( _nodes[n].firstEdge );
|
||||||
|
}
|
||||||
|
|
||||||
|
EdgeIterator EndEdges( const NodeIterator &n ) const {
|
||||||
|
return EdgeIterator( _nodes[n+1].firstEdge );
|
||||||
|
}
|
||||||
|
|
||||||
|
//searches for a specific edge
|
||||||
|
EdgeIterator FindEdge( const NodeIterator &from, const NodeIterator &to ) const {
|
||||||
|
EdgeIterator smallestEdge = SPECIAL_EDGEID;
|
||||||
|
EdgeWeight smallestWeight = UINT_MAX;
|
||||||
|
for ( EdgeIterator edge = BeginEdges( from ); edge < EndEdges(from); edge++ )
|
||||||
|
{
|
||||||
|
const NodeID target = GetTarget(edge);
|
||||||
|
const EdgeWeight weight = GetEdgeData(edge).distance;
|
||||||
|
{
|
||||||
|
if(target == to && weight < smallestWeight)
|
||||||
|
{
|
||||||
|
smallestEdge = edge; smallestWeight = weight;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return smallestEdge;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
private:
|
||||||
|
|
||||||
|
struct _StrNode {
|
||||||
|
//index of the first edge
|
||||||
|
EdgeIterator firstEdge;
|
||||||
|
//amount of edges
|
||||||
|
// unsigned edges;
|
||||||
|
// unsigned size;
|
||||||
|
};
|
||||||
|
|
||||||
|
struct _StrEdge {
|
||||||
|
NodeID target;
|
||||||
|
EdgeData data;
|
||||||
|
};
|
||||||
|
|
||||||
|
NodeIterator _numNodes;
|
||||||
|
EdgeIterator _numEdges;
|
||||||
|
|
||||||
|
std::vector< _StrNode > _nodes;
|
||||||
|
std::vector< _StrEdge > _edges;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif // STATICGRAPH_H_INCLUDED
|
@ -7,6 +7,6 @@ The server part is mostly adapted from the boost http examples. It should be rep
|
|||||||
|
|
||||||
The KD-Tree uses a lot of RAM. An own implementation might be better.
|
The KD-Tree uses a lot of RAM. An own implementation might be better.
|
||||||
|
|
||||||
Dynamic Graph shall be replaced with a static one for queries
|
|
||||||
|
|
||||||
Use Boost to compress all in-/output streams to the file system
|
Use Boost to compress all in-/output streams to the file system
|
||||||
|
|
||||||
|
Rework extractor to be fully externalized
|
13
routed.cpp
13
routed.cpp
@ -36,13 +36,14 @@ or see http://www.gnu.org/licenses/agpl.txt.
|
|||||||
#include <boost/thread.hpp>
|
#include <boost/thread.hpp>
|
||||||
#include <boost/bind.hpp>
|
#include <boost/bind.hpp>
|
||||||
#include "HttpServer/server.h"
|
#include "HttpServer/server.h"
|
||||||
|
#include "DataStructures/StaticGraph.h"
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
//typedef google::dense_hash_map<NodeID, NodeInfo> NodeMap;
|
//typedef google::dense_hash_map<NodeID, NodeInfo> NodeMap;
|
||||||
typedef ContractionCleanup::Edge::EdgeData EdgeData;
|
typedef ContractionCleanup::Edge::EdgeData EdgeData;
|
||||||
typedef DynamicGraph<EdgeData>::InputEdge GraphEdge;
|
typedef StaticGraph<EdgeData>::InputEdge GraphEdge;
|
||||||
typedef http::server server;
|
typedef http::server<StaticGraph<EdgeData> > server;
|
||||||
|
|
||||||
//NodeMap * int2ExtNodeMap = new NodeMap();
|
//NodeMap * int2ExtNodeMap = new NodeMap();
|
||||||
|
|
||||||
@ -109,11 +110,11 @@ int main (int argc, char *argv[])
|
|||||||
|
|
||||||
time = get_timestamp();
|
time = get_timestamp();
|
||||||
cout << "building search graph ..." << flush;
|
cout << "building search graph ..." << flush;
|
||||||
DynamicGraph<EdgeData> * graph = new DynamicGraph<EdgeData>(kdtreeService->getNumberOfNodes()-1, edgelist);
|
StaticGraph<EdgeData> * graph = new StaticGraph<EdgeData>(kdtreeService->getNumberOfNodes()-1, edgelist);
|
||||||
cout << "checking sanity ..." << flush;
|
cout << "checking sanity ..." << flush;
|
||||||
NodeID numberOfNodes = graph->GetNumberOfNodes();
|
NodeID numberOfNodes = graph->GetNumberOfNodes();
|
||||||
for ( NodeID node = 0; node < numberOfNodes; ++node ) {
|
for ( NodeID node = 0; node < numberOfNodes; ++node ) {
|
||||||
for ( DynamicGraph<EdgeData>::EdgeIterator edge = graph->BeginEdges( node ), endEdges = graph->EndEdges( node ); edge != endEdges; ++edge ) {
|
for ( StaticGraph<EdgeData>::EdgeIterator edge = graph->BeginEdges( node ), endEdges = graph->EndEdges( node ); edge != endEdges; ++edge ) {
|
||||||
const NodeID start = node;
|
const NodeID start = node;
|
||||||
const NodeID target = graph->GetTarget( edge );
|
const NodeID target = graph->GetTarget( edge );
|
||||||
const EdgeData& data = graph->GetEdgeData( edge );
|
const EdgeData& data = graph->GetEdgeData( edge );
|
||||||
@ -136,7 +137,7 @@ int main (int argc, char *argv[])
|
|||||||
}
|
}
|
||||||
cout << "ok" << endl;
|
cout << "ok" << endl;
|
||||||
|
|
||||||
SearchEngine<EdgeData> * sEngine = new SearchEngine<EdgeData>(graph, kdtreeService);
|
SearchEngine<EdgeData, StaticGraph<EdgeData> > * sEngine = new SearchEngine<EdgeData, StaticGraph<EdgeData> >(graph, kdtreeService);
|
||||||
cout << "in " << get_timestamp() - time << "s" << endl;
|
cout << "in " << get_timestamp() - time << "s" << endl;
|
||||||
|
|
||||||
time = get_timestamp();
|
time = get_timestamp();
|
||||||
@ -150,7 +151,7 @@ int main (int argc, char *argv[])
|
|||||||
cout << "starting web server ..." << flush;
|
cout << "starting web server ..." << flush;
|
||||||
// Run server in background thread.
|
// Run server in background thread.
|
||||||
server s("0.0.0.0", "5000", omp_get_num_procs(), sEngine);
|
server s("0.0.0.0", "5000", omp_get_num_procs(), sEngine);
|
||||||
boost::thread t(boost::bind(&http::server::run, &s));
|
boost::thread t(boost::bind(&server::run, &s));
|
||||||
cout << "ok" << endl;
|
cout << "ok" << endl;
|
||||||
|
|
||||||
// Restore previous signals.
|
// Restore previous signals.
|
||||||
|
Loading…
Reference in New Issue
Block a user