Merge branch 'develop' of https://github.com/DennisOSRM/Project-OSRM into develop

This commit is contained in:
DennisOSRM 2013-07-03 10:03:08 +02:00
commit 2c3f05e6f1
27 changed files with 1306 additions and 486 deletions

1
.gitignore vendored
View File

@ -79,4 +79,3 @@ stxxl.errlog
/sandbox/ /sandbox/
/test/profile.lua /test/profile.lua
/profile.lua

View File

@ -30,7 +30,6 @@ class IteratorbasedCRC32 {
private: private:
typedef typename ContainerT::iterator ContainerT_iterator; typedef typename ContainerT::iterator ContainerT_iterator;
unsigned crc; unsigned crc;
unsigned slowcrc_table[1<<8];
typedef boost::crc_optimal<32, 0x1EDC6F41, 0x0, 0x0, true, true> my_crc_32_type; typedef boost::crc_optimal<32, 0x1EDC6F41, 0x0, 0x0, true, true> my_crc_32_type;
typedef unsigned (IteratorbasedCRC32::*CRC32CFunctionPtr)(char *str, unsigned len, unsigned crc); typedef unsigned (IteratorbasedCRC32::*CRC32CFunctionPtr)(char *str, unsigned len, unsigned crc);

View File

@ -96,7 +96,7 @@ void EdgeBasedGraphFactory::GetEdgeBasedEdges(DeallocatingVector< EdgeBasedEdge
edgeBasedEdges.swap(outputEdgeList); edgeBasedEdges.swap(outputEdgeList);
} }
void EdgeBasedGraphFactory::GetEdgeBasedNodes( DeallocatingVector< EdgeBasedNode> & nodes) { void EdgeBasedGraphFactory::GetEdgeBasedNodes( std::vector<EdgeBasedNode> & nodes) {
#ifndef NDEBUG #ifndef NDEBUG
BOOST_FOREACH(EdgeBasedNode & node, edgeBasedNodes){ BOOST_FOREACH(EdgeBasedNode & node, edgeBasedNodes){
assert(node.lat1 != INT_MAX); assert(node.lon1 != INT_MAX); assert(node.lat1 != INT_MAX); assert(node.lon1 != INT_MAX);

View File

@ -25,19 +25,6 @@
#ifndef EDGEBASEDGRAPHFACTORY_H_ #ifndef EDGEBASEDGRAPHFACTORY_H_
#define EDGEBASEDGRAPHFACTORY_H_ #define EDGEBASEDGRAPHFACTORY_H_
#include <algorithm>
#include <queue>
#include <vector>
#include <stxxl.h>
#include <cstdlib>
#include <boost/foreach.hpp>
#include <boost/make_shared.hpp>
#include <boost/noncopyable.hpp>
#include <boost/shared_ptr.hpp>
#include <boost/unordered_map.hpp>
#include <boost/unordered_set.hpp>
#include "../typedefs.h" #include "../typedefs.h"
#include "../DataStructures/DeallocatingVector.h" #include "../DataStructures/DeallocatingVector.h"
#include "../DataStructures/DynamicGraph.h" #include "../DataStructures/DynamicGraph.h"
@ -49,14 +36,22 @@
#include "../DataStructures/Percent.h" #include "../DataStructures/Percent.h"
#include "../DataStructures/TurnInstructions.h" #include "../DataStructures/TurnInstructions.h"
#include "../Util/BaseConfiguration.h" #include "../Util/BaseConfiguration.h"
#include "../Util/LuaUtil.h"
extern "C" { #include <stxxl.h>
#include <lua.h>
#include <lauxlib.h>
#include <lualib.h>
}
#include <luabind/luabind.hpp>
#include <boost/foreach.hpp>
#include <boost/make_shared.hpp>
#include <boost/noncopyable.hpp>
#include <boost/shared_ptr.hpp>
#include <boost/unordered_map.hpp>
#include <boost/unordered_set.hpp>
#include <cstdlib>
#include <algorithm>
#include <queue>
#include <vector>
class EdgeBasedGraphFactory : boost::noncopyable { class EdgeBasedGraphFactory : boost::noncopyable {
public: public:
@ -64,9 +59,23 @@ public:
bool operator<(const EdgeBasedNode & other) const { bool operator<(const EdgeBasedNode & other) const {
return other.id < id; return other.id < id;
} }
bool operator==(const EdgeBasedNode & other) const { bool operator==(const EdgeBasedNode & other) const {
return id == other.id; return id == other.id;
} }
inline _Coordinate Centroid() const {
_Coordinate centroid;
//The coordinates of the midpoint are given by:
//x = (x1 + x2) /2 and y = (y1 + y2) /2.
centroid.lon = (std::min(lon1, lon2) + std::max(lon1, lon2))/2;
centroid.lat = (std::min(lat1, lat2) + std::max(lat1, lat2))/2;
return centroid;
}
inline bool isIgnored() const {
return ignoreInGrid;
}
NodeID id; NodeID id;
int lat1; int lat1;
int lat2; int lat2;
@ -126,7 +135,7 @@ private:
RestrictionMap _restrictionMap; RestrictionMap _restrictionMap;
DeallocatingVector<EdgeBasedEdge> edgeBasedEdges; DeallocatingVector<EdgeBasedEdge> edgeBasedEdges;
DeallocatingVector<EdgeBasedNode> edgeBasedNodes; std::vector<EdgeBasedNode> edgeBasedNodes;
NodeID CheckForEmanatingIsOnlyTurn(const NodeID u, const NodeID v) const; NodeID CheckForEmanatingIsOnlyTurn(const NodeID u, const NodeID v) const;
bool CheckIfTurnIsRestricted(const NodeID u, const NodeID v, const NodeID w) const; bool CheckIfTurnIsRestricted(const NodeID u, const NodeID v, const NodeID w) const;
@ -144,7 +153,7 @@ public:
void Run(const char * originalEdgeDataFilename, lua_State *myLuaState); void Run(const char * originalEdgeDataFilename, lua_State *myLuaState);
void GetEdgeBasedEdges( DeallocatingVector< EdgeBasedEdge >& edges ); void GetEdgeBasedEdges( DeallocatingVector< EdgeBasedEdge >& edges );
void GetEdgeBasedNodes( DeallocatingVector< EdgeBasedNode> & nodes); void GetEdgeBasedNodes( std::vector< EdgeBasedNode> & nodes);
void GetOriginalEdgeData( std::vector< OriginalEdgeData> & originalEdgeData); void GetOriginalEdgeData( std::vector< OriginalEdgeData> & originalEdgeData);
TurnInstruction AnalyzeTurn(const NodeID u, const NodeID v, const NodeID w, unsigned& penalty, lua_State *myLuaState) const; TurnInstruction AnalyzeTurn(const NodeID u, const NodeID v, const NodeID w, unsigned& penalty, lua_State *myLuaState) const;
unsigned GetNumberOfNodes() const; unsigned GetNumberOfNodes() const;

View File

@ -23,6 +23,7 @@ or see http://www.gnu.org/licenses/agpl.txt.
#include "../DataStructures/DeallocatingVector.h" #include "../DataStructures/DeallocatingVector.h"
#include <boost/assert.hpp>
#include <boost/integer.hpp> #include <boost/integer.hpp>
#include <algorithm> #include <algorithm>
@ -118,7 +119,6 @@ class DynamicGraph {
} }
EdgeIterator BeginEdges( const NodeIterator n ) const { EdgeIterator BeginEdges( const NodeIterator n ) const {
//assert( EndEdges( n ) - EdgeIterator( _nodes[n].firstEdge ) <= 100 );
return EdgeIterator( m_nodes[n].firstEdge ); return EdgeIterator( m_nodes[n].firstEdge );
} }
@ -203,11 +203,11 @@ class DynamicGraph {
protected: protected:
bool isDummy( EdgeIterator edge ) const { bool isDummy( const EdgeIterator edge ) const {
return m_edges[edge].target == (std::numeric_limits< NodeIterator >::max)(); return m_edges[edge].target == (std::numeric_limits< NodeIterator >::max)();
} }
void makeDummy( EdgeIterator edge ) { void makeDummy( const EdgeIterator edge ) {
m_edges[edge].target = (std::numeric_limits< NodeIterator >::max)(); m_edges[edge].target = (std::numeric_limits< NodeIterator >::max)();
} }

View File

@ -0,0 +1,87 @@
/*
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 HILBERTVALUE_H_
#define HILBERTVALUE_H_
#include <boost/integer.hpp>
#include <boost/noncopyable.hpp>
// computes a 64 bit value that corresponds to the hilbert space filling curve
class HilbertCode : boost::noncopyable {
public:
static uint64_t GetHilbertNumberForCoordinate(
const _Coordinate & current_coordinate) {
unsigned location[2];
location[0] = current_coordinate.lat+( 90*100000);
location[1] = current_coordinate.lon+(180*100000);
TransposeCoordinate(location);
const uint64_t result = BitInterleaving(location[0], location[1]);
return result;
}
private:
static inline uint64_t BitInterleaving(const uint32_t a, const uint32_t b) {
uint64_t result = 0;
for(int8_t index = 31; index >= 0; --index){
result |= (a >> index) & 1;
result <<= 1;
result |= (b >> index) & 1;
if(0 != index){
result <<= 1;
}
}
return result;
}
static inline void TransposeCoordinate( uint32_t * X) {
uint32_t M = 1 << (32-1), P, Q, t;
int i;
// Inverse undo
for( Q = M; Q > 1; Q >>= 1 ) {
P=Q-1;
for( i = 0; i < 2; ++i ) {
if( X[i] & Q ) {
X[0] ^= P; // invert
} else {
t = (X[0]^X[i]) & P;
X[0] ^= t;
X[i] ^= t;
}
} // exchange
}
// Gray encode
for( i = 1; i < 2; ++i ) {
X[i] ^= X[i-1];
}
t=0;
for( Q = M; Q > 1; Q >>= 1 ) {
if( X[2-1] & Q ) {
t ^= Q-1;
}
} //check if this for loop is wrong
for( i = 0; i < 2; ++i ) {
X[i] ^= t;
}
}
};
#endif /* HILBERTVALUE_H_ */

View File

@ -21,34 +21,49 @@ or see http://www.gnu.org/licenses/agpl.txt.
#ifndef NODEINFORMATIONHELPDESK_H_ #ifndef NODEINFORMATIONHELPDESK_H_
#define NODEINFORMATIONHELPDESK_H_ #define NODEINFORMATIONHELPDESK_H_
#include "NodeCoords.h"
#include "PhantomNodes.h"
#include "QueryEdge.h"
#include "StaticRTree.h"
#include "../Contractor/EdgeBasedGraphFactory.h"
#include "../typedefs.h"
#include <boost/assert.hpp>
#include <boost/noncopyable.hpp>
#include <fstream> #include <fstream>
#include <iostream> #include <iostream>
#include <vector> #include <vector>
#include <boost/noncopyable.hpp> typedef EdgeBasedGraphFactory::EdgeBasedNode RTreeLeaf;
#include "../typedefs.h"
#include "../DataStructures/QueryEdge.h"
#include "NNGrid.h"
#include "PhantomNodes.h"
#include "NodeCoords.h"
class NodeInformationHelpDesk : boost::noncopyable{ class NodeInformationHelpDesk : boost::noncopyable{
public: public:
NodeInformationHelpDesk(const char* ramIndexInput, const char* fileIndexInput, const unsigned _numberOfNodes, const unsigned crc) : numberOfNodes(_numberOfNodes), checkSum(crc) { NodeInformationHelpDesk(
readOnlyGrid = new ReadOnlyGrid(ramIndexInput,fileIndexInput); const char* ramIndexInput,
assert(0 == coordinateVector.size()); const char* fileIndexInput,
const unsigned number_of_nodes,
const unsigned crc) : number_of_nodes(number_of_nodes), checkSum(crc) {
read_only_rtree = new StaticRTree<RTreeLeaf>(
ramIndexInput,
fileIndexInput
);
BOOST_ASSERT_MSG(
0 == coordinateVector.size(),
"Coordinate vector not empty"
);
} }
//Todo: Shared memory mechanism //Todo: Shared memory mechanism
// NodeInformationHelpDesk(const char* ramIndexInput, const char* fileIndexInput, const unsigned crc) : checkSum(crc) {
// readOnlyGrid = new ReadOnlyGrid(ramIndexInput,fileIndexInput);
// }
~NodeInformationHelpDesk() { ~NodeInformationHelpDesk() {
delete readOnlyGrid; delete read_only_rtree;
} }
void initNNGrid(std::ifstream& nodesInstream, std::ifstream& edgesInStream) {
void initNNGrid(
std::ifstream& nodesInstream,
std::ifstream& edgesInStream
) {
DEBUG("Loading node data"); DEBUG("Loading node data");
NodeInfo b; NodeInfo b;
while(!nodesInstream.eof()) { while(!nodesInstream.eof()) {
@ -68,20 +83,15 @@ public:
OriginalEdgeData deserialized_originalEdgeData; OriginalEdgeData deserialized_originalEdgeData;
for(unsigned i = 0; i < numberOfOrigEdges; ++i) { for(unsigned i = 0; i < numberOfOrigEdges; ++i) {
edgesInStream.read((char*)&(deserialized_originalEdgeData), sizeof(OriginalEdgeData)); edgesInStream.read((char*)&(deserialized_originalEdgeData), sizeof(OriginalEdgeData));
origEdgeData_viaNode[i] = deserialized_originalEdgeData.viaNode; origEdgeData_viaNode[i] = deserialized_originalEdgeData.viaNode;
origEdgeData_nameID[i] = deserialized_originalEdgeData.nameID; origEdgeData_nameID[i] = deserialized_originalEdgeData.nameID;
origEdgeData_turnInstruction[i] = deserialized_originalEdgeData.turnInstruction; origEdgeData_turnInstruction[i] = deserialized_originalEdgeData.turnInstruction;
} }
edgesInStream.close(); edgesInStream.close();
DEBUG("Loaded " << numberOfOrigEdges << " orig edges"); DEBUG("Loaded " << numberOfOrigEdges << " orig edges");
DEBUG("Opening NN indices"); DEBUG("Opening NN indices");
readOnlyGrid->OpenIndexFiles();
} }
// void initNNGrid() {
// readOnlyGrid->OpenIndexFiles();
// }
inline int getLatitudeOfNode(const unsigned id) const { inline int getLatitudeOfNode(const unsigned id) const {
const NodeID node = origEdgeData_viaNode.at(id); const NodeID node = origEdgeData_viaNode.at(id);
return coordinateVector.at(node).lat; return coordinateVector.at(node).lat;
@ -100,24 +110,36 @@ public:
return origEdgeData_turnInstruction.at(id); return origEdgeData_turnInstruction.at(id);
} }
inline NodeID getNumberOfNodes() const { return numberOfNodes; } inline NodeID getNumberOfNodes() const {
inline NodeID getNumberOfNodes2() const { return coordinateVector.size(); } return number_of_nodes;
}
inline bool FindNearestNodeCoordForLatLon(const _Coordinate& coord, _Coordinate& result) const { inline NodeID getNumberOfNodes2() const {
return readOnlyGrid->FindNearestCoordinateOnEdgeInNodeBasedGraph(coord, result); return coordinateVector.size();
} }
inline bool FindPhantomNodeForCoordinate( const _Coordinate & location, PhantomNode & resultNode, const unsigned zoomLevel) { inline bool FindNearestNodeCoordForLatLon(
return readOnlyGrid->FindPhantomNodeForCoordinate(location, resultNode, zoomLevel); const _Coordinate& input_coordinate,
} _Coordinate& result,
const unsigned zoom_level = 18
) const {
PhantomNode resulting_phantom_node;
bool foundNode = FindPhantomNodeForCoordinate(input_coordinate, resulting_phantom_node, zoom_level);
result = resulting_phantom_node.location;
return foundNode;
}
inline void FindRoutingStarts(const _Coordinate &start, const _Coordinate &target, PhantomNodes & phantomNodes, const unsigned zoomLevel) const { inline bool FindPhantomNodeForCoordinate(
readOnlyGrid->FindRoutingStarts(start, target, phantomNodes, zoomLevel); const _Coordinate & input_coordinate,
} PhantomNode & resulting_phantom_node,
const unsigned zoom_level
inline void FindNearestPointOnEdge(const _Coordinate & input, _Coordinate& output){ ) const {
readOnlyGrid->FindNearestPointOnEdge(input, output); return read_only_rtree->FindPhantomNodeForCoordinate(
} input_coordinate,
resulting_phantom_node,
zoom_level
);
}
inline unsigned GetCheckSum() const { inline unsigned GetCheckSum() const {
return checkSum; return checkSum;
@ -129,8 +151,8 @@ private:
std::vector<unsigned> origEdgeData_nameID; std::vector<unsigned> origEdgeData_nameID;
std::vector<TurnInstruction> origEdgeData_turnInstruction; std::vector<TurnInstruction> origEdgeData_turnInstruction;
ReadOnlyGrid * readOnlyGrid; StaticRTree<EdgeBasedGraphFactory::EdgeBasedNode> * read_only_rtree;
const unsigned numberOfNodes; const unsigned number_of_nodes;
const unsigned checkSum; const unsigned checkSum;
}; };

View File

@ -0,0 +1,909 @@
/*
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 STATICRTREE_H_
#define STATICRTREE_H_
#include "MercatorUtil.h"
#include "TimingUtil.h"
#include "Coordinate.h"
#include "PhantomNodes.h"
#include "DeallocatingVector.h"
#include "HilbertValue.h"
#include "../typedefs.h"
#include <boost/assert.hpp>
#include <boost/bind.hpp>
#include <boost/foreach.hpp>
#include <boost/algorithm/minmax.hpp>
#include <boost/algorithm/minmax_element.hpp>
#include <boost/range/algorithm_ext/erase.hpp>
#include <boost/noncopyable.hpp>
#include <boost/thread.hpp>
#include <cassert>
#include <cfloat>
#include <climits>
#include <algorithm>
#include <fstream>
#include <queue>
#include <vector>
//tuning parameters
const static uint32_t RTREE_BRANCHING_FACTOR = 50;
const static uint32_t RTREE_LEAF_NODE_SIZE = 1170;
// Implements a static, i.e. packed, R-tree
static boost::thread_specific_ptr<std::ifstream> thread_local_rtree_stream;
template<class DataT>
class StaticRTree : boost::noncopyable {
private:
struct RectangleInt2D {
RectangleInt2D() :
min_lon(INT_MAX),
max_lon(INT_MIN),
min_lat(INT_MAX),
max_lat(INT_MIN) {}
int32_t min_lon, max_lon;
int32_t min_lat, max_lat;
inline void InitializeMBRectangle(
const DataT * objects,
const uint32_t element_count
) {
for(uint32_t i = 0; i < element_count; ++i) {
min_lon = std::min(
min_lon, std::min(objects[i].lon1, objects[i].lon2)
);
max_lon = std::max(
max_lon, std::max(objects[i].lon1, objects[i].lon2)
);
min_lat = std::min(
min_lat, std::min(objects[i].lat1, objects[i].lat2)
);
max_lat = std::max(
max_lat, std::max(objects[i].lat1, objects[i].lat2)
);
}
}
inline void AugmentMBRectangle(const RectangleInt2D & other) {
min_lon = std::min(min_lon, other.min_lon);
max_lon = std::max(max_lon, other.max_lon);
min_lat = std::min(min_lat, other.min_lat);
max_lat = std::max(max_lat, other.max_lat);
}
inline _Coordinate Centroid() const {
_Coordinate centroid;
//The coordinates of the midpoints are given by:
//x = (x1 + x2) /2 and y = (y1 + y2) /2.
centroid.lon = (min_lon + max_lon)/2;
centroid.lat = (min_lat + max_lat)/2;
return centroid;
}
inline bool Intersects(const RectangleInt2D & other) const {
_Coordinate upper_left (other.max_lat, other.min_lon);
_Coordinate upper_right(other.max_lat, other.max_lon);
_Coordinate lower_right(other.min_lat, other.max_lon);
_Coordinate lower_left (other.min_lat, other.min_lon);
return (
Contains(upper_left)
|| Contains(upper_right)
|| Contains(lower_right)
|| Contains(lower_left)
);
}
inline double GetMinDist(const _Coordinate & location) const {
bool is_contained = Contains(location);
if (is_contained) {
return 0.0;
}
double min_dist = DBL_MAX;
min_dist = std::min(
min_dist,
ApproximateDistance(
location.lat,
location.lon,
max_lat,
min_lon
)
);
min_dist = std::min(
min_dist,
ApproximateDistance(
location.lat,
location.lon,
max_lat,
max_lon
)
);
min_dist = std::min(
min_dist,
ApproximateDistance(
location.lat,
location.lon,
min_lat,
max_lon
)
);
min_dist = std::min(
min_dist,
ApproximateDistance(
location.lat,
location.lon,
min_lat,
min_lon
)
);
return min_dist;
}
inline double GetMinMaxDist(const _Coordinate & location) const {
double min_max_dist = DBL_MAX;
//Get minmax distance to each of the four sides
_Coordinate upper_left (max_lat, min_lon);
_Coordinate upper_right(max_lat, max_lon);
_Coordinate lower_right(min_lat, max_lon);
_Coordinate lower_left (min_lat, min_lon);
min_max_dist = std::min(
min_max_dist,
std::max(
ApproximateDistance(location, upper_left ),
ApproximateDistance(location, upper_right)
)
);
min_max_dist = std::min(
min_max_dist,
std::max(
ApproximateDistance(location, upper_right),
ApproximateDistance(location, lower_right)
)
);
min_max_dist = std::min(
min_max_dist,
std::max(
ApproximateDistance(location, lower_right),
ApproximateDistance(location, lower_left )
)
);
min_max_dist = std::min(
min_max_dist,
std::max(
ApproximateDistance(location, lower_left ),
ApproximateDistance(location, upper_left )
)
);
return min_max_dist;
}
inline bool Contains(const _Coordinate & location) const {
bool lats_contained =
(location.lat > min_lat) && (location.lat < max_lat);
bool lons_contained =
(location.lon > min_lon) && (location.lon < max_lon);
return lats_contained && lons_contained;
}
inline friend std::ostream & operator<< ( std::ostream & out, const RectangleInt2D & rect ) {
out << rect.min_lat/100000. << "," << rect.min_lon/100000. << " " << rect.max_lat/100000. << "," << rect.max_lon/100000.;
return out;
}
};
typedef RectangleInt2D RectangleT;
struct WrappedInputElement {
explicit WrappedInputElement(const uint32_t _array_index, const uint64_t _hilbert_value) :
m_array_index(_array_index), m_hilbert_value(_hilbert_value) {}
WrappedInputElement() : m_array_index(UINT_MAX), m_hilbert_value(0) {}
uint32_t m_array_index;
uint64_t m_hilbert_value;
inline bool operator<(const WrappedInputElement & other) const {
return m_hilbert_value < other.m_hilbert_value;
}
};
struct LeafNode {
LeafNode() : object_count(0) {}
uint32_t object_count;
DataT objects[RTREE_LEAF_NODE_SIZE];
};
struct TreeNode {
TreeNode() : child_count(0), child_is_on_disk(false) {}
RectangleT minimum_bounding_rectangle;
uint32_t child_count:31;
bool child_is_on_disk:1;
uint32_t children[RTREE_BRANCHING_FACTOR];
};
struct QueryCandidate {
explicit QueryCandidate(const uint32_t n_id, const double dist) : node_id(n_id), min_dist(dist)/*, minmax_dist(DBL_MAX)*/ {}
QueryCandidate() : node_id(UINT_MAX), min_dist(DBL_MAX)/*, minmax_dist(DBL_MAX)*/ {}
uint32_t node_id;
double min_dist;
// double minmax_dist;
inline bool operator<(const QueryCandidate & other) const {
return min_dist < other.min_dist;
}
};
std::vector<TreeNode> m_search_tree;
uint64_t m_element_count;
std::string m_leaf_node_filename;
public:
//Construct a pack R-Tree from the input-list with Kamel-Faloutsos algorithm [1]
explicit StaticRTree(std::vector<DataT> & input_data_vector, const char * tree_node_filename, const char * leaf_node_filename) :
m_leaf_node_filename(leaf_node_filename) {
m_element_count = input_data_vector.size();
//remove elements that are flagged to be ignored
// boost::remove_erase_if(input_data_vector, boost::bind(&DataT::isIgnored, _1 ));
INFO("constructing r-tree of " << m_element_count << " elements");
// INFO("sizeof(LeafNode)=" << sizeof(LeafNode));
// INFO("sizeof(TreeNode)=" << sizeof(TreeNode));
// INFO("sizeof(WrappedInputElement)=" << sizeof(WrappedInputElement));
double time1 = get_timestamp();
std::vector<WrappedInputElement> input_wrapper_vector(input_data_vector.size());
//generate auxiliary vector of hilbert-values
#pragma omp parallel for schedule(guided)
for(uint64_t element_counter = 0; element_counter < m_element_count; ++element_counter) {
//INFO("ID: " << input_data_vector[element_counter].id);
input_wrapper_vector[element_counter].m_array_index = element_counter;
//Get Hilbert-Value for centroid in mercartor projection
DataT & current_element = input_data_vector[element_counter];
_Coordinate current_centroid = current_element.Centroid();
current_centroid.lat = 100000*lat2y(current_centroid.lat/100000.);
uint64_t current_hilbert_value = HilbertCode::GetHilbertNumberForCoordinate(current_centroid);
input_wrapper_vector[element_counter].m_hilbert_value = current_hilbert_value;
}
//INFO("finished wrapper setup");
//open leaf file
std::ofstream leaf_node_file(leaf_node_filename, std::ios::binary);
leaf_node_file.write((char*) &m_element_count, sizeof(uint64_t));
//sort the hilbert-value representatives
std::sort(input_wrapper_vector.begin(), input_wrapper_vector.end());
// INFO("finished sorting");
std::vector<TreeNode> tree_nodes_in_level;
//pack M elements into leaf node and write to leaf file
uint64_t processed_objects_count = 0;
while(processed_objects_count < m_element_count) {
LeafNode current_leaf;
TreeNode current_node;
for(uint32_t current_element_index = 0; RTREE_LEAF_NODE_SIZE > current_element_index; ++current_element_index) {
if(m_element_count > (processed_objects_count + current_element_index)) {
// INFO("Checking element " << (processed_objects_count + current_element_index));
uint32_t index_of_next_object = input_wrapper_vector[processed_objects_count + current_element_index].m_array_index;
current_leaf.objects[current_element_index] = input_data_vector[index_of_next_object];
++current_leaf.object_count;
}
}
if(0 == processed_objects_count) {
for(uint32_t i = 0; i < current_leaf.object_count; ++i) {
//INFO("[" << i << "] id: " << current_leaf.objects[i].id << ", weight: " << current_leaf.objects[i].weight << ", " << current_leaf.objects[i].lat1/100000. << "," << current_leaf.objects[i].lon1/100000. << ";" << current_leaf.objects[i].lat2/100000. << "," << current_leaf.objects[i].lon2/100000.);
}
}
//generate tree node that resemble the objects in leaf and store it for next level
current_node.minimum_bounding_rectangle.InitializeMBRectangle(current_leaf.objects, current_leaf.object_count);
current_node.child_is_on_disk = true;
current_node.children[0] = tree_nodes_in_level.size();
tree_nodes_in_level.push_back(current_node);
//write leaf_node to leaf node file
leaf_node_file.write((char*)&current_leaf, sizeof(current_leaf));
processed_objects_count += current_leaf.object_count;
}
// INFO("wrote " << processed_objects_count << " leaf objects");
//close leaf file
leaf_node_file.close();
uint32_t processing_level = 0;
while(1 < tree_nodes_in_level.size()) {
// INFO("processing " << (uint32_t)tree_nodes_in_level.size() << " tree nodes in level " << processing_level);
std::vector<TreeNode> tree_nodes_in_next_level;
uint32_t processed_tree_nodes_in_level = 0;
while(processed_tree_nodes_in_level < tree_nodes_in_level.size()) {
TreeNode parent_node;
//pack RTREE_BRANCHING_FACTOR elements into tree_nodes each
for(uint32_t current_child_node_index = 0; RTREE_BRANCHING_FACTOR > current_child_node_index; ++current_child_node_index) {
if(processed_tree_nodes_in_level < tree_nodes_in_level.size()) {
TreeNode & current_child_node = tree_nodes_in_level[processed_tree_nodes_in_level];
//add tree node to parent entry
parent_node.children[current_child_node_index] = m_search_tree.size();
m_search_tree.push_back(current_child_node);
//augment MBR of parent
parent_node.minimum_bounding_rectangle.AugmentMBRectangle(current_child_node.minimum_bounding_rectangle);
//increase counters
++parent_node.child_count;
++processed_tree_nodes_in_level;
}
}
tree_nodes_in_next_level.push_back(parent_node);
// INFO("processed: " << processed_tree_nodes_in_level << ", generating " << (uint32_t)tree_nodes_in_next_level.size() << " parents");
}
tree_nodes_in_level.swap(tree_nodes_in_next_level);
++processing_level;
}
BOOST_ASSERT_MSG(1 == tree_nodes_in_level.size(), "tree broken, more than one root node");
//last remaining entry is the root node;
// INFO("root node has " << (uint32_t)tree_nodes_in_level[0].child_count << " children");
//store root node
m_search_tree.push_back(tree_nodes_in_level[0]);
//reverse and renumber tree to have root at index 0
std::reverse(m_search_tree.begin(), m_search_tree.end());
#pragma omp parallel for schedule(guided)
for(uint32_t i = 0; i < m_search_tree.size(); ++i) {
TreeNode & current_tree_node = m_search_tree[i];
for(uint32_t j = 0; j < current_tree_node.child_count; ++j) {
const uint32_t old_id = current_tree_node.children[j];
const uint32_t new_id = m_search_tree.size() - old_id - 1;
current_tree_node.children[j] = new_id;
}
}
//open tree file
std::ofstream tree_node_file(tree_node_filename, std::ios::binary);
uint32_t size_of_tree = m_search_tree.size();
BOOST_ASSERT_MSG(0 < size_of_tree, "tree empty");
tree_node_file.write((char *)&size_of_tree, sizeof(uint32_t));
tree_node_file.write((char *)&m_search_tree[0], sizeof(TreeNode)*size_of_tree);
//close tree node file.
tree_node_file.close();
double time2 = get_timestamp();
// INFO("written " << processed_objects_count << " leafs in " << sizeof(LeafNode)*(1+(unsigned)std::ceil(processed_objects_count/RTREE_LEAF_NODE_SIZE) )+sizeof(uint64_t) << " bytes");
// INFO("written search tree of " << size_of_tree << " tree nodes in " << sizeof(TreeNode)*size_of_tree+sizeof(uint32_t) << " bytes");
INFO("finished r-tree construction in " << (time2-time1) << " seconds");
//todo: test queries
/* INFO("first MBR:" << m_search_tree[0].minimum_bounding_rectangle);
DataT result;
time1 = get_timestamp();
bool found_nearest = NearestNeighbor(_Coordinate(50.191085,8.466479), result);
time2 = get_timestamp();
INFO("found nearest element to (50.191085,8.466479): " << (found_nearest ? "yes" : "no") << " in " << (time2-time1) << "s at (" << result.lat1/100000. << "," << result.lon1/100000. << " " << result.lat2/100000. << "," << result.lon2/100000. << ")");
time1 = get_timestamp();
found_nearest = NearestNeighbor(_Coordinate(50.23979, 8.51882), result);
time2 = get_timestamp();
INFO("found nearest element to (50.23979, 8.51882): " << (found_nearest ? "yes" : "no") << " in " << (time2-time1) << "s at (" << result.lat1/100000. << "," << result.lon1/100000. << " " << result.lat2/100000. << "," << result.lon2/100000. << ")");
time1 = get_timestamp();
found_nearest = NearestNeighbor(_Coordinate(49.0316,2.6937), result);
time2 = get_timestamp();
INFO("found nearest element to (49.0316,2.6937): " << (found_nearest ? "yes" : "no") << " in " << (time2-time1) << "s at (" << result.lat1/100000. << "," << result.lon1/100000. << " " << result.lat2/100000. << "," << result.lon2/100000. << ")");
*/
}
//Read-only operation for queries
explicit StaticRTree(
const char * node_filename,
const char * leaf_filename
) : m_leaf_node_filename(leaf_filename) {
//INFO("Loading nodes: " << node_filename);
//INFO("opening leafs: " << leaf_filename);
//open tree node file and load into RAM.
std::ifstream tree_node_file(node_filename, std::ios::binary);
uint32_t tree_size = 0;
tree_node_file.read((char*)&tree_size, sizeof(uint32_t));
//INFO("reading " << tree_size << " tree nodes in " << (sizeof(TreeNode)*tree_size) << " bytes");
m_search_tree.resize(tree_size);
tree_node_file.read((char*)&m_search_tree[0], sizeof(TreeNode)*tree_size);
tree_node_file.close();
//open leaf node file and store thread specific pointer
std::ifstream leaf_node_file(leaf_filename, std::ios::binary);
leaf_node_file.read((char*)&m_element_count, sizeof(uint64_t));
leaf_node_file.close();
//INFO( tree_size << " nodes in search tree");
//INFO( m_element_count << " elements in leafs");
}
/*
inline void FindKNearestPhantomNodesForCoordinate(
const _Coordinate & location,
const unsigned zoom_level,
const unsigned candidate_count,
std::vector<std::pair<PhantomNode, double> > & result_vector
) const {
bool ignore_tiny_components = (zoom_level <= 14);
DataT nearest_edge;
uint32_t io_count = 0;
uint32_t explored_tree_nodes_count = 0;
INFO("searching for coordinate " << input_coordinate);
double min_dist = DBL_MAX;
double min_max_dist = DBL_MAX;
bool found_a_nearest_edge = false;
_Coordinate nearest, current_start_coordinate, current_end_coordinate;
//initialize queue with root element
std::priority_queue<QueryCandidate> traversal_queue;
traversal_queue.push(QueryCandidate(0, m_search_tree[0].minimum_bounding_rectangle.GetMinDist(input_coordinate)));
BOOST_ASSERT_MSG(FLT_EPSILON > (0. - traversal_queue.top().min_dist), "Root element in NN Search has min dist != 0.");
while(!traversal_queue.empty()) {
const QueryCandidate current_query_node = traversal_queue.top(); traversal_queue.pop();
++explored_tree_nodes_count;
bool prune_downward = (current_query_node.min_dist >= min_max_dist);
bool prune_upward = (current_query_node.min_dist >= min_dist);
if( !prune_downward && !prune_upward ) { //downward pruning
TreeNode & current_tree_node = m_search_tree[current_query_node.node_id];
if (current_tree_node.child_is_on_disk) {
LeafNode current_leaf_node;
LoadLeafFromDisk(current_tree_node.children[0], current_leaf_node);
++io_count;
for(uint32_t i = 0; i < current_leaf_node.object_count; ++i) {
DataT & current_edge = current_leaf_node.objects[i];
if(ignore_tiny_components && current_edge.belongsToTinyComponent) {
continue;
}
double current_ratio = 0.;
double current_perpendicular_distance = ComputePerpendicularDistance(
input_coordinate,
_Coordinate(current_edge.lat1, current_edge.lon1),
_Coordinate(current_edge.lat2, current_edge.lon2),
nearest,
&current_ratio
);
if(
current_perpendicular_distance < min_dist
&& !DoubleEpsilonCompare(
current_perpendicular_distance,
min_dist
)
) { //found a new minimum
min_dist = current_perpendicular_distance;
result_phantom_node.edgeBasedNode = current_edge.id;
result_phantom_node.nodeBasedEdgeNameID = current_edge.nameID;
result_phantom_node.weight1 = current_edge.weight;
result_phantom_node.weight2 = INT_MAX;
result_phantom_node.location = nearest;
current_start_coordinate.lat = current_edge.lat1;
current_start_coordinate.lon = current_edge.lon1;
current_end_coordinate.lat = current_edge.lat2;
current_end_coordinate.lon = current_edge.lon2;
nearest_edge = current_edge;
found_a_nearest_edge = true;
} else if(
DoubleEpsilonCompare(current_perpendicular_distance, min_dist) &&
1 == abs(current_edge.id - result_phantom_node.edgeBasedNode )
&& CoordinatesAreEquivalent(
current_start_coordinate,
_Coordinate(
current_edge.lat1,
current_edge.lon1
),
_Coordinate(
current_edge.lat2,
current_edge.lon2
),
current_end_coordinate
)
) {
result_phantom_node.edgeBasedNode = std::min(current_edge.id, result_phantom_node.edgeBasedNode);
result_phantom_node.weight2 = current_edge.weight;
}
}
} else {
//traverse children, prune if global mindist is smaller than local one
for (uint32_t i = 0; i < current_tree_node.child_count; ++i) {
const int32_t child_id = current_tree_node.children[i];
TreeNode & child_tree_node = m_search_tree[child_id];
RectangleT & child_rectangle = child_tree_node.minimum_bounding_rectangle;
const double current_min_dist = child_rectangle.GetMinDist(input_coordinate);
const double current_min_max_dist = child_rectangle.GetMinMaxDist(input_coordinate);
if( current_min_max_dist < min_max_dist ) {
min_max_dist = current_min_max_dist;
}
if (current_min_dist > min_max_dist) {
continue;
}
if (current_min_dist > min_dist) { //upward pruning
continue;
}
traversal_queue.push(QueryCandidate(child_id, current_min_dist));
}
}
}
}
const double ratio = (found_a_nearest_edge ?
std::min(1., ApproximateDistance(_Coordinate(nearest_edge.lat1, nearest_edge.lon1),
result_phantom_node.location)/ApproximateDistance(_Coordinate(nearest_edge.lat1, nearest_edge.lon1), _Coordinate(nearest_edge.lat2, nearest_edge.lon2))
) : 0
);
result_phantom_node.weight1 *= ratio;
if(INT_MAX != result_phantom_node.weight2) {
result_phantom_node.weight2 *= (1.-ratio);
}
result_phantom_node.ratio = ratio;
//Hack to fix rounding errors and wandering via nodes.
if(std::abs(input_coordinate.lon - result_phantom_node.location.lon) == 1) {
result_phantom_node.location.lon = input_coordinate.lon;
}
if(std::abs(input_coordinate.lat - result_phantom_node.location.lat) == 1) {
result_phantom_node.location.lat = input_coordinate.lat;
}
INFO("mindist: " << min_dist << ", io's: " << io_count << ", nodes: " << explored_tree_nodes_count << ", loc: " << result_phantom_node.location << ", ratio: " << ratio << ", id: " << result_phantom_node.edgeBasedNode);
INFO("bidirected: " << (result_phantom_node.isBidirected() ? "yes" : "no") );
return found_a_nearest_edge;
}
*/
bool FindPhantomNodeForCoordinate(
const _Coordinate & input_coordinate,
PhantomNode & result_phantom_node,
const unsigned zoom_level
) {
bool ignore_tiny_components = (zoom_level <= 14);
DataT nearest_edge;
uint32_t io_count = 0;
uint32_t explored_tree_nodes_count = 0;
//INFO("searching for coordinate " << input_coordinate);
double min_dist = DBL_MAX;
double min_max_dist = DBL_MAX;
bool found_a_nearest_edge = false;
_Coordinate nearest, current_start_coordinate, current_end_coordinate;
//initialize queue with root element
std::priority_queue<QueryCandidate> traversal_queue;
double current_min_dist = m_search_tree[0].minimum_bounding_rectangle.GetMinDist(input_coordinate);
traversal_queue.push(
QueryCandidate(0, current_min_dist)
);
BOOST_ASSERT_MSG(
FLT_EPSILON > (0. - traversal_queue.top().min_dist),
"Root element in NN Search has min dist != 0."
);
while(!traversal_queue.empty()) {
const QueryCandidate current_query_node = traversal_queue.top(); traversal_queue.pop();
++explored_tree_nodes_count;
bool prune_downward = (current_query_node.min_dist >= min_max_dist);
bool prune_upward = (current_query_node.min_dist >= min_dist);
if( !prune_downward && !prune_upward ) { //downward pruning
TreeNode & current_tree_node = m_search_tree[current_query_node.node_id];
if (current_tree_node.child_is_on_disk) {
LeafNode current_leaf_node;
LoadLeafFromDisk(current_tree_node.children[0], current_leaf_node);
++io_count;
//INFO("checking " << current_leaf_node.object_count << " elements");
for(uint32_t i = 0; i < current_leaf_node.object_count; ++i) {
DataT & current_edge = current_leaf_node.objects[i];
if(ignore_tiny_components && current_edge.belongsToTinyComponent) {
continue;
}
if(current_edge.isIgnored()) {
continue;
}
double current_ratio = 0.;
double current_perpendicular_distance = ComputePerpendicularDistance(
input_coordinate,
_Coordinate(current_edge.lat1, current_edge.lon1),
_Coordinate(current_edge.lat2, current_edge.lon2),
nearest,
&current_ratio
);
//INFO("[" << current_edge.id << "] (" << current_edge.lat1/100000. << "," << current_edge.lon1/100000. << ")==(" << current_edge.lat2/100000. << "," << current_edge.lon2/100000. << ") at distance " << current_perpendicular_distance << " min dist: " << min_dist
// << ", ratio " << current_ratio
// );
if(
current_perpendicular_distance < min_dist
&& !DoubleEpsilonCompare(
current_perpendicular_distance,
min_dist
)
) { //found a new minimum
min_dist = current_perpendicular_distance;
result_phantom_node.edgeBasedNode = current_edge.id;
result_phantom_node.nodeBasedEdgeNameID = current_edge.nameID;
result_phantom_node.weight1 = current_edge.weight;
result_phantom_node.weight2 = INT_MAX;
result_phantom_node.location = nearest;
current_start_coordinate.lat = current_edge.lat1;
current_start_coordinate.lon = current_edge.lon1;
current_end_coordinate.lat = current_edge.lat2;
current_end_coordinate.lon = current_edge.lon2;
nearest_edge = current_edge;
found_a_nearest_edge = true;
} else if(
DoubleEpsilonCompare(current_perpendicular_distance, min_dist) &&
1 == abs(current_edge.id - result_phantom_node.edgeBasedNode )
&& CoordinatesAreEquivalent(
current_start_coordinate,
_Coordinate(
current_edge.lat1,
current_edge.lon1
),
_Coordinate(
current_edge.lat2,
current_edge.lon2
),
current_end_coordinate
)
) {
BOOST_ASSERT_MSG(current_edge.id != result_phantom_node.edgeBasedNode, "IDs not different");
//INFO("found bidirected edge on nodes " << current_edge.id << " and " << result_phantom_node.edgeBasedNode);
result_phantom_node.weight2 = current_edge.weight;
if(current_edge.id < result_phantom_node.edgeBasedNode) {
result_phantom_node.edgeBasedNode = current_edge.id;
std::swap(result_phantom_node.weight1, result_phantom_node.weight2);
std::swap(current_end_coordinate, current_start_coordinate);
// INFO("case 2");
}
//INFO("w1: " << result_phantom_node.weight1 << ", w2: " << result_phantom_node.weight2);
}
}
} else {
//traverse children, prune if global mindist is smaller than local one
for (uint32_t i = 0; i < current_tree_node.child_count; ++i) {
const int32_t child_id = current_tree_node.children[i];
TreeNode & child_tree_node = m_search_tree[child_id];
RectangleT & child_rectangle = child_tree_node.minimum_bounding_rectangle;
const double current_min_dist = child_rectangle.GetMinDist(input_coordinate);
const double current_min_max_dist = child_rectangle.GetMinMaxDist(input_coordinate);
if( current_min_max_dist < min_max_dist ) {
min_max_dist = current_min_max_dist;
}
if (current_min_dist > min_max_dist) {
continue;
}
if (current_min_dist > min_dist) { //upward pruning
continue;
}
traversal_queue.push(QueryCandidate(child_id, current_min_dist));
}
}
}
}
const double ratio = (found_a_nearest_edge ?
std::min(1., ApproximateDistance(current_start_coordinate,
result_phantom_node.location)/ApproximateDistance(current_start_coordinate, current_end_coordinate)
) : 0
);
result_phantom_node.weight1 *= ratio;
if(INT_MAX != result_phantom_node.weight2) {
result_phantom_node.weight2 *= (1.-ratio);
}
result_phantom_node.ratio = ratio;
//Hack to fix rounding errors and wandering via nodes.
if(std::abs(input_coordinate.lon - result_phantom_node.location.lon) == 1) {
result_phantom_node.location.lon = input_coordinate.lon;
}
if(std::abs(input_coordinate.lat - result_phantom_node.location.lat) == 1) {
result_phantom_node.location.lat = input_coordinate.lat;
}
// INFO("start: (" << nearest_edge.lat1 << "," << nearest_edge.lon1 << "), end: (" << nearest_edge.lat2 << "," << nearest_edge.lon2 << ")" );
// INFO("mindist: " << min_dist << ", io's: " << io_count << ", nodes: " << explored_tree_nodes_count << ", loc: " << result_phantom_node.location << ", ratio: " << ratio << ", id: " << result_phantom_node.edgeBasedNode);
// INFO("weight1: " << result_phantom_node.weight1 << ", weight2: " << result_phantom_node.weight2);
// INFO("bidirected: " << (result_phantom_node.isBidirected() ? "yes" : "no") );
// INFO("NameID: " << result_phantom_node.nodeBasedEdgeNameID);
return found_a_nearest_edge;
}
/*
//Nearest-Neighbor query with the Roussopoulos et al. algorithm [2]
inline bool NearestNeighbor(const _Coordinate & input_coordinate, DataT & result_element) {
uint32_t io_count = 0;
uint32_t explored_tree_nodes_count = 0;
INFO("searching for coordinate " << input_coordinate);
double min_dist = DBL_MAX;
double min_max_dist = DBL_MAX;
bool found_return_value = false;
//initialize queue with root element
std::priority_queue<QueryCandidate> traversal_queue;
traversal_queue.push(QueryCandidate(0, m_search_tree[0].minimum_bounding_rectangle.GetMinDist(input_coordinate)));
BOOST_ASSERT_MSG(FLT_EPSILON > (0. - traversal_queue.top().min_dist), "Root element in NN Search has min dist != 0.");
while(!traversal_queue.empty()) {
const QueryCandidate current_query_node = traversal_queue.top(); traversal_queue.pop();
++explored_tree_nodes_count;
// INFO("popped node " << current_query_node.node_id << " at distance " << current_query_node.min_dist);
bool prune_downward = (current_query_node.min_dist >= min_max_dist);
bool prune_upward = (current_query_node.min_dist >= min_dist);
// INFO(" up prune: " << (prune_upward ? "y" : "n" ));
// INFO(" down prune: " << (prune_downward ? "y" : "n" ));
if( prune_downward || prune_upward ) { //downward pruning
// INFO(" pruned node " << current_query_node.node_id << " because " << current_query_node.min_dist << "<" << min_max_dist);
} else {
TreeNode & current_tree_node = m_search_tree[current_query_node.node_id];
if (current_tree_node.child_is_on_disk) {
// INFO(" Fetching child from disk for id: " << current_query_node.node_id);
LeafNode current_leaf_node;
LoadLeafFromDisk(current_tree_node.children[0], current_leaf_node);
++io_count;
double ratio = 0.;
_Coordinate nearest;
for(uint32_t i = 0; i < current_leaf_node.object_count; ++i) {
DataT & current_object = current_leaf_node.objects[i];
double current_perpendicular_distance = ComputePerpendicularDistance(
input_coordinate,
_Coordinate(current_object.lat1, current_object.lon1),
_Coordinate(current_object.lat2, current_object.lon2),
nearest,
&ratio
);
if(current_perpendicular_distance < min_dist && !DoubleEpsilonCompare(current_perpendicular_distance, min_dist)) { //found a new minimum
min_dist = current_perpendicular_distance;
result_element = current_object;
found_return_value = true;
}
}
} else {
//traverse children, prune if global mindist is smaller than local one
// INFO(" Checking " << current_tree_node.child_count << " children of node " << current_query_node.node_id);
for (uint32_t i = 0; i < current_tree_node.child_count; ++i) {
const int32_t child_id = current_tree_node.children[i];
TreeNode & child_tree_node = m_search_tree[child_id];
RectangleT & child_rectangle = child_tree_node.minimum_bounding_rectangle;
const double current_min_dist = child_rectangle.GetMinDist(input_coordinate);
const double current_min_max_dist = child_rectangle.GetMinMaxDist(input_coordinate);
if( current_min_max_dist < min_max_dist ) {
min_max_dist = current_min_max_dist;
}
if (current_min_dist > min_max_dist) {
continue;
}
if (current_min_dist > min_dist) { //upward pruning
continue;
}
// INFO(" pushing node " << child_id << " at distance " << current_min_dist);
traversal_queue.push(QueryCandidate(child_id, current_min_dist));
}
}
}
}
INFO("mindist: " << min_dist << ", io's: " << io_count << ", touched nodes: " << explored_tree_nodes_count);
return found_return_value;
}
*/
private:
inline void LoadLeafFromDisk(const uint32_t leaf_id, LeafNode& result_node) {
if(!thread_local_rtree_stream.get() || !thread_local_rtree_stream->is_open()) {
thread_local_rtree_stream.reset(
new std::ifstream(
m_leaf_node_filename.c_str(),
std::ios::in | std::ios::binary
)
);
}
if(!thread_local_rtree_stream->good()) {
thread_local_rtree_stream->clear(std::ios::goodbit);
DEBUG("Resetting stale filestream");
}
uint64_t seek_pos = sizeof(uint64_t) + leaf_id*sizeof(LeafNode);
thread_local_rtree_stream->seekg(seek_pos);
thread_local_rtree_stream->read((char *)&result_node, sizeof(LeafNode));
}
inline double ComputePerpendicularDistance(
const _Coordinate& inputPoint,
const _Coordinate& source,
const _Coordinate& target,
_Coordinate& nearest, double *r) const {
const double x = static_cast<double>(inputPoint.lat);
const double y = static_cast<double>(inputPoint.lon);
const double a = static_cast<double>(source.lat);
const double b = static_cast<double>(source.lon);
const double c = static_cast<double>(target.lat);
const double d = static_cast<double>(target.lon);
double p,q,mX,nY;
if(fabs(a-c) > FLT_EPSILON){
const double m = (d-b)/(c-a); // slope
// Projection of (x,y) on line joining (a,b) and (c,d)
p = ((x + (m*y)) + (m*m*a - m*b))/(1. + m*m);
q = b + m*(p - a);
} else {
p = c;
q = y;
}
nY = (d*p - c*q)/(a*d - b*c);
mX = (p - nY*a)/c;// These values are actually n/m+n and m/m+n , we need
// not calculate the explicit values of m an n as we
// are just interested in the ratio
if(std::isnan(mX)) {
*r = (target == inputPoint) ? 1. : 0.;
} else {
*r = mX;
}
if(*r<=0.){
nearest.lat = source.lat;
nearest.lon = source.lon;
return ((b - y)*(b - y) + (a - x)*(a - x));
// return std::sqrt(((b - y)*(b - y) + (a - x)*(a - x)));
} else if(*r >= 1.){
nearest.lat = target.lat;
nearest.lon = target.lon;
return ((d - y)*(d - y) + (c - x)*(c - x));
// return std::sqrt(((d - y)*(d - y) + (c - x)*(c - x)));
}
// point lies in between
nearest.lat = p;
nearest.lon = q;
// return std::sqrt((p-x)*(p-x) + (q-y)*(q-y));
return (p-x)*(p-x) + (q-y)*(q-y);
}
inline bool CoordinatesAreEquivalent(const _Coordinate & a, const _Coordinate & b, const _Coordinate & c, const _Coordinate & d) const {
return (a == b && c == d) || (a == c && b == d) || (a == d && b == c);
}
inline bool DoubleEpsilonCompare(const double d1, const double d2) const {
return (std::fabs(d1 - d2) < FLT_EPSILON);
}
};
//[1] "On Packing R-Trees"; I. Kamel, C. Faloutsos; 1993; DOI: 10.1145/170088.170403
//[2] "Nearest Neighbor Queries", N. Roussopulos et al; 1995; DOI: 10.1145/223784.223794
#endif /* STATICRTREE_H_ */

View File

@ -21,12 +21,12 @@
#ifndef EXTRACTIONCONTAINERS_H_ #ifndef EXTRACTIONCONTAINERS_H_
#define EXTRACTIONCONTAINERS_H_ #define EXTRACTIONCONTAINERS_H_
#include <boost/foreach.hpp>
#include <stxxl.h>
#include "ExtractorStructs.h" #include "ExtractorStructs.h"
#include "../DataStructures/TimingUtil.h" #include "../DataStructures/TimingUtil.h"
#include <boost/foreach.hpp>
#include <stxxl.h>
class ExtractionContainers { class ExtractionContainers {
public: public:
typedef stxxl::vector<NodeID> STXXLNodeIDVector; typedef stxxl::vector<NodeID> STXXLNodeIDVector;

View File

@ -76,7 +76,7 @@ inline bool PBFParser::ReadHeader() {
else if ( "DenseNodes" == feature ) { else if ( "DenseNodes" == feature ) {
supported = true; supported = true;
} }
if ( !supported ) { if ( !supported ) {
std::cerr << "[error] required feature not supported: " << feature.data() << std::endl; std::cerr << "[error] required feature not supported: " << feature.data() << std::endl;
return false; return false;
@ -159,18 +159,15 @@ inline void PBFParser::parseDenseNode(_ThreadData * threadData) {
int64_t m_lastDenseLatitude = 0; int64_t m_lastDenseLatitude = 0;
int64_t m_lastDenseLongitude = 0; int64_t m_lastDenseLongitude = 0;
ImportNode n;
std::vector<ImportNode> extracted_nodes_vector;
const int number_of_nodes = dense.id_size(); const int number_of_nodes = dense.id_size();
extracted_nodes_vector.reserve(number_of_nodes); std::vector<ImportNode> extracted_nodes_vector(number_of_nodes);
for(int i = 0; i < number_of_nodes; ++i) { for(int i = 0; i < number_of_nodes; ++i) {
n.Clear();
m_lastDenseID += dense.id( i ); m_lastDenseID += dense.id( i );
m_lastDenseLatitude += dense.lat( i ); m_lastDenseLatitude += dense.lat( i );
m_lastDenseLongitude += dense.lon( i ); m_lastDenseLongitude += dense.lon( i );
n.id = m_lastDenseID; extracted_nodes_vector[i].id = m_lastDenseID;
n.lat = 100000*( ( double ) m_lastDenseLatitude * threadData->PBFprimitiveBlock.granularity() + threadData->PBFprimitiveBlock.lat_offset() ) / NANO; extracted_nodes_vector[i].lat = 100000*( ( double ) m_lastDenseLatitude * threadData->PBFprimitiveBlock.granularity() + threadData->PBFprimitiveBlock.lat_offset() ) / NANO;
n.lon = 100000*( ( double ) m_lastDenseLongitude * threadData->PBFprimitiveBlock.granularity() + threadData->PBFprimitiveBlock.lon_offset() ) / NANO; extracted_nodes_vector[i].lon = 100000*( ( double ) m_lastDenseLongitude * threadData->PBFprimitiveBlock.granularity() + threadData->PBFprimitiveBlock.lon_offset() ) / NANO;
while (denseTagIndex < dense.keys_vals_size()) { while (denseTagIndex < dense.keys_vals_size()) {
const int tagValue = dense.keys_vals( denseTagIndex ); const int tagValue = dense.keys_vals( denseTagIndex );
if( 0==tagValue ) { if( 0==tagValue ) {
@ -180,10 +177,9 @@ inline void PBFParser::parseDenseNode(_ThreadData * threadData) {
const int keyValue = dense.keys_vals ( denseTagIndex+1 ); const int keyValue = dense.keys_vals ( denseTagIndex+1 );
const std::string & key = threadData->PBFprimitiveBlock.stringtable().s(tagValue).data(); const std::string & key = threadData->PBFprimitiveBlock.stringtable().s(tagValue).data();
const std::string & value = threadData->PBFprimitiveBlock.stringtable().s(keyValue).data(); const std::string & value = threadData->PBFprimitiveBlock.stringtable().s(keyValue).data();
n.keyVals.Add(key, value); extracted_nodes_vector[i].keyVals.Add(key, value);
denseTagIndex += 2; denseTagIndex += 2;
} }
extracted_nodes_vector.push_back(n);
} }
#pragma omp parallel for schedule ( guided ) #pragma omp parallel for schedule ( guided )
@ -292,37 +288,33 @@ inline void PBFParser::parseRelation(_ThreadData * threadData) {
} }
inline void PBFParser::parseWay(_ThreadData * threadData) { inline void PBFParser::parseWay(_ThreadData * threadData) {
ExtractionWay w;
std::vector<ExtractionWay> waysToParse;
const int number_of_ways = threadData->PBFprimitiveBlock.primitivegroup( threadData->currentGroupID ).ways_size(); const int number_of_ways = threadData->PBFprimitiveBlock.primitivegroup( threadData->currentGroupID ).ways_size();
waysToParse.reserve(number_of_ways); std::vector<ExtractionWay> parsed_way_vector(number_of_ways);
for(int i = 0; i < number_of_ways; ++i) { for(int i = 0; i < number_of_ways; ++i) {
w.Clear();
const OSMPBF::Way& inputWay = threadData->PBFprimitiveBlock.primitivegroup( threadData->currentGroupID ).ways( i ); const OSMPBF::Way& inputWay = threadData->PBFprimitiveBlock.primitivegroup( threadData->currentGroupID ).ways( i );
w.id = inputWay.id(); parsed_way_vector[i].id = inputWay.id();
unsigned pathNode(0); unsigned pathNode(0);
const int number_of_referenced_nodes = inputWay.refs_size(); const int number_of_referenced_nodes = inputWay.refs_size();
for(int i = 0; i < number_of_referenced_nodes; ++i) { for(int j = 0; j < number_of_referenced_nodes; ++j) {
pathNode += inputWay.refs(i); pathNode += inputWay.refs(j);
w.path.push_back(pathNode); parsed_way_vector[i].path.push_back(pathNode);
} }
assert(inputWay.keys_size() == inputWay.vals_size()); assert(inputWay.keys_size() == inputWay.vals_size());
const int number_of_keys = inputWay.keys_size(); const int number_of_keys = inputWay.keys_size();
for(int i = 0; i < number_of_keys; ++i) { for(int j = 0; j < number_of_keys; ++j) {
const std::string & key = threadData->PBFprimitiveBlock.stringtable().s(inputWay.keys(i)); const std::string & key = threadData->PBFprimitiveBlock.stringtable().s(inputWay.keys(j));
const std::string & val = threadData->PBFprimitiveBlock.stringtable().s(inputWay.vals(i)); const std::string & val = threadData->PBFprimitiveBlock.stringtable().s(inputWay.vals(j));
w.keyVals.Add(key, val); parsed_way_vector[i].keyVals.Add(key, val);
} }
waysToParse.push_back(w);
} }
#pragma omp parallel for schedule ( guided ) #pragma omp parallel for schedule ( guided )
for(int i = 0; i < number_of_ways; ++i) { for(int i = 0; i < number_of_ways; ++i) {
ExtractionWay & w = waysToParse[i]; ExtractionWay & w = parsed_way_vector[i];
ParseWayInLua( w, scriptingEnvironment.getLuaStateForThreadID(omp_get_thread_num()) ); ParseWayInLua( w, scriptingEnvironment.getLuaStateForThreadID(omp_get_thread_num()) );
} }
BOOST_FOREACH(ExtractionWay & w, waysToParse) { BOOST_FOREACH(ExtractionWay & w, parsed_way_vector) {
extractor_callbacks->wayFunction(w); extractor_callbacks->wayFunction(w);
} }
} }
@ -423,7 +415,7 @@ inline bool PBFParser::readBlob(std::fstream& stream, _ThreadData * threadData)
if(stream.eof()) { if(stream.eof()) {
return false; return false;
} }
const int size = threadData->PBFBlobHeader.datasize(); const int size = threadData->PBFBlobHeader.datasize();
if ( size < 0 || size > MAX_BLOB_SIZE ) { if ( size < 0 || size > MAX_BLOB_SIZE ) {
std::cerr << "[error] invalid Blob size:" << size << std::endl; std::cerr << "[error] invalid Blob size:" << size << std::endl;

View File

@ -1,17 +1,17 @@
/* /*
open source routing machine open source routing machine
Copyright (C) Dennis Luxen, others 2010 Copyright (C) Dennis Luxen, others 2010
This program is free software; you can redistribute it and/or modify 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 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 the Free Software Foundation; either version 3 of the License, or
any later version. any later version.
This program is distributed in the hope that it will be useful, This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details. GNU General Public License for more details.
You should have received a copy of the GNU Affero General Public License 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
@ -21,6 +21,13 @@
#ifndef PBFPARSER_H_ #ifndef PBFPARSER_H_
#define PBFPARSER_H_ #define PBFPARSER_H_
#include "../DataStructures/HashTable.h"
#include "../DataStructures/ConcurrentQueue.h"
#include "../Util/MachineInfo.h"
#include "../Util/OpenMPWrapper.h"
#include "../typedefs.h"
#include "BaseParser.h"
#include <boost/shared_ptr.hpp> #include <boost/shared_ptr.hpp>
#include <boost/make_shared.hpp> #include <boost/make_shared.hpp>
#include <boost/ref.hpp> #include <boost/ref.hpp>
@ -30,44 +37,38 @@
#include <zlib.h> #include <zlib.h>
#include "../typedefs.h"
#include "../DataStructures/HashTable.h"
#include "../DataStructures/ConcurrentQueue.h"
#include "../Util/MachineInfo.h"
#include "../Util/OpenMPWrapper.h"
#include "BaseParser.h"
class PBFParser : public BaseParser { class PBFParser : public BaseParser {
enum EntityType { enum EntityType {
TypeNode = 1, TypeNode = 1,
TypeWay = 2, TypeWay = 2,
TypeRelation = 4, TypeRelation = 4,
TypeDenseNode = 8 TypeDenseNode = 8
} ; } ;
struct _ThreadData { struct _ThreadData {
int currentGroupID; int currentGroupID;
int currentEntityID; int currentEntityID;
short entityTypeIndicator; short entityTypeIndicator;
OSMPBF::BlobHeader PBFBlobHeader; OSMPBF::BlobHeader PBFBlobHeader;
OSMPBF::Blob PBFBlob; OSMPBF::Blob PBFBlob;
OSMPBF::HeaderBlock PBFHeaderBlock; OSMPBF::HeaderBlock PBFHeaderBlock;
OSMPBF::PrimitiveBlock PBFprimitiveBlock; OSMPBF::PrimitiveBlock PBFprimitiveBlock;
std::vector<char> charBuffer; std::vector<char> charBuffer;
}; };
public: public:
PBFParser(const char * fileName, ExtractorCallbacks* ec, ScriptingEnvironment& se); PBFParser(const char * fileName, ExtractorCallbacks* ec, ScriptingEnvironment& se);
virtual ~PBFParser(); virtual ~PBFParser();
inline bool ReadHeader(); inline bool ReadHeader();
inline bool Parse(); inline bool Parse();
private: private:
inline void ReadData(); inline void ReadData();
inline void ParseData(); inline void ParseData();
@ -75,7 +76,7 @@ private:
inline void parseNode(_ThreadData * ); inline void parseNode(_ThreadData * );
inline void parseRelation(_ThreadData * threadData); inline void parseRelation(_ThreadData * threadData);
inline void parseWay(_ThreadData * threadData); inline void parseWay(_ThreadData * threadData);
inline void loadGroup(_ThreadData * threadData); inline void loadGroup(_ThreadData * threadData);
inline void loadBlock(_ThreadData * threadData); inline void loadBlock(_ThreadData * threadData);
inline bool readPBFBlobHeader(std::fstream& stream, _ThreadData * threadData); inline bool readPBFBlobHeader(std::fstream& stream, _ThreadData * threadData);
@ -83,17 +84,17 @@ private:
inline bool unpackLZMA(std::fstream &, _ThreadData * ); inline bool unpackLZMA(std::fstream &, _ThreadData * );
inline bool readBlob(std::fstream& stream, _ThreadData * threadData) ; inline bool readBlob(std::fstream& stream, _ThreadData * threadData) ;
inline bool readNextBlock(std::fstream& stream, _ThreadData * threadData); inline bool readNextBlock(std::fstream& stream, _ThreadData * threadData);
static const int NANO = 1000 * 1000 * 1000; static const int NANO = 1000 * 1000 * 1000;
static const int MAX_BLOB_HEADER_SIZE = 64 * 1024; static const int MAX_BLOB_HEADER_SIZE = 64 * 1024;
static const int MAX_BLOB_SIZE = 32 * 1024 * 1024; static const int MAX_BLOB_SIZE = 32 * 1024 * 1024;
#ifndef NDEBUG #ifndef NDEBUG
/* counting the number of read blocks and groups */ /* counting the number of read blocks and groups */
unsigned groupCount; unsigned groupCount;
unsigned blockCount; unsigned blockCount;
#endif #endif
std::fstream input; // the input stream to parse std::fstream input; // the input stream to parse
boost::shared_ptr<ConcurrentQueue < _ThreadData* > > threadDataQueue; boost::shared_ptr<ConcurrentQueue < _ThreadData* > > threadDataQueue;
}; };

View File

@ -21,13 +21,13 @@ or see http://www.gnu.org/licenses/agpl.txt.
#ifndef LOCATEPLUGIN_H_ #ifndef LOCATEPLUGIN_H_
#define LOCATEPLUGIN_H_ #define LOCATEPLUGIN_H_
#include <fstream>
#include "../Server/DataStructures/QueryObjectsStorage.h"
#include "BasePlugin.h" #include "BasePlugin.h"
#include "RouteParameters.h" #include "RouteParameters.h"
#include "../Util/StringUtil.h"
#include "../DataStructures/NodeInformationHelpDesk.h" #include "../DataStructures/NodeInformationHelpDesk.h"
#include "../Server/DataStructures/QueryObjectsStorage.h"
#include "../Util/StringUtil.h"
#include <fstream>
/* /*
* This Plugin locates the nearest node in the road network for a given coordinate. * This Plugin locates the nearest node in the road network for a given coordinate.

View File

@ -82,8 +82,12 @@ task :default => [:build]
desc "Build using CMake." desc "Build using CMake."
task :build do task :build do
Dir.chdir BUILD_FOLDER do if Dir.exists? BUILD_FOLDER
system "make" Dir.chdir BUILD_FOLDER do
system "make"
end
else
system "mkdir build; cd build; cmake ..; make"
end end
end end

View File

@ -44,6 +44,7 @@ public:
inline void RoutingStep(typename QueryDataT::QueryHeap & _forwardHeap, typename QueryDataT::QueryHeap & _backwardHeap, NodeID *middle, int *_upperbound, const int edgeBasedOffset, const bool forwardDirection) const { inline void RoutingStep(typename QueryDataT::QueryHeap & _forwardHeap, typename QueryDataT::QueryHeap & _backwardHeap, NodeID *middle, int *_upperbound, const int edgeBasedOffset, const bool forwardDirection) const {
const NodeID node = _forwardHeap.DeleteMin(); const NodeID node = _forwardHeap.DeleteMin();
const int distance = _forwardHeap.GetKey(node); const int distance = _forwardHeap.GetKey(node);
//INFO("Settled (" << _forwardHeap.GetData( node ).parent << "," << node << ")=" << distance);
if(_backwardHeap.WasInserted(node) ){ if(_backwardHeap.WasInserted(node) ){
const int newDistance = _backwardHeap.GetKey(node) + distance; const int newDistance = _backwardHeap.GetKey(node) + distance;
if(newDistance < *_upperbound ){ if(newDistance < *_upperbound ){

View File

@ -73,18 +73,24 @@ public:
//insert new starting nodes into forward heap, adjusted by previous distances. //insert new starting nodes into forward heap, adjusted by previous distances.
if(searchFrom1stStartNode) { if(searchFrom1stStartNode) {
forward_heap1.Insert(phantomNodePair.startPhantom.edgeBasedNode, -phantomNodePair.startPhantom.weight1, phantomNodePair.startPhantom.edgeBasedNode); forward_heap1.Insert(phantomNodePair.startPhantom.edgeBasedNode, -phantomNodePair.startPhantom.weight1, phantomNodePair.startPhantom.edgeBasedNode);
INFO("fw1: " << phantomNodePair.startPhantom.edgeBasedNode << "´, w: " << -phantomNodePair.startPhantom.weight1);
forward_heap2.Insert(phantomNodePair.startPhantom.edgeBasedNode, -phantomNodePair.startPhantom.weight1, phantomNodePair.startPhantom.edgeBasedNode); forward_heap2.Insert(phantomNodePair.startPhantom.edgeBasedNode, -phantomNodePair.startPhantom.weight1, phantomNodePair.startPhantom.edgeBasedNode);
} INFO("fw2: " << phantomNodePair.startPhantom.edgeBasedNode << "´, w: " << -phantomNodePair.startPhantom.weight1);
}
if(phantomNodePair.startPhantom.isBidirected() && searchFrom2ndStartNode) { if(phantomNodePair.startPhantom.isBidirected() && searchFrom2ndStartNode) {
forward_heap1.Insert(phantomNodePair.startPhantom.edgeBasedNode+1, -phantomNodePair.startPhantom.weight2, phantomNodePair.startPhantom.edgeBasedNode+1); forward_heap1.Insert(phantomNodePair.startPhantom.edgeBasedNode+1, -phantomNodePair.startPhantom.weight2, phantomNodePair.startPhantom.edgeBasedNode+1);
INFO("fw1: " << phantomNodePair.startPhantom.edgeBasedNode+1 << "´, w: " << -phantomNodePair.startPhantom.weight2);
forward_heap2.Insert(phantomNodePair.startPhantom.edgeBasedNode+1, -phantomNodePair.startPhantom.weight2, phantomNodePair.startPhantom.edgeBasedNode+1); forward_heap2.Insert(phantomNodePair.startPhantom.edgeBasedNode+1, -phantomNodePair.startPhantom.weight2, phantomNodePair.startPhantom.edgeBasedNode+1);
INFO("fw2: " << phantomNodePair.startPhantom.edgeBasedNode+1 << "´, w: " << -phantomNodePair.startPhantom.weight2);
} }
//insert new backward nodes into backward heap, unadjusted. //insert new backward nodes into backward heap, unadjusted.
reverse_heap1.Insert(phantomNodePair.targetPhantom.edgeBasedNode, phantomNodePair.targetPhantom.weight1, phantomNodePair.targetPhantom.edgeBasedNode); reverse_heap1.Insert(phantomNodePair.targetPhantom.edgeBasedNode, phantomNodePair.targetPhantom.weight1, phantomNodePair.targetPhantom.edgeBasedNode);
INFO("rv1: " << phantomNodePair.targetPhantom.edgeBasedNode << ", w;" << phantomNodePair.targetPhantom.weight1 );
if(phantomNodePair.targetPhantom.isBidirected() ) { if(phantomNodePair.targetPhantom.isBidirected() ) {
reverse_heap2.Insert(phantomNodePair.targetPhantom.edgeBasedNode+1, phantomNodePair.targetPhantom.weight2, phantomNodePair.targetPhantom.edgeBasedNode+1); reverse_heap2.Insert(phantomNodePair.targetPhantom.edgeBasedNode+1, phantomNodePair.targetPhantom.weight2, phantomNodePair.targetPhantom.edgeBasedNode+1);
} INFO("rv2: " << phantomNodePair.targetPhantom.edgeBasedNode+1 << ", w;" << phantomNodePair.targetPhantom.weight2 );
}
const int forward_offset = phantomNodePair.startPhantom.weight1 + (phantomNodePair.startPhantom.isBidirected() ? phantomNodePair.startPhantom.weight2 : 0); const int forward_offset = phantomNodePair.startPhantom.weight1 + (phantomNodePair.startPhantom.isBidirected() ? phantomNodePair.startPhantom.weight2 : 0);
const int reverse_offset = phantomNodePair.targetPhantom.weight1 + (phantomNodePair.targetPhantom.isBidirected() ? phantomNodePair.targetPhantom.weight2 : 0); const int reverse_offset = phantomNodePair.targetPhantom.weight1 + (phantomNodePair.targetPhantom.isBidirected() ? phantomNodePair.targetPhantom.weight2 : 0);

View File

@ -28,7 +28,7 @@ extern "C" {
} }
#include <boost/filesystem/convenience.hpp> #include <boost/filesystem/convenience.hpp>
#include <luabind/luabind.hpp>
#include <iostream> #include <iostream>
#include <string> #include <string>

View File

@ -1,5 +1,5 @@
# config/cucumber.yml # config/cucumber.yml
##YAML Template ##YAML Template
--- ---
default: --require features default: --require features --tags ~@todo --tag ~@stress
verify: --require features --tags ~@todo --tag ~@stress -f progress verify: --require features --tags ~@todo --tag ~@stress -f progress

View File

@ -23,8 +23,9 @@ or see http://www.gnu.org/licenses/agpl.txt.
#include "Contractor/EdgeBasedGraphFactory.h" #include "Contractor/EdgeBasedGraphFactory.h"
#include "DataStructures/BinaryHeap.h" #include "DataStructures/BinaryHeap.h"
#include "DataStructures/DeallocatingVector.h" #include "DataStructures/DeallocatingVector.h"
#include "DataStructures/NNGrid.h"
#include "DataStructures/QueryEdge.h" #include "DataStructures/QueryEdge.h"
#include "DataStructures/StaticGraph.h"
#include "DataStructures/StaticRTree.h"
#include "Util/BaseConfiguration.h" #include "Util/BaseConfiguration.h"
#include "Util/GraphLoader.h" #include "Util/GraphLoader.h"
#include "Util/InputFileUtil.h" #include "Util/InputFileUtil.h"
@ -92,8 +93,8 @@ int main (int argc, char *argv[]) {
std::string nodeOut(argv[1]); nodeOut += ".nodes"; std::string nodeOut(argv[1]); nodeOut += ".nodes";
std::string edgeOut(argv[1]); edgeOut += ".edges"; std::string edgeOut(argv[1]); edgeOut += ".edges";
std::string graphOut(argv[1]); graphOut += ".hsgr"; std::string graphOut(argv[1]); graphOut += ".hsgr";
std::string ramIndexOut(argv[1]); ramIndexOut += ".ramIndex"; std::string rtree_nodes_path(argv[1]); rtree_nodes_path += ".ramIndex";
std::string fileIndexOut(argv[1]); fileIndexOut += ".fileIndex"; std::string rtree_leafs_path(argv[1]); rtree_leafs_path += ".fileIndex";
/*** Setup Scripting Environment ***/ /*** Setup Scripting Environment ***/
if(!testDataFile( (argc > 3 ? argv[3] : "profile.lua") )) { if(!testDataFile( (argc > 3 ? argv[3] : "profile.lua") )) {
@ -154,7 +155,7 @@ int main (int argc, char *argv[]) {
NodeID edgeBasedNodeNumber = edgeBasedGraphFactory->GetNumberOfNodes(); NodeID edgeBasedNodeNumber = edgeBasedGraphFactory->GetNumberOfNodes();
DeallocatingVector<EdgeBasedEdge> edgeBasedEdgeList; DeallocatingVector<EdgeBasedEdge> edgeBasedEdgeList;
edgeBasedGraphFactory->GetEdgeBasedEdges(edgeBasedEdgeList); edgeBasedGraphFactory->GetEdgeBasedEdges(edgeBasedEdgeList);
DeallocatingVector<EdgeBasedGraphFactory::EdgeBasedNode> nodeBasedEdgeList; std::vector<EdgeBasedGraphFactory::EdgeBasedNode> nodeBasedEdgeList;
edgeBasedGraphFactory->GetEdgeBasedNodes(nodeBasedEdgeList); edgeBasedGraphFactory->GetEdgeBasedNodes(nodeBasedEdgeList);
delete edgeBasedGraphFactory; delete edgeBasedGraphFactory;
@ -174,11 +175,15 @@ int main (int argc, char *argv[]) {
* Building grid-like nearest-neighbor data structure * Building grid-like nearest-neighbor data structure
*/ */
INFO("building grid ..."); INFO("building r-tree ...");
WritableGrid * writeableGrid = new WritableGrid(); StaticRTree<EdgeBasedGraphFactory::EdgeBasedNode> * rtree =
writeableGrid->ConstructGrid(nodeBasedEdgeList, ramIndexOut.c_str(), fileIndexOut.c_str()); new StaticRTree<EdgeBasedGraphFactory::EdgeBasedNode>(
delete writeableGrid; nodeBasedEdgeList,
IteratorbasedCRC32<DeallocatingVector<EdgeBasedGraphFactory::EdgeBasedNode> > crc32; rtree_nodes_path.c_str(),
rtree_leafs_path.c_str()
);
delete rtree;
IteratorbasedCRC32<std::vector<EdgeBasedGraphFactory::EdgeBasedNode> > crc32;
unsigned crc32OfNodeBasedEdgeList = crc32(nodeBasedEdgeList.begin(), nodeBasedEdgeList.end() ); unsigned crc32OfNodeBasedEdgeList = crc32(nodeBasedEdgeList.begin(), nodeBasedEdgeList.end() );
nodeBasedEdgeList.clear(); nodeBasedEdgeList.clear();
INFO("CRC32 based checksum is " << crc32OfNodeBasedEdgeList); INFO("CRC32 based checksum is " << crc32OfNodeBasedEdgeList);

View File

@ -26,7 +26,11 @@ Then /^routability should be$/ do |table|
if got[direction].empty? == false if got[direction].empty? == false
route = way_list json['route_instructions'] route = way_list json['route_instructions']
if route != "w#{i}" if route != "w#{i}"
got[direction] = "testing w#{i}, but got #{route}!?" if row[direction].empty? == true
got[direction] = want
else
got[direction] = "testing w#{i}, but got #{route}!?"
end
elsif want =~ /^\d+s/ elsif want =~ /^\d+s/
time = json['route_summary']['total_time'] time = json['route_summary']['total_time']
got[direction] = "#{time}s" got[direction] = "#{time}s"

View File

@ -42,10 +42,10 @@ def build_ways_from_table table
#add one unconnected way for each row #add one unconnected way for each row
table.hashes.each_with_index do |row,ri| table.hashes.each_with_index do |row,ri|
#NOTE: #NOTE:
#currently osrm crashes when processing an isolated oneway with just 2 nodes, so we use 4 #currently osrm crashes when processing an isolated oneway with just 2 nodes, so we use 4 edges
#this is relatated to the fact that a oneway deadend doesn't make a lot of sense #this is relatated to the fact that a oneway dead-end street doesn't make a lot of sense
#if we stack ways on different x coordinates, outability tests get messed up, because osrm might pick a neighboring way if the one test can't be used. #if we stack ways on different x coordinates, routability tests get messed up, because osrm might pick a neighboring way if the one test can't be used.
#instead we place all lines as a string on the same y coordinate. this prevents using neightboring ways. #instead we place all lines as a string on the same y coordinate. this prevents using neightboring ways.
#a few nodes... #a few nodes...

View File

@ -22,8 +22,8 @@ class FuzzyMatch
end end
def self.match_location got, want def self.match_location got, want
match( got[0], "#{want.lat} ~0.002%" ) && match( got[0], "#{want.lat} ~0.0025%" ) &&
match( got[1], "#{want.lon} ~0.002%" ) match( got[1], "#{want.lon} ~0.0025%" )
end end
end end

View File

@ -16,16 +16,15 @@ Feature: Handle bad data in a graceful manner
Scenario: Only dead-end oneways Scenario: Only dead-end oneways
Given the node map Given the node map
| a | b | c | | a | b | c | d | e |
Given the ways Given the ways
| nodes | oneway | | nodes | oneway |
| ab | yes | | abcde | yes |
| cb | yes |
When I route I should get When I route I should get
| from | to | route | | from | to | route |
| a | b | ab | | b | d | abcde |
@todo @todo
Scenario: Start/end point at the same location Scenario: Start/end point at the same location
@ -59,27 +58,29 @@ Feature: Handle bad data in a graceful manner
| k | -78 | 0 | | k | -78 | 0 |
| l | -80 | 0 | | l | -80 | 0 |
| m | -82 | 0 | | m | -82 | 0 |
| n | -87 | 0 | # | n | -87 | 0 |
| o | -89 | 0 | # | o | -89 | 0 |
And the ways And the ways
| nodes | | nodes |
| ab | # | ab |
| bc | | bc |
| cd | | cd |
| de | | de |
| kl | | kl |
| lm | | lm |
| mn | # | mn |
| no | # | no |
When I route I should get When I route I should get
| from | to | route | | from | to | route |
| a | b | | # | a | b | cd |
| b | c | | # | b | c | cd |
| a | d | | # | a | d | cd |
| c | d | cd | # | c | d | cd |
| l | m | lm | | d | e | de |
| o | l | | # | k | l | kl |
| n | m | | # | l | m | lm |
| o | n | | # | o | l | lm |
# | n | m | lm |
# | o | n | lm |

View File

@ -4,7 +4,7 @@ Testbot uses a signal penalty of 7s.
Background: Background:
Given the profile "testbot" Given the profile "testbot"
Scenario: Traffic signals should incur a delay, without changing distance Scenario: Traffic signals should incur a delay, without changing distance
Given the node map Given the node map
| a | b | c | | a | b | c |
@ -44,11 +44,8 @@ Testbot uses a signal penalty of 7s.
When I route I should get When I route I should get
| from | to | route | time | | from | to | route | time |
| a | b | abc | 10s +-1 |
| a | c | abc | 27s +-1 | | a | c | abc | 27s +-1 |
| d | e | def | 20s +-1 |
| d | f | def | 47s +-1 | | d | f | def | 47s +-1 |
| g | h | ghi | 30s +-1 |
| g | i | ghi | 67s +-1 | | g | i | ghi | 67s +-1 |
Scenario: Passing multiple traffic signals should incur a accumulated delay Scenario: Passing multiple traffic signals should incur a accumulated delay
@ -69,6 +66,7 @@ Testbot uses a signal penalty of 7s.
| from | to | route | time | | from | to | route | time |
| a | e | abcde | 61s +-1 | | a | e | abcde | 61s +-1 |
@todo
Scenario: Signal penalty should not depend on way type Scenario: Signal penalty should not depend on way type
Given the node map Given the node map
| a | b | c | | a | b | c |
@ -114,6 +112,7 @@ Testbot uses a signal penalty of 7s.
| from | to | route | time | | from | to | route | time |
| a | e | abcde | 61s +-1 | | a | e | abcde | 61s +-1 |
@todo
Scenario: Starting or ending at a traffic signal should not incur a delay Scenario: Starting or ending at a traffic signal should not incur a delay
Given the node map Given the node map
| a | b | c | | a | b | c |
@ -154,7 +153,7 @@ Testbot uses a signal penalty of 7s.
And the node map And the node map
| a | | b | | c | | a | | b | | c |
| | | d | | | | | | d | | |
And the nodes And the nodes
| node | highway | | node | highway |
| b | traffic_signals | | b | traffic_signals |
@ -163,7 +162,7 @@ Testbot uses a signal penalty of 7s.
| nodes | highway | | nodes | highway |
| abc | primary | | abc | primary |
| adc | primary | | adc | primary |
When I route I should get When I route I should get
| from | to | route | | from | to | route |
| a | c | adc | | a | c | adc |

View File

@ -1,9 +1,9 @@
@routing @testbot @via @routing @testbot @via
Feature: Via points Feature: Via points
Background: Background:
Given the profile "testbot" Given the profile "testbot"
Scenario: Simple via point Scenario: Simple via point
Given the node map Given the node map
| a | b | c | | a | b | c |
@ -21,12 +21,12 @@ Feature: Via points
Given the node map Given the node map
| a | b | c | | a | b | c |
| | d | | | | d | |
And the ways And the ways
| nodes | | nodes |
| abc | | abc |
| bd | | bd |
When I route I should get When I route I should get
| waypoints | route | | waypoints | route |
| a,d,c | abc,bd,bd,abc | | a,d,c | abc,bd,bd,abc |
@ -34,19 +34,19 @@ Feature: Via points
Scenario: Multiple via points Scenario: Multiple via points
Given the node map Given the node map
| a | | c | | e | | | a | | | | e | f | g | |
| | b | | d | | f | | | b | c | d | | | | h |
And the ways And the ways
| nodes | | nodes |
| ace | | ae |
| bdf |
| ab | | ab |
| bc | | bcd |
| cd |
| de | | de |
| ef | | efg |
| gh |
| dh |
When I route I should get When I route I should get
| waypoints | route | | waypoints | route |
| a,b,c,d,e,f | ab,bc,cd,de,ef | | a,c,f,h | ab,bcd,de,efg,gh |

View File

@ -1,219 +0,0 @@
-- Begin of globals
require("lib/access")
barrier_whitelist = { ["cattle_grid"] = true, ["border_control"] = true, ["toll_booth"] = true, ["sally_port"] = true, ["gate"] = true, ["no"] = true}
access_tag_whitelist = { ["yes"] = true, ["motorcar"] = true, ["motor_vehicle"] = true, ["vehicle"] = true, ["permissive"] = true, ["designated"] = true }
access_tag_blacklist = { ["no"] = true, ["private"] = true, ["agricultural"] = true, ["forestry"] = true }
access_tag_restricted = { ["destination"] = true, ["delivery"] = true }
access_tags = { "motorcar", "motor_vehicle", "vehicle" }
access_tags_hierachy = { "motorcar", "motor_vehicle", "vehicle", "access" }
service_tag_restricted = { ["parking_aisle"] = true }
ignore_in_grid = { ["ferry"] = true }
restriction_exception_tags = { "motorcar", "motor_vehicle", "vehicle" }
speed_profile = {
["motorway"] = 90,
["motorway_link"] = 75,
["trunk"] = 85,
["trunk_link"] = 70,
["primary"] = 65,
["primary_link"] = 60,
["secondary"] = 55,
["secondary_link"] = 50,
["tertiary"] = 40,
["tertiary_link"] = 30,
["unclassified"] = 25,
["residential"] = 25,
["living_street"] = 10,
["service"] = 15,
-- ["track"] = 5,
["ferry"] = 5,
["shuttle_train"] = 10,
["default"] = 50
}
take_minimum_of_speeds = false
obey_oneway = true
obey_bollards = true
use_restrictions = true
ignore_areas = true -- future feature
traffic_signal_penalty = 2
u_turn_penalty = 20
-- End of globals
function get_exceptions(vector)
for i,v in ipairs(restriction_exception_tags) do
vector:Add(v)
end
end
local function parse_maxspeed(source)
if source == nil then
return 0
end
local n = tonumber(source:match("%d*"))
if n == nil then
n = 0
end
if string.match(source, "mph") or string.match(source, "mp/h") then
n = (n*1609)/1000;
end
return math.abs(n)
end
function node_function (node)
local barrier = node.tags:Find ("barrier")
local access = Access.find_access_tag(node, access_tags_hierachy)
local traffic_signal = node.tags:Find("highway")
--flag node if it carries a traffic light
if traffic_signal == "traffic_signals" then
node.traffic_light = true;
end
-- parse access and barrier tags
if access and access ~= "" then
if access_tag_blacklist[access] then
node.bollard = true
end
elseif barrier and barrier ~= "" then
if barrier_whitelist[barrier] then
return
else
node.bollard = true
end
end
return 1
end
function way_function (way)
-- First, get the properties of each way that we come across
local highway = way.tags:Find("highway")
local name = way.tags:Find("name")
local ref = way.tags:Find("ref")
local junction = way.tags:Find("junction")
local route = way.tags:Find("route")
local maxspeed = parse_maxspeed(way.tags:Find ( "maxspeed") )
local maxspeed_forward = tonumber(way.tags:Find( "maxspeed:forward"))
local maxspeed_backward = tonumber(way.tags:Find( "maxspeed:backward"))
local barrier = way.tags:Find("barrier")
local oneway = way.tags:Find("oneway")
local cycleway = way.tags:Find("cycleway")
local duration = way.tags:Find("duration")
local service = way.tags:Find("service")
local area = way.tags:Find("area")
local access = Access.find_access_tag(way, access_tags_hierachy)
-- Second, parse the way according to these properties
if ignore_areas and ("yes" == area) then
return 0
end
-- Check if we are allowed to access the way
if access_tag_blacklist[access] then
return 0
end
-- Set the name that will be used for instructions
if "" ~= ref then
way.name = ref
elseif "" ~= name then
way.name = name
-- else
-- way.name = highway -- if no name exists, use way type
end
if "roundabout" == junction then
way.roundabout = true;
end
-- Handling ferries and piers
if (speed_profile[route] ~= nil and speed_profile[route] > 0) then
if durationIsValid(duration) then
way.duration = math.max( parseDuration(duration), 1 );
end
way.direction = Way.bidirectional
if speed_profile[route] ~= nil then
highway = route;
end
if tonumber(way.duration) < 0 then
way.speed = speed_profile[highway]
end
end
-- Set the avg speed on the way if it is accessible by road class
if (speed_profile[highway] ~= nil and way.speed == -1 ) then
if maxspeed > speed_profile[highway] then
way.speed = maxspeed
else
if 0 == maxspeed then
maxspeed = math.huge
end
way.speed = math.min(speed_profile[highway], maxspeed)
end
end
-- Set the avg speed on ways that are marked accessible
if "" ~= highway and access_tag_whitelist[access] and way.speed == -1 then
if 0 == maxspeed then
maxspeed = math.huge
end
way.speed = math.min(speed_profile["default"], maxspeed)
end
-- Set access restriction flag if access is allowed under certain restrictions only
if access ~= "" and access_tag_restricted[access] then
way.is_access_restricted = true
end
-- Set access restriction flag if service is allowed under certain restrictions only
if service ~= "" and service_tag_restricted[service] then
way.is_access_restricted = true
end
-- Set direction according to tags on way
if obey_oneway then
if oneway == "no" or oneway == "0" or oneway == "false" then
way.direction = Way.bidirectional
elseif oneway == "-1" then
way.direction = Way.opposite
elseif oneway == "yes" or oneway == "1" or oneway == "true" or junction == "roundabout" or highway == "motorway_link" or highway == "motorway" then
way.direction = Way.oneway
else
way.direction = Way.bidirectional
end
else
way.direction = Way.bidirectional
end
-- Override speed settings if explicit forward/backward maxspeeds are given
if maxspeed_forward ~= nil and maxspeed_forward > 0 then
if Way.bidirectional == way.direction then
way.backward_speed = way.speed
end
way.speed = maxspeed_forward
end
if maxspeed_backward ~= nil and maxspeed_backward > 0 then
way.backward_speed = maxspeed_backward
end
-- Override general direction settings of there is a specific one for our mode of travel
if ignore_in_grid[highway] ~= nil and ignore_in_grid[highway] then
way.ignore_in_grid = true
end
way.type = 1
return 1
end
-- These are wrappers to parse vectors of nodes and ways and thus to speed up any tracing JIT
function node_vector_function(vector)
for v in vector.nodes do
node_function(v)
end
end

1
profile.lua Symbolic link
View File

@ -0,0 +1 @@
profiles/car.lua

View File

@ -11,10 +11,10 @@ service_tag_restricted = { ["parking_aisle"] = true }
ignore_in_grid = { ["ferry"] = true } ignore_in_grid = { ["ferry"] = true }
restriction_exception_tags = { "motorcar", "motor_vehicle", "vehicle" } restriction_exception_tags = { "motorcar", "motor_vehicle", "vehicle" }
speed_profile = { speed_profile = {
["motorway"] = 90, ["motorway"] = 90,
["motorway_link"] = 75, ["motorway_link"] = 75,
["trunk"] = 85, ["trunk"] = 85,
["trunk_link"] = 70, ["trunk_link"] = 70,
["primary"] = 65, ["primary"] = 65,
["primary_link"] = 60, ["primary_link"] = 60,
@ -43,7 +43,7 @@ u_turn_penalty = 20
-- End of globals -- End of globals
function get_exceptions(vector) function get_exceptions(vector)
for i,v in ipairs(restriction_exception_tags) do for i,v in ipairs(restriction_exception_tags) do
vector:Add(v) vector:Add(v)
end end
end end
@ -66,13 +66,13 @@ function node_function (node)
local barrier = node.tags:Find ("barrier") local barrier = node.tags:Find ("barrier")
local access = Access.find_access_tag(node, access_tags_hierachy) local access = Access.find_access_tag(node, access_tags_hierachy)
local traffic_signal = node.tags:Find("highway") local traffic_signal = node.tags:Find("highway")
--flag node if it carries a traffic light --flag node if it carries a traffic light
if traffic_signal == "traffic_signals" then if traffic_signal == "traffic_signals" then
node.traffic_light = true; node.traffic_light = true;
end end
-- parse access and barrier tags -- parse access and barrier tags
if access and access ~= "" then if access and access ~= "" then
if access_tag_blacklist[access] then if access_tag_blacklist[access] then
@ -90,35 +90,40 @@ end
function way_function (way) function way_function (way)
-- First, get the properties of each way that we come across -- we dont route over areas
local highway = way.tags:Find("highway") local area = way.tags:Find("area")
local name = way.tags:Find("name") if ignore_areas and ("yes" == area) then
local ref = way.tags:Find("ref") return 0
local junction = way.tags:Find("junction") end
local route = way.tags:Find("route")
local maxspeed = parse_maxspeed(way.tags:Find ( "maxspeed") ) -- check if oneway tag is unsupported
local maxspeed_forward = parse_maxspeed(way.tags:Find( "maxspeed:forward")) local oneway = way.tags:Find("oneway")
local maxspeed_backward = parse_maxspeed(way.tags:Find( "maxspeed:backward")) if "reversible" == oneway then
local barrier = way.tags:Find("barrier") return 0
local oneway = way.tags:Find("oneway") end
local cycleway = way.tags:Find("cycleway")
local duration = way.tags:Find("duration") -- Check if we are allowed to access the way
local service = way.tags:Find("service") local access = Access.find_access_tag(way, access_tags_hierachy)
local area = way.tags:Find("area") if access_tag_blacklist[access] then
local access = Access.find_access_tag(way, access_tags_hierachy) return 0
end
-- Second, parse the way according to these properties -- Second, parse the way according to these properties
local highway = way.tags:Find("highway")
local name = way.tags:Find("name")
local ref = way.tags:Find("ref")
local junction = way.tags:Find("junction")
local route = way.tags:Find("route")
local maxspeed = parse_maxspeed(way.tags:Find ( "maxspeed") )
local maxspeed_forward = parse_maxspeed(way.tags:Find( "maxspeed:forward"))
local maxspeed_backward = parse_maxspeed(way.tags:Find( "maxspeed:backward"))
local barrier = way.tags:Find("barrier")
local cycleway = way.tags:Find("cycleway")
local duration = way.tags:Find("duration")
local service = way.tags:Find("service")
if ignore_areas and ("yes" == area) then
return 0
end
-- Check if we are allowed to access the way
if access_tag_blacklist[access] then
return 0
end
-- Set the name that will be used for instructions -- Set the name that will be used for instructions
if "" ~= ref then if "" ~= ref then
way.name = ref way.name = ref
elseif "" ~= name then elseif "" ~= name then
@ -126,87 +131,82 @@ function way_function (way)
-- else -- else
-- way.name = highway -- if no name exists, use way type -- way.name = highway -- if no name exists, use way type
end end
if "roundabout" == junction then if "roundabout" == junction then
way.roundabout = true; way.roundabout = true;
end end
-- Handling ferries and piers -- Handling ferries and piers
if (speed_profile[route] ~= nil and speed_profile[route] > 0) then if (speed_profile[route] ~= nil and speed_profile[route] > 0) then
if durationIsValid(duration) then if durationIsValid(duration) then
way.duration = math.max( parseDuration(duration), 1 ); way.duration = math.max( parseDuration(duration), 1 );
end end
way.direction = Way.bidirectional way.direction = Way.bidirectional
if speed_profile[route] ~= nil then if speed_profile[route] ~= nil then
highway = route; highway = route;
end end
if tonumber(way.duration) < 0 then if tonumber(way.duration) < 0 then
way.speed = speed_profile[highway] way.speed = speed_profile[highway]
end end
end end
-- Set the avg speed on the way if it is accessible by road class -- Set the avg speed on the way if it is accessible by road class
if (speed_profile[highway] ~= nil and way.speed == -1 ) then if (speed_profile[highway] ~= nil and way.speed == -1 ) then
if maxspeed > speed_profile[highway] then if maxspeed > speed_profile[highway] then
way.speed = maxspeed way.speed = maxspeed
else else
if 0 == maxspeed then if 0 == maxspeed then
maxspeed = math.huge maxspeed = math.huge
end end
way.speed = math.min(speed_profile[highway], maxspeed) way.speed = math.min(speed_profile[highway], maxspeed)
end end
end end
-- Set the avg speed on ways that are marked accessible -- Set the avg speed on ways that are marked accessible
if "" ~= highway and access_tag_whitelist[access] and way.speed == -1 then if "" ~= highway and access_tag_whitelist[access] and way.speed == -1 then
if 0 == maxspeed then if 0 == maxspeed then
maxspeed = math.huge maxspeed = math.huge
end
way.speed = math.min(speed_profile["default"], maxspeed)
end end
way.speed = math.min(speed_profile["default"], maxspeed)
end
-- Set access restriction flag if access is allowed under certain restrictions only -- Set access restriction flag if access is allowed under certain restrictions only
if access ~= "" and access_tag_restricted[access] then if access ~= "" and access_tag_restricted[access] then
way.is_access_restricted = true way.is_access_restricted = true
end end
-- Set access restriction flag if service is allowed under certain restrictions only -- Set access restriction flag if service is allowed under certain restrictions only
if service ~= "" and service_tag_restricted[service] then if service ~= "" and service_tag_restricted[service] then
way.is_access_restricted = true way.is_access_restricted = true
end end
-- Set direction according to tags on way -- Set direction according to tags on way
if obey_oneway then way.direction = Way.bidirectional
if oneway == "no" or oneway == "0" or oneway == "false" then if obey_oneway then
way.direction = Way.bidirectional if oneway == "-1" then
elseif oneway == "-1" then
way.direction = Way.opposite way.direction = Way.opposite
elseif oneway == "yes" or oneway == "1" or oneway == "true" or junction == "roundabout" or highway == "motorway_link" or highway == "motorway" then elseif oneway == "yes" or oneway == "1" or oneway == "true" or junction == "roundabout" or highway == "motorway_link" or highway == "motorway" then
way.direction = Way.oneway way.direction = Way.oneway
else
way.direction = Way.bidirectional
end
else
way.direction = Way.bidirectional
end end
end
-- Override speed settings if explicit forward/backward maxspeeds are given -- Override speed settings if explicit forward/backward maxspeeds are given
if maxspeed_forward ~= nil and maxspeed_forward > 0 then if maxspeed_forward ~= nil and maxspeed_forward > 0 then
if Way.bidirectional == way.direction then if Way.bidirectional == way.direction then
way.backward_speed = way.speed way.backward_speed = way.speed
end
way.speed = maxspeed_forward
end
if maxspeed_backward ~= nil and maxspeed_backward > 0 then
way.backward_speed = maxspeed_backward
end end
way.speed = maxspeed_forward
end
if maxspeed_backward ~= nil and maxspeed_backward > 0 then
way.backward_speed = maxspeed_backward
end
-- Override general direction settings of there is a specific one for our mode of travel -- Override general direction settings of there is a specific one for our mode of travel
if ignore_in_grid[highway] ~= nil and ignore_in_grid[highway] then
if ignore_in_grid[highway] ~= nil and ignore_in_grid[highway] then
way.ignore_in_grid = true way.ignore_in_grid = true
end end
way.type = 1
way.type = 1
return 1 return 1
end end

View File

@ -3,7 +3,7 @@ local ipairs = ipairs
module "Access" module "Access"
function find_access_tag(source,access_tags_hierachy) function find_access_tag(source,access_tags_hierachy)
for i,v in ipairs(access_tags_hierachy) do for i,v in ipairs(access_tags_hierachy) do
local tag = source.tags:Find(v) local tag = source.tags:Find(v)
if tag ~= '' then if tag ~= '' then
return tag return tag