Merge branch 'master' of https://DennisOSRM@github.com/DennisOSRM/Project-OSRM.git
This commit is contained in:
commit
95d8d44259
@ -22,7 +22,7 @@ or see http://www.gnu.org/licenses/agpl.txt.
|
||||
#define DOUGLASPEUCKER_H_
|
||||
|
||||
#include <cfloat>
|
||||
#include <stack>
|
||||
#include "../DataStructures/SimpleStack.h"
|
||||
|
||||
/*This class object computes the bitvector of indicating generalized input points
|
||||
* according to the (Ramer-)Douglas-Peucker algorithm.
|
||||
@ -39,9 +39,9 @@ class DouglasPeucker {
|
||||
private:
|
||||
typedef std::pair<std::size_t, std::size_t> PairOfPoints;
|
||||
//Stack to simulate the recursion
|
||||
std::stack<PairOfPoints > recursionStack;
|
||||
SimpleStack<PairOfPoints > recursionStack;
|
||||
|
||||
double ComputeDistance(const _Coordinate& inputPoint, const _Coordinate& source, const _Coordinate& target) {
|
||||
double ComputeDistanceOfPointToLine(const _Coordinate& inputPoint, const _Coordinate& source, const _Coordinate& target) {
|
||||
double r;
|
||||
const double x = (double)inputPoint.lat;
|
||||
const double y = (double)inputPoint.lon;
|
||||
@ -81,6 +81,7 @@ public:
|
||||
std::size_t leftBorderOfRange = 0;
|
||||
std::size_t rightBorderOfRange = 1;
|
||||
//Sweep linerarily over array and identify those ranges that need to be checked
|
||||
recursionStack.hint(inputVector.size());
|
||||
do {
|
||||
assert(inputVector[leftBorderOfRange].necessary);
|
||||
assert(inputVector[inputVector.size()-1].necessary);
|
||||
@ -104,7 +105,7 @@ public:
|
||||
std::size_t indexOfFarthestElement = pair.second;
|
||||
//find index idx of element with maxDistance
|
||||
for(std::size_t i = pair.first+1; i < pair.second; ++i){
|
||||
double distance = std::fabs(ComputeDistance(inputVector[i].location, inputVector[pair.first].location, inputVector[pair.second].location));
|
||||
double distance = std::fabs(ComputeDistanceOfPointToLine(inputVector[i].location, inputVector[pair.first].location, inputVector[pair.second].location));
|
||||
if(distance > DouglasPeuckerThresholds[zoomLevel] && distance > maxDistance) {
|
||||
indexOfFarthestElement = i;
|
||||
maxDistance = distance;
|
||||
|
@ -24,28 +24,28 @@ or see http://www.gnu.org/licenses/agpl.txt.
|
||||
#include <list>
|
||||
#include <boost/unordered_map.hpp>
|
||||
|
||||
template<typename ValueT>
|
||||
template<typename KeyT, typename ValueT>
|
||||
class LRUCache {
|
||||
private:
|
||||
struct CacheEntry {
|
||||
CacheEntry(unsigned k, ValueT v) : key(k), value(v) {}
|
||||
unsigned key;
|
||||
CacheEntry(KeyT k, ValueT v) : key(k), value(v) {}
|
||||
KeyT key;
|
||||
ValueT value;
|
||||
};
|
||||
unsigned capacity;
|
||||
std::list<CacheEntry> itemsInCache;
|
||||
boost::unordered_map<unsigned, typename std::list<CacheEntry>::iterator > positionMap;
|
||||
boost::unordered_map<KeyT, typename std::list<CacheEntry>::iterator > positionMap;
|
||||
public:
|
||||
LRUCache(unsigned c) : capacity(c) {}
|
||||
|
||||
bool Holds(unsigned key) {
|
||||
bool Holds(KeyT key) {
|
||||
if(positionMap.find(key) != positionMap.end()) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
void Insert(const unsigned key, ValueT value) {
|
||||
void Insert(const KeyT key, ValueT &value) {
|
||||
itemsInCache.push_front(CacheEntry(key, value));
|
||||
positionMap.insert(std::make_pair(key, itemsInCache.begin()));
|
||||
if(itemsInCache.size() > capacity) {
|
||||
@ -53,7 +53,7 @@ public:
|
||||
itemsInCache.pop_back();
|
||||
}
|
||||
}
|
||||
bool Fetch(const unsigned key, ValueT& result) {
|
||||
bool Fetch(const KeyT key, ValueT& result) {
|
||||
if(Holds(key)) {
|
||||
CacheEntry e = *(positionMap.find(key)->second);
|
||||
result = e.value;
|
||||
|
@ -147,13 +147,11 @@ public:
|
||||
/** search for point on edge close to source */
|
||||
unsigned fileIndex = GetFileIndexForLatLon(startCoord.lat, startCoord.lon);
|
||||
std::vector<_GridEdge> candidates;
|
||||
|
||||
for(int j = -32768; j < (32768+1); j+=32768) {
|
||||
for(int i = -1; i < 2; i++){
|
||||
GetContentsOfFileBucket(fileIndex+i+j, candidates);
|
||||
}
|
||||
}
|
||||
|
||||
_GridEdge smallestEdge;
|
||||
_Coordinate tmp, newEndpoint;
|
||||
double dist = numeric_limits<double>::max();
|
||||
@ -179,7 +177,6 @@ public:
|
||||
//INFO("b) " << candidate.edgeBasedNode << ", dist: " << tmpDist);
|
||||
}
|
||||
}
|
||||
|
||||
// INFO("startcoord: " << smallestEdge.startCoord << ", tgtcoord" << smallestEdge.targetCoord << "result: " << newEndpoint);
|
||||
// INFO("length of old edge: " << LengthOfVector(smallestEdge.startCoord, smallestEdge.targetCoord));
|
||||
// INFO("Length of new edge: " << LengthOfVector(smallestEdge.startCoord, newEndpoint));
|
||||
@ -253,16 +250,16 @@ public:
|
||||
|
||||
|
||||
private:
|
||||
void BuildCellIndexToFileIndexMap(const unsigned ramIndex, boost::unordered_map<unsigned ,unsigned >& cellMap){
|
||||
inline void BuildCellIndexToFileIndexMap(const unsigned ramIndex, boost::unordered_map<unsigned ,unsigned >& cellMap){
|
||||
unsigned lineBase = ramIndex/1024;
|
||||
lineBase = lineBase*32*32768;
|
||||
unsigned columnBase = ramIndex%1024;
|
||||
columnBase=columnBase*32;
|
||||
for (int i = 0;i < 32;i++) {
|
||||
for (int j = 0;j < 32;j++) {
|
||||
for (int i = 0;i < 32;++i) {
|
||||
for (int j = 0;j < 32;++j) {
|
||||
unsigned fileIndex = lineBase + i * 32768 + columnBase + j;
|
||||
unsigned cellIndex = i * 32 + j;
|
||||
cellMap.insert(std::make_pair(fileIndex, cellIndex));
|
||||
cellMap[fileIndex] = cellIndex;
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -369,7 +366,7 @@ private:
|
||||
return;
|
||||
}
|
||||
|
||||
std::vector<unsigned long> cellIndex(32*32);
|
||||
unsigned long cellIndex[32*32];
|
||||
|
||||
boost::unordered_map< unsigned, unsigned > cellMap(1024);
|
||||
BuildCellIndexToFileIndexMap(ramIndex, cellMap);
|
||||
@ -382,8 +379,8 @@ private:
|
||||
}
|
||||
|
||||
localStream->seekg(startIndexInFile);
|
||||
localStream->read((char*) &cellIndex[0], 32*32*sizeof(unsigned long));
|
||||
assert(cellMap.find(fileIndex) != cellMap.end());
|
||||
localStream->read((char*) cellIndex, 32*32*sizeof(unsigned long));
|
||||
assert(cellMap.find(fileIndex) != cellMap.end());
|
||||
if(cellIndex[cellMap.find(fileIndex)->second] == ULONG_MAX) {
|
||||
return;
|
||||
}
|
||||
@ -397,7 +394,7 @@ private:
|
||||
break;
|
||||
result.push_back(gridEdge);
|
||||
} while(true);
|
||||
}
|
||||
}
|
||||
|
||||
void AddEdge(_GridEdge edge) {
|
||||
std::vector<BresenhamPixel> indexList;
|
||||
|
@ -29,40 +29,38 @@ or see http://www.gnu.org/licenses/agpl.txt.
|
||||
|
||||
template<typename NodeT>
|
||||
struct NodeCoords {
|
||||
typedef unsigned key_type; //type of NodeID
|
||||
typedef int value_type; //type of lat,lons
|
||||
typedef unsigned key_type; //type of NodeID
|
||||
typedef int value_type; //type of lat,lons
|
||||
|
||||
NodeCoords(int _lat, int _lon, NodeT _id) : lat(_lat), lon(_lon), id(_id) {}
|
||||
NodeCoords() : lat(INT_MAX), lon(INT_MAX), id(UINT_MAX) {}
|
||||
int lat;
|
||||
int lon;
|
||||
NodeT id;
|
||||
NodeCoords(int _lat, int _lon, NodeT _id) : lat(_lat), lon(_lon), id(_id) {}
|
||||
NodeCoords() : lat(INT_MAX), lon(INT_MAX), id(UINT_MAX) {}
|
||||
int lat;
|
||||
int lon;
|
||||
NodeT id;
|
||||
|
||||
static NodeCoords<NodeT> min_value()
|
||||
{
|
||||
return NodeCoords<NodeT>(-90*100000,-180*100000,numeric_limits<NodeT>::min());
|
||||
}
|
||||
static NodeCoords<NodeT> max_value()
|
||||
{
|
||||
return NodeCoords<NodeT>(90*100000, 180*100000, numeric_limits<NodeT>::max());
|
||||
}
|
||||
static NodeCoords<NodeT> min_value() {
|
||||
return NodeCoords<NodeT>(-90*100000,-180*100000,numeric_limits<NodeT>::min());
|
||||
}
|
||||
static NodeCoords<NodeT> max_value() {
|
||||
return NodeCoords<NodeT>(90*100000, 180*100000, numeric_limits<NodeT>::max());
|
||||
}
|
||||
|
||||
value_type operator[](size_t n) const {
|
||||
switch(n) {
|
||||
case 1:
|
||||
return lat;
|
||||
break;
|
||||
case 0:
|
||||
return lon;
|
||||
break;
|
||||
default:
|
||||
assert(false);
|
||||
return UINT_MAX;
|
||||
break;
|
||||
}
|
||||
assert(false);
|
||||
return UINT_MAX;
|
||||
}
|
||||
value_type operator[](size_t n) const {
|
||||
switch(n) {
|
||||
case 1:
|
||||
return lat;
|
||||
break;
|
||||
case 0:
|
||||
return lon;
|
||||
break;
|
||||
default:
|
||||
assert(false);
|
||||
return UINT_MAX;
|
||||
break;
|
||||
}
|
||||
assert(false);
|
||||
return UINT_MAX;
|
||||
}
|
||||
};
|
||||
|
||||
#endif //_NODE_COORDS_H
|
||||
|
@ -31,46 +31,41 @@ or see http://www.gnu.org/licenses/agpl.txt.
|
||||
|
||||
class NodeInformationHelpDesk{
|
||||
public:
|
||||
NodeInformationHelpDesk(const char* ramIndexInput, const char* fileIndexInput, unsigned _numberOfNodes) : numberOfNodes(_numberOfNodes) {
|
||||
NodeInformationHelpDesk(const char* ramIndexInput, const char* fileIndexInput, const unsigned _numberOfNodes) : numberOfNodes(_numberOfNodes) {
|
||||
readOnlyGrid = new ReadOnlyGrid(ramIndexInput,fileIndexInput);
|
||||
int2ExtNodeMap = new vector<_Coordinate>();
|
||||
int2ExtNodeMap->reserve(numberOfNodes);
|
||||
assert(0 == int2ExtNodeMap->size());
|
||||
coordinateVector.reserve(numberOfNodes);
|
||||
assert(0 == coordinateVector.size());
|
||||
}
|
||||
|
||||
~NodeInformationHelpDesk() {
|
||||
delete int2ExtNodeMap;
|
||||
delete readOnlyGrid;
|
||||
}
|
||||
void initNNGrid(ifstream& in) {
|
||||
while(!in.eof()) {
|
||||
NodeInfo b;
|
||||
in.read((char *)&b, sizeof(b));
|
||||
int2ExtNodeMap->push_back(_Coordinate(b.lat, b.lon));
|
||||
coordinateVector.push_back(_Coordinate(b.lat, b.lon));
|
||||
}
|
||||
in.close();
|
||||
readOnlyGrid->OpenIndexFiles();
|
||||
}
|
||||
|
||||
inline int getLatitudeOfNode(const NodeID node) const {
|
||||
return int2ExtNodeMap->at(node).lat;
|
||||
}
|
||||
inline int getLatitudeOfNode(const NodeID node) const { return coordinateVector.at(node).lat; }
|
||||
|
||||
inline int getLongitudeOfNode(const NodeID node) const { return int2ExtNodeMap->at(node).lon; }
|
||||
inline int getLongitudeOfNode(const NodeID node) const { return coordinateVector.at(node).lon; }
|
||||
|
||||
NodeID getNumberOfNodes() const { return numberOfNodes; }
|
||||
NodeID getNumberOfNodes2() const { return int2ExtNodeMap->size(); }
|
||||
inline NodeID getNumberOfNodes() const { return numberOfNodes; }
|
||||
inline NodeID getNumberOfNodes2() const { return coordinateVector.size(); }
|
||||
|
||||
inline void FindNearestNodeCoordForLatLon(const _Coordinate& coord, _Coordinate& result) {
|
||||
inline void FindNearestNodeCoordForLatLon(const _Coordinate& coord, _Coordinate& result) const {
|
||||
readOnlyGrid->FindNearestCoordinateOnEdgeInNodeBasedGraph(coord, result);
|
||||
}
|
||||
bool FindPhantomNodeForCoordinate( const _Coordinate & location, PhantomNode & resultNode) {
|
||||
return readOnlyGrid->FindPhantomNodeForCoordinate(location, resultNode);
|
||||
inline void FindPhantomNodeForCoordinate( const _Coordinate & location, PhantomNode & resultNode) const {
|
||||
readOnlyGrid->FindPhantomNodeForCoordinate(location, resultNode);
|
||||
}
|
||||
|
||||
inline bool FindRoutingStarts(const _Coordinate &start, const _Coordinate &target, PhantomNodes & phantomNodes) {
|
||||
inline void FindRoutingStarts(const _Coordinate &start, const _Coordinate &target, PhantomNodes & phantomNodes) const {
|
||||
readOnlyGrid->FindRoutingStarts(start, target, phantomNodes);
|
||||
return true;
|
||||
}
|
||||
|
||||
inline void FindNearestPointOnEdge(const _Coordinate & input, _Coordinate& output){
|
||||
@ -78,7 +73,7 @@ public:
|
||||
}
|
||||
|
||||
private:
|
||||
vector<_Coordinate> * int2ExtNodeMap;
|
||||
std::vector<_Coordinate> coordinateVector;
|
||||
ReadOnlyGrid * readOnlyGrid;
|
||||
unsigned numberOfNodes;
|
||||
};
|
||||
|
@ -23,6 +23,7 @@ or see http://www.gnu.org/licenses/agpl.txt.
|
||||
|
||||
#include <climits>
|
||||
#include <deque>
|
||||
#include "SimpleStack.h"
|
||||
|
||||
#include <boost/thread.hpp>
|
||||
|
||||
@ -36,7 +37,7 @@ struct _HeapData {
|
||||
_HeapData( NodeID p ) : parent(p) { }
|
||||
};
|
||||
|
||||
typedef boost::thread_specific_ptr<BinaryHeap< NodeID, NodeID, int, _HeapData> > HeapPtr;
|
||||
typedef boost::thread_specific_ptr<BinaryHeap< NodeID, NodeID, int, _HeapData, UnorderedMapStorage<NodeID, int> > > HeapPtr;
|
||||
|
||||
template<class EdgeData, class GraphT>
|
||||
class SearchEngine {
|
||||
@ -57,13 +58,15 @@ public:
|
||||
}
|
||||
|
||||
inline void InitializeThreadLocalStorageIfNecessary() {
|
||||
if(!_forwardHeap.get())
|
||||
_forwardHeap.reset(new BinaryHeap< NodeID, NodeID, int, _HeapData>(nodeHelpDesk->getNumberOfNodes()));
|
||||
if(!_forwardHeap.get()) {
|
||||
_forwardHeap.reset(new BinaryHeap< NodeID, NodeID, int, _HeapData, UnorderedMapStorage<NodeID, int> >(nodeHelpDesk->getNumberOfNodes()));
|
||||
}
|
||||
else
|
||||
_forwardHeap->Clear();
|
||||
|
||||
if(!_backwardHeap.get())
|
||||
_backwardHeap.reset(new BinaryHeap< NodeID, NodeID, int, _HeapData>(nodeHelpDesk->getNumberOfNodes()));
|
||||
if(!_backwardHeap.get()) {
|
||||
_backwardHeap.reset(new BinaryHeap< NodeID, NodeID, int, _HeapData, UnorderedMapStorage<NodeID, int> >(nodeHelpDesk->getNumberOfNodes()));
|
||||
}
|
||||
else
|
||||
_backwardHeap->Clear();
|
||||
}
|
||||
@ -117,20 +120,16 @@ public:
|
||||
pathNode = _backwardHeap->GetData(pathNode).parent;
|
||||
packedPath.push_back(pathNode);
|
||||
}
|
||||
for(deque<NodeID>::size_type i = 0;i < packedPath.size() - 1;i++){
|
||||
_UnpackEdge(packedPath[i], packedPath[i + 1], path);
|
||||
}
|
||||
|
||||
_UnpackPath(packedPath, path);
|
||||
return _upperbound;
|
||||
}
|
||||
|
||||
inline bool FindRoutingStarts(const _Coordinate & start, const _Coordinate & target, PhantomNodes & routingStarts) const {
|
||||
inline void FindRoutingStarts(const _Coordinate & start, const _Coordinate & target, PhantomNodes & routingStarts) const {
|
||||
nodeHelpDesk->FindRoutingStarts(start, target, routingStarts);
|
||||
return true;
|
||||
}
|
||||
|
||||
inline bool FindPhantomNodeForCoordinate(const _Coordinate & location, PhantomNode & result) const {
|
||||
return nodeHelpDesk->FindPhantomNodeForCoordinate(location, result);
|
||||
inline void FindPhantomNodeForCoordinate(const _Coordinate & location, PhantomNode & result) const {
|
||||
nodeHelpDesk->FindPhantomNodeForCoordinate(location, result);
|
||||
}
|
||||
|
||||
inline NodeID GetNameIDForOriginDestinationNodeID(NodeID s, NodeID t) const {
|
||||
@ -226,41 +225,52 @@ private:
|
||||
}
|
||||
}
|
||||
|
||||
inline bool _UnpackEdge(const NodeID source, const NodeID target, std::vector<_PathData> & path) const {
|
||||
assert(source != target);
|
||||
//find edge first.
|
||||
typename GraphT::EdgeIterator smallestEdge = SPECIAL_EDGEID;
|
||||
int smallestWeight = INT_MAX;
|
||||
for(typename GraphT::EdgeIterator eit = _graph->BeginEdges(source);eit < _graph->EndEdges(source);eit++){
|
||||
const int weight = _graph->GetEdgeData(eit).distance;
|
||||
if(_graph->GetTarget(eit) == target && weight < smallestWeight && _graph->GetEdgeData(eit).forward){
|
||||
smallestEdge = eit;
|
||||
smallestWeight = weight;
|
||||
}
|
||||
inline void _UnpackPath(const std::deque<NodeID> & packedPath, std::vector<_PathData> & unpackedPath) const {
|
||||
const std::deque<NodeID>::size_type sizeOfPackedPath = packedPath.size();
|
||||
SimpleStack<std::pair<NodeID, NodeID> > recursionStack(sizeOfPackedPath);
|
||||
|
||||
//We have to push the path in reverse order onto the stack because it's LIFO.
|
||||
for(std::deque<NodeID>::size_type i = sizeOfPackedPath-1; i > 0; --i){
|
||||
recursionStack.push(std::make_pair(packedPath[i-1], packedPath[i]));
|
||||
}
|
||||
|
||||
if(smallestEdge == SPECIAL_EDGEID){
|
||||
for(typename GraphT::EdgeIterator eit = _graph->BeginEdges(target);eit < _graph->EndEdges(target);eit++){
|
||||
std::pair<NodeID, NodeID> edge;
|
||||
while(!recursionStack.empty()) {
|
||||
edge = recursionStack.top();
|
||||
recursionStack.pop();
|
||||
|
||||
typename GraphT::EdgeIterator smallestEdge = SPECIAL_EDGEID;
|
||||
int smallestWeight = INT_MAX;
|
||||
for(typename GraphT::EdgeIterator eit = _graph->BeginEdges(edge.first);eit < _graph->EndEdges(edge.first);++eit){
|
||||
const int weight = _graph->GetEdgeData(eit).distance;
|
||||
if(_graph->GetTarget(eit) == source && weight < smallestWeight && _graph->GetEdgeData(eit).backward){
|
||||
if(_graph->GetTarget(eit) == edge.second && weight < smallestWeight && _graph->GetEdgeData(eit).forward){
|
||||
smallestEdge = eit;
|
||||
smallestWeight = weight;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
assert(smallestWeight != INT_MAX);
|
||||
if(smallestEdge == SPECIAL_EDGEID){
|
||||
for(typename GraphT::EdgeIterator eit = _graph->BeginEdges(edge.second);eit < _graph->EndEdges(edge.second);++eit){
|
||||
const int weight = _graph->GetEdgeData(eit).distance;
|
||||
if(_graph->GetTarget(eit) == edge.first && weight < smallestWeight && _graph->GetEdgeData(eit).backward){
|
||||
smallestEdge = eit;
|
||||
smallestWeight = weight;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
const EdgeData& ed = _graph->GetEdgeData(smallestEdge);
|
||||
if(ed.shortcut) {//unpack
|
||||
const NodeID middle = ed.via;
|
||||
_UnpackEdge(source, middle, path);
|
||||
_UnpackEdge(middle, target, path);
|
||||
return false;
|
||||
} else {
|
||||
assert(!ed.shortcut);
|
||||
path.push_back(_PathData(ed.via, ed.nameID, ed.turnInstruction, ed.distance) );
|
||||
return true;
|
||||
assert(smallestWeight != INT_MAX);
|
||||
|
||||
const EdgeData& ed = _graph->GetEdgeData(smallestEdge);
|
||||
if(ed.shortcut) {//unpack
|
||||
const NodeID middle = ed.via;
|
||||
//again, we need to this in reversed order
|
||||
recursionStack.push(std::make_pair(middle, edge.second));
|
||||
recursionStack.push(std::make_pair(edge.first, middle));
|
||||
} else {
|
||||
assert(!ed.shortcut);
|
||||
unpackedPath.push_back(_PathData(ed.via, ed.nameID, ed.turnInstruction, ed.distance) );
|
||||
}
|
||||
}
|
||||
}
|
||||
};
|
||||
|
71
DataStructures/SimpleStack.h
Normal file
71
DataStructures/SimpleStack.h
Normal file
@ -0,0 +1,71 @@
|
||||
/*
|
||||
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 SIMPLESTACK_H_
|
||||
#define SIMPLESTACK_H_
|
||||
|
||||
#include <cassert>
|
||||
#include <vector>
|
||||
|
||||
template<typename StackItemT, class ContainerT = std::vector<StackItemT> >
|
||||
class SimpleStack {
|
||||
|
||||
private:
|
||||
int last;
|
||||
ContainerT arr;
|
||||
|
||||
public:
|
||||
SimpleStack() : last(-1) {
|
||||
}
|
||||
|
||||
SimpleStack(std::size_t size_hint) : last(-1) {
|
||||
hint(size_hint);
|
||||
}
|
||||
|
||||
inline void hint(std::size_t size_hint) {
|
||||
arr.reserve(size_hint);
|
||||
}
|
||||
|
||||
inline void push(StackItemT t) {
|
||||
++last;
|
||||
arr.push_back(t);
|
||||
}
|
||||
|
||||
inline void pop() {
|
||||
arr.pop_back();
|
||||
--last;
|
||||
}
|
||||
|
||||
inline StackItemT top() {
|
||||
assert (last >= 0);
|
||||
return arr[last];
|
||||
}
|
||||
|
||||
inline int size() {
|
||||
return last+1;
|
||||
}
|
||||
|
||||
inline bool empty() {
|
||||
return (-1 == last);
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
#endif /* SIMPLESTACK_H_ */
|
@ -32,145 +32,146 @@ or see http://www.gnu.org/licenses/agpl.txt.
|
||||
template<class SearchEngineT>
|
||||
class JSONDescriptor : public BaseDescriptor<SearchEngineT>{
|
||||
private:
|
||||
_DescriptorConfig config;
|
||||
_RouteSummary summary;
|
||||
DescriptionFactory descriptionFactory;
|
||||
std::string tmp;
|
||||
_Coordinate current;
|
||||
struct {
|
||||
int startIndex;
|
||||
int nameID;
|
||||
int leaveAtExit;
|
||||
} roundAbout;
|
||||
_DescriptorConfig config;
|
||||
_RouteSummary summary;
|
||||
DescriptionFactory descriptionFactory;
|
||||
_Coordinate current;
|
||||
struct {
|
||||
int startIndex;
|
||||
int nameID;
|
||||
int leaveAtExit;
|
||||
} roundAbout;
|
||||
|
||||
public:
|
||||
JSONDescriptor() {}
|
||||
void SetConfig(const _DescriptorConfig & c) { config = c; }
|
||||
JSONDescriptor() {}
|
||||
void SetConfig(const _DescriptorConfig & c) { config = c; }
|
||||
|
||||
void Run(http::Reply & reply, RawRouteData &rawRoute, PhantomNodes &phantomNodes, SearchEngineT &sEngine, unsigned durationOfTrip) {
|
||||
WriteHeaderToOutput(reply.content);
|
||||
if(durationOfTrip != INT_MAX && rawRoute.routeSegments.size() > 0) {
|
||||
summary.startName = sEngine.GetEscapedNameForNameID(phantomNodes.startPhantom.nodeBasedEdgeNameID);
|
||||
descriptionFactory.SetStartSegment(phantomNodes.startPhantom);
|
||||
summary.destName = sEngine.GetEscapedNameForNameID(phantomNodes.targetPhantom.nodeBasedEdgeNameID);
|
||||
reply.content += "0,"
|
||||
"\"status_message\": \"Found route between points\",";
|
||||
for(unsigned segmentIdx = 0; segmentIdx < rawRoute.routeSegments.size(); segmentIdx++) {
|
||||
const std::vector< _PathData > & path = rawRoute.routeSegments[segmentIdx];
|
||||
BOOST_FOREACH(_PathData pathData, path) {
|
||||
sEngine.GetCoordinatesForNodeID(pathData.node, current);
|
||||
descriptionFactory.AppendSegment(current, pathData );
|
||||
}
|
||||
//TODO: Add via points
|
||||
}
|
||||
descriptionFactory.SetEndSegment(phantomNodes.targetPhantom);
|
||||
} else {
|
||||
//We do not need to do much, if there is no route ;-)
|
||||
reply.content += "207,"
|
||||
"\"status_message\": \"Cannot find route between points\",";
|
||||
}
|
||||
void Run(http::Reply & reply, RawRouteData &rawRoute, PhantomNodes &phantomNodes, SearchEngineT &sEngine, const unsigned durationOfTrip) {
|
||||
WriteHeaderToOutput(reply.content);
|
||||
if(durationOfTrip != INT_MAX && rawRoute.routeSegments.size() > 0) {
|
||||
summary.startName = sEngine.GetEscapedNameForNameID(phantomNodes.startPhantom.nodeBasedEdgeNameID);
|
||||
descriptionFactory.SetStartSegment(phantomNodes.startPhantom);
|
||||
summary.destName = sEngine.GetEscapedNameForNameID(phantomNodes.targetPhantom.nodeBasedEdgeNameID);
|
||||
reply.content += "0,"
|
||||
"\"status_message\": \"Found route between points\",";
|
||||
for(unsigned segmentIdx = 0; segmentIdx < rawRoute.routeSegments.size(); ++segmentIdx) {
|
||||
BOOST_FOREACH(_PathData & pathData, rawRoute.routeSegments[segmentIdx]) {
|
||||
sEngine.GetCoordinatesForNodeID(pathData.node, current);
|
||||
descriptionFactory.AppendSegment(current, pathData );
|
||||
}
|
||||
}
|
||||
descriptionFactory.SetEndSegment(phantomNodes.targetPhantom);
|
||||
} else {
|
||||
//We do not need to do much, if there is no route ;-)
|
||||
reply.content += "207,"
|
||||
"\"status_message\": \"Cannot find route between points\",";
|
||||
}
|
||||
|
||||
summary.BuildDurationAndLengthStrings(descriptionFactory.Run(config.z), durationOfTrip);
|
||||
summary.BuildDurationAndLengthStrings(descriptionFactory.Run(config.z), durationOfTrip);
|
||||
|
||||
reply.content += "\"route_summary\": {"
|
||||
"\"total_distance\":";
|
||||
reply.content += summary.lengthString;
|
||||
reply.content += ","
|
||||
"\"total_time\":";
|
||||
reply.content += summary.durationString;
|
||||
reply.content += ","
|
||||
"\"start_point\":\"";
|
||||
reply.content += summary.startName;
|
||||
reply.content += "\","
|
||||
"\"end_point\":\"";
|
||||
reply.content += summary.destName;
|
||||
reply.content += "\"";
|
||||
reply.content += "},";
|
||||
reply.content += "\"route_geometry\": ";
|
||||
if(config.geometry) {
|
||||
if(config.encodeGeometry)
|
||||
descriptionFactory.AppendEncodedPolylineString(reply.content, config.encodeGeometry);
|
||||
} else {
|
||||
reply.content += "[]";
|
||||
}
|
||||
reply.content += "\"route_summary\": {"
|
||||
"\"total_distance\":";
|
||||
reply.content += summary.lengthString;
|
||||
reply.content += ","
|
||||
"\"total_time\":";
|
||||
reply.content += summary.durationString;
|
||||
reply.content += ","
|
||||
"\"start_point\":\"";
|
||||
reply.content += summary.startName;
|
||||
reply.content += "\","
|
||||
"\"end_point\":\"";
|
||||
reply.content += summary.destName;
|
||||
reply.content += "\"";
|
||||
reply.content += "},";
|
||||
reply.content += "\"route_geometry\": ";
|
||||
if(config.geometry) {
|
||||
if(config.encodeGeometry)
|
||||
descriptionFactory.AppendEncodedPolylineString(reply.content, config.encodeGeometry);
|
||||
} else {
|
||||
reply.content += "[]";
|
||||
}
|
||||
|
||||
reply.content += ","
|
||||
"\"route_instructions\": [";
|
||||
if(config.instructions) {
|
||||
//Segment information has following format:
|
||||
//["instruction","streetname",length,position,time,"length","earth_direction",azimuth]
|
||||
//Example: ["Turn left","High Street",200,4,10,"200m","NE",22.5]
|
||||
//See also: http://developers.cloudmade.com/wiki/navengine/JSON_format
|
||||
unsigned prefixSumOfNecessarySegments = 0;
|
||||
roundAbout.leaveAtExit = 0;
|
||||
roundAbout.nameID = 0;
|
||||
std::string tmpDist, tmpLength, tmp;
|
||||
//Fetch data from Factory and generate a string from it.
|
||||
BOOST_FOREACH(SegmentInformation segment, descriptionFactory.pathDescription) {
|
||||
if(TurnInstructions.TurnIsNecessary( segment.turnInstruction) ) {
|
||||
if(TurnInstructions.EnterRoundAbout == segment.turnInstruction) {
|
||||
roundAbout.nameID = segment.nameID;
|
||||
roundAbout.startIndex = prefixSumOfNecessarySegments;
|
||||
} else {
|
||||
if(0 != prefixSumOfNecessarySegments)
|
||||
reply.content += ",";
|
||||
reply.content += ","
|
||||
"\"route_instructions\": [";
|
||||
if(config.instructions) {
|
||||
//Segment information has following format:
|
||||
//["instruction","streetname",length,position,time,"length","earth_direction",azimuth]
|
||||
//Example: ["Turn left","High Street",200,4,10,"200m","NE",22.5]
|
||||
//See also: http://developers.cloudmade.com/wiki/navengine/JSON_format
|
||||
unsigned prefixSumOfNecessarySegments = 0;
|
||||
roundAbout.leaveAtExit = 0;
|
||||
roundAbout.nameID = 0;
|
||||
std::string tmpDist, tmpLength, tmpDuration;
|
||||
//Fetch data from Factory and generate a string from it.
|
||||
BOOST_FOREACH(SegmentInformation & segment, descriptionFactory.pathDescription) {
|
||||
if(TurnInstructions.TurnIsNecessary( segment.turnInstruction) ) {
|
||||
if(TurnInstructions.EnterRoundAbout == segment.turnInstruction) {
|
||||
roundAbout.nameID = segment.nameID;
|
||||
roundAbout.startIndex = prefixSumOfNecessarySegments;
|
||||
} else {
|
||||
if(0 != prefixSumOfNecessarySegments)
|
||||
reply.content += ",";
|
||||
|
||||
reply.content += "[\"";
|
||||
if(TurnInstructions.LeaveRoundAbout == segment.turnInstruction) {
|
||||
reply.content += TurnInstructions.TurnStrings[TurnInstructions.EnterRoundAbout];
|
||||
reply.content += " and leave at ";
|
||||
reply.content += TurnInstructions.Ordinals[roundAbout.leaveAtExit+1];
|
||||
reply.content += " exit";
|
||||
roundAbout.leaveAtExit = 0;
|
||||
} else {
|
||||
reply.content += TurnInstructions.TurnStrings[segment.turnInstruction];
|
||||
}
|
||||
reply.content += "\",\"";
|
||||
reply.content += sEngine.GetEscapedNameForNameID(segment.nameID);
|
||||
reply.content += "\",";
|
||||
intToString(segment.length, tmpDist);
|
||||
reply.content += tmpDist;
|
||||
reply.content += ",";
|
||||
intToString(prefixSumOfNecessarySegments, tmpLength);
|
||||
reply.content += tmpLength;
|
||||
reply.content += ",";
|
||||
intToString(segment.duration, tmp);
|
||||
reply.content += ",\"";
|
||||
reply.content += tmpLength;
|
||||
//TODO: fix heading
|
||||
reply.content += "\",\"NE\",22.5";
|
||||
reply.content += "]";
|
||||
}
|
||||
} else if(TurnInstructions.StayOnRoundAbout == segment.turnInstruction) {
|
||||
++roundAbout.leaveAtExit;
|
||||
}
|
||||
if(segment.necessary)
|
||||
++prefixSumOfNecessarySegments;
|
||||
}
|
||||
}
|
||||
reply.content += "],";
|
||||
//list all viapoints so that the client may display it
|
||||
reply.content += "\"via_points\":[";
|
||||
for(unsigned segmentIdx = 1; (true == config.geometry) && (segmentIdx < rawRoute.segmentEndCoordinates.size()); segmentIdx++) {
|
||||
if(segmentIdx > 1)
|
||||
reply.content += ",";
|
||||
reply.content += "[";
|
||||
if(rawRoute.segmentEndCoordinates[segmentIdx].startPhantom.location.isSet())
|
||||
convertInternalReversedCoordinateToString(rawRoute.segmentEndCoordinates[segmentIdx].startPhantom.location, tmp);
|
||||
else
|
||||
convertInternalReversedCoordinateToString(rawRoute.rawViaNodeCoordinates[segmentIdx], tmp);
|
||||
reply.content += tmp;
|
||||
reply.content += "]";
|
||||
}
|
||||
reply.content += "],"
|
||||
"\"transactionId\": \"OSRM Routing Engine JSON Descriptor (v0.2)\"";
|
||||
reply.content += "}";
|
||||
}
|
||||
reply.content += "[\"";
|
||||
if(TurnInstructions.LeaveRoundAbout == segment.turnInstruction) {
|
||||
reply.content += TurnInstructions.TurnStrings[TurnInstructions.EnterRoundAbout];
|
||||
reply.content += " and leave at ";
|
||||
reply.content += TurnInstructions.Ordinals[roundAbout.leaveAtExit+1];
|
||||
reply.content += " exit";
|
||||
roundAbout.leaveAtExit = 0;
|
||||
} else {
|
||||
reply.content += TurnInstructions.TurnStrings[segment.turnInstruction];
|
||||
}
|
||||
reply.content += "\",\"";
|
||||
reply.content += sEngine.GetEscapedNameForNameID(segment.nameID);
|
||||
reply.content += "\",";
|
||||
intToString(segment.length, tmpDist);
|
||||
reply.content += tmpDist;
|
||||
reply.content += ",";
|
||||
intToString(prefixSumOfNecessarySegments, tmpLength);
|
||||
reply.content += tmpLength;
|
||||
reply.content += ",";
|
||||
intToString(segment.duration, tmpDuration);
|
||||
reply.content += tmpDuration;
|
||||
reply.content += ",\"";
|
||||
reply.content += tmpLength;
|
||||
//TODO: fix heading
|
||||
reply.content += "\",\"NE\",22.5";
|
||||
reply.content += "]";
|
||||
}
|
||||
} else if(TurnInstructions.StayOnRoundAbout == segment.turnInstruction) {
|
||||
++roundAbout.leaveAtExit;
|
||||
}
|
||||
if(segment.necessary)
|
||||
++prefixSumOfNecessarySegments;
|
||||
}
|
||||
}
|
||||
reply.content += "],";
|
||||
//list all viapoints so that the client may display it
|
||||
reply.content += "\"via_points\":[";
|
||||
if(true == config.geometry) {
|
||||
std::string tmp;
|
||||
for(unsigned segmentIdx = 1; segmentIdx < rawRoute.segmentEndCoordinates.size(); ++segmentIdx) {
|
||||
if(segmentIdx > 1)
|
||||
reply.content += ",";
|
||||
reply.content += "[";
|
||||
if(rawRoute.segmentEndCoordinates[segmentIdx].startPhantom.location.isSet())
|
||||
convertInternalReversedCoordinateToString(rawRoute.segmentEndCoordinates[segmentIdx].startPhantom.location, tmp);
|
||||
else
|
||||
convertInternalReversedCoordinateToString(rawRoute.rawViaNodeCoordinates[segmentIdx], tmp);
|
||||
reply.content += tmp;
|
||||
reply.content += "]";
|
||||
}
|
||||
}
|
||||
reply.content += "],"
|
||||
"\"transactionId\": \"OSRM Routing Engine JSON Descriptor (v0.3)\"";
|
||||
reply.content += "}";
|
||||
}
|
||||
|
||||
void WriteHeaderToOutput(std::string & output) {
|
||||
output += "{"
|
||||
"\"version\": 0.3,"
|
||||
"\"status\":";
|
||||
}
|
||||
inline void WriteHeaderToOutput(std::string & output) {
|
||||
output += "{"
|
||||
"\"version\": 0.3,"
|
||||
"\"status\":";
|
||||
}
|
||||
};
|
||||
#endif /* JSON_DESCRIPTOR_H_ */
|
||||
|
Loading…
Reference in New Issue
Block a user