Refactor routing_algorithms to only contain free functions

This commit is contained in:
Patrick Niklaus 2017-02-25 01:24:21 +00:00 committed by Patrick Niklaus
parent 2fa8d0f534
commit 436b34ffea
20 changed files with 1481 additions and 1689 deletions

View File

@ -1,107 +0,0 @@
#ifndef EDGE_UNPACKER_H
#define EDGE_UNPACKER_H
#include "extractor/guidance/turn_instruction.hpp"
#include "extractor/travel_mode.hpp"
#include "engine/phantom_node.hpp"
#include "osrm/coordinate.hpp"
#include "util/guidance/turn_lanes.hpp"
#include "util/typedefs.hpp"
#include <stack>
#include <vector>
namespace osrm
{
namespace engine
{
/**
* Given a sequence of connected `NodeID`s in the CH graph, performs a depth-first unpacking of
* the shortcut
* edges. For every "original" edge found, it calls the `callback` with the two NodeIDs for the
* edge, and the EdgeData
* for that edge.
*
* The primary purpose of this unpacking is to expand a path through the CH into the original
* route through the
* pre-contracted graph.
*
* Because of the depth-first-search, the `callback` will effectively be called in sequence for
* the original route
* from beginning to end.
*
* @param packed_path_begin iterator pointing to the start of the NodeID list
* @param packed_path_end iterator pointing to the end of the NodeID list
* @param callback void(const std::pair<NodeID, NodeID>, const EdgeData &) called for each
* original edge found.
*/
template <typename DataFacadeT, typename BidirectionalIterator, typename Callback>
inline void UnpackCHPath(const DataFacadeT &facade,
BidirectionalIterator packed_path_begin,
BidirectionalIterator packed_path_end,
Callback &&callback)
{
// make sure we have at least something to unpack
if (packed_path_begin == packed_path_end)
return;
using EdgeData = typename DataFacadeT::EdgeData;
std::stack<std::pair<NodeID, NodeID>> recursion_stack;
// We have to push the path in reverse order onto the stack because it's LIFO.
for (auto current = std::prev(packed_path_end); current != packed_path_begin;
current = std::prev(current))
{
recursion_stack.emplace(*std::prev(current), *current);
}
std::pair<NodeID, NodeID> edge;
while (!recursion_stack.empty())
{
edge = recursion_stack.top();
recursion_stack.pop();
// Look for an edge on the forward CH graph (.forward)
EdgeID smaller_edge_id = facade.FindSmallestEdge(
edge.first, edge.second, [](const EdgeData &data) { return data.forward; });
// If we didn't find one there, the we might be looking at a part of the path that
// was found using the backward search. Here, we flip the node order (.second, .first)
// and only consider edges with the `.backward` flag.
if (SPECIAL_EDGEID == smaller_edge_id)
{
smaller_edge_id = facade.FindSmallestEdge(
edge.second, edge.first, [](const EdgeData &data) { return data.backward; });
}
// If we didn't find anything *still*, then something is broken and someone has
// called this function with bad values.
BOOST_ASSERT_MSG(smaller_edge_id != SPECIAL_EDGEID, "Invalid smaller edge ID");
const auto &data = facade.GetEdgeData(smaller_edge_id);
BOOST_ASSERT_MSG(data.weight != std::numeric_limits<EdgeWeight>::max(),
"edge weight invalid");
// If the edge is a shortcut, we need to add the two halfs to the stack.
if (data.shortcut)
{ // unpack
const NodeID middle_node_id = data.id;
// Note the order here - we're adding these to a stack, so we
// want the first->middle to get visited before middle->second
recursion_stack.emplace(middle_node_id, edge.second);
recursion_stack.emplace(edge.first, middle_node_id);
}
else
{
// We found an original edge, call our callback.
std::forward<Callback>(callback)(edge, data);
}
}
}
}
}
#endif // EDGE_UNPACKER_H

View File

@ -19,15 +19,14 @@ namespace engine
class RoutingAlgorithmsInterface class RoutingAlgorithmsInterface
{ {
public: public:
virtual void AlternativeRouting(const PhantomNodes &phantom_node_pair, virtual InternalRouteResult AlternativeRouting(const PhantomNodes &phantom_node_pair) const = 0;
InternalRouteResult &raw_route_data) const = 0;
virtual void ShortestRouting(const std::vector<PhantomNodes> &phantom_node_pair, virtual InternalRouteResult
const boost::optional<bool> continue_straight_at_waypoint, ShortestRouting(const std::vector<PhantomNodes> &phantom_node_pair,
InternalRouteResult &raw_route_data) const = 0; const boost::optional<bool> continue_straight_at_waypoint) const = 0;
virtual void DirectShortestPathRouting(const std::vector<PhantomNodes> &phantom_node_pair, virtual InternalRouteResult
InternalRouteResult &raw_route_data) const = 0; DirectShortestPathRouting(const std::vector<PhantomNodes> &phantom_node_pair) const = 0;
virtual std::vector<EdgeWeight> virtual std::vector<EdgeWeight>
ManyToManyRouting(const std::vector<PhantomNode> &phantom_nodes, ManyToManyRouting(const std::vector<PhantomNode> &phantom_nodes,
@ -53,29 +52,28 @@ template <typename AlgorithmT> class RoutingAlgorithms final : public RoutingAlg
public: public:
RoutingAlgorithms(SearchEngineData &heaps, RoutingAlgorithms(SearchEngineData &heaps,
const datafacade::ContiguousInternalMemoryDataFacade<AlgorithmT> &facade) const datafacade::ContiguousInternalMemoryDataFacade<AlgorithmT> &facade)
: facade(facade), alternative_routing(heaps), shortest_path_routing(heaps), : heaps(heaps), facade(facade)
direct_shortest_path_routing(heaps), many_to_many_routing(heaps), map_matching(heaps)
{ {
} }
void AlternativeRouting(const PhantomNodes &phantom_node_pair, InternalRouteResult
InternalRouteResult &raw_route_data) const final override AlternativeRouting(const PhantomNodes &phantom_node_pair) const final override
{ {
alternative_routing(facade, phantom_node_pair, raw_route_data); return routing_algorithms::alternativePathSearch(heaps, facade, phantom_node_pair);
} }
void ShortestRouting(const std::vector<PhantomNodes> &phantom_node_pair, InternalRouteResult
const boost::optional<bool> continue_straight_at_waypoint, ShortestRouting(const std::vector<PhantomNodes> &phantom_node_pair,
InternalRouteResult &raw_route_data) const final override const boost::optional<bool> continue_straight_at_waypoint) const final override
{ {
shortest_path_routing( return routing_algorithms::shortestPathSearch(
facade, phantom_node_pair, continue_straight_at_waypoint, raw_route_data); heaps, facade, phantom_node_pair, continue_straight_at_waypoint);
} }
void DirectShortestPathRouting(const std::vector<PhantomNodes> &phantom_node_pair, InternalRouteResult DirectShortestPathRouting(
InternalRouteResult &raw_route_data) const final override const std::vector<PhantomNodes> &phantom_node_pair) const final override
{ {
direct_shortest_path_routing(facade, phantom_node_pair, raw_route_data); return routing_algorithms::directShortestPathSearch(heaps, facade, phantom_node_pair);
} }
std::vector<EdgeWeight> std::vector<EdgeWeight>
@ -83,7 +81,8 @@ template <typename AlgorithmT> class RoutingAlgorithms final : public RoutingAlg
const std::vector<std::size_t> &source_indices, const std::vector<std::size_t> &source_indices,
const std::vector<std::size_t> &target_indices) const final override const std::vector<std::size_t> &target_indices) const final override
{ {
return many_to_many_routing(facade, phantom_nodes, source_indices, target_indices); return routing_algorithms::manyToManySearch(
heaps, facade, phantom_nodes, source_indices, target_indices);
} }
routing_algorithms::SubMatchingList MapMatching( routing_algorithms::SubMatchingList MapMatching(
@ -92,32 +91,30 @@ template <typename AlgorithmT> class RoutingAlgorithms final : public RoutingAlg
const std::vector<unsigned> &trace_timestamps, const std::vector<unsigned> &trace_timestamps,
const std::vector<boost::optional<double>> &trace_gps_precision) const final override const std::vector<boost::optional<double>> &trace_gps_precision) const final override
{ {
return map_matching( return routing_algorithms::mapMatching(heaps,
facade, candidates_list, trace_coordinates, trace_timestamps, trace_gps_precision); facade,
candidates_list,
trace_coordinates,
trace_timestamps,
trace_gps_precision);
} }
std::vector<routing_algorithms::TurnData> std::vector<routing_algorithms::TurnData>
TileTurns(const std::vector<datafacade::BaseDataFacade::RTreeLeaf> &edges, TileTurns(const std::vector<datafacade::BaseDataFacade::RTreeLeaf> &edges,
const std::vector<std::size_t> &sorted_edge_indexes) const final override const std::vector<std::size_t> &sorted_edge_indexes) const final override
{ {
return tile_turns(facade, edges, sorted_edge_indexes); return routing_algorithms::getTileTurns(facade, edges, sorted_edge_indexes);
} }
bool HasAlternativeRouting() const final override bool HasAlternativeRouting() const final override
{ {
return algorithm_trais::HasAlternativeRouting<AlgorithmT>()(facade); return algorithm_trais::HasAlternativeRouting<AlgorithmT>()(facade);
}; }
private: private:
SearchEngineData &heaps;
// Owned by shared-ptr passed to the query // Owned by shared-ptr passed to the query
const datafacade::ContiguousInternalMemoryDataFacade<AlgorithmT> &facade; const datafacade::ContiguousInternalMemoryDataFacade<AlgorithmT> &facade;
mutable routing_algorithms::AlternativeRouting<AlgorithmT> alternative_routing;
mutable routing_algorithms::ShortestPathRouting<AlgorithmT> shortest_path_routing;
mutable routing_algorithms::DirectShortestPathRouting<AlgorithmT> direct_shortest_path_routing;
mutable routing_algorithms::ManyToManyRouting<AlgorithmT> many_to_many_routing;
mutable routing_algorithms::MapMatching<AlgorithmT> map_matching;
routing_algorithms::TileTurns<AlgorithmT> tile_turns;
}; };
} }
} }

View File

@ -1,22 +1,11 @@
#ifndef ALTERNATIVE_PATH_ROUTING_HPP #ifndef ALTERNATIVE_PATH_ROUTING_HPP
#define ALTERNATIVE_PATH_ROUTING_HPP #define ALTERNATIVE_PATH_ROUTING_HPP
#include "engine/datafacade/datafacade_base.hpp" #include "engine/datafacade/contiguous_internalmem_datafacade.hpp"
#include "engine/routing_algorithms/routing_base.hpp" #include "engine/internal_route_result.hpp"
#include "engine/algorithm.hpp" #include "engine/algorithm.hpp"
#include "engine/search_engine_data.hpp" #include "engine/search_engine_data.hpp"
#include "util/integer_range.hpp"
#include <boost/assert.hpp>
#include <algorithm>
#include <iterator>
#include <memory>
#include <unordered_map>
#include <unordered_set>
#include <vector>
namespace osrm namespace osrm
{ {
@ -25,181 +14,13 @@ namespace engine
namespace routing_algorithms namespace routing_algorithms
{ {
const double constexpr VIAPATH_ALPHA = 0.10; InternalRouteResult
const double constexpr VIAPATH_EPSILON = 0.15; // alternative at most 15% longer alternativePathSearch(SearchEngineData &search_engine_data,
const double constexpr VIAPATH_GAMMA = 0.75; // alternative shares at most 75% with the shortest. const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
const PhantomNodes &phantom_node_pair);
template <typename AlgorithmT> class AlternativeRouting;
template <> class AlternativeRouting<algorithm::CH> final : private BasicRouting<algorithm::CH>
{
using super = BasicRouting<algorithm::CH>;
using FacadeT = datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH>;
using QueryHeap = SearchEngineData::QueryHeap;
using SearchSpaceEdge = std::pair<NodeID, NodeID>;
struct RankedCandidateNode
{
RankedCandidateNode(const NodeID node, const int length, const int sharing)
: node(node), length(length), sharing(sharing)
{
}
NodeID node;
int length;
int sharing;
bool operator<(const RankedCandidateNode &other) const
{
return (2 * length + sharing) < (2 * other.length + other.sharing);
}
};
SearchEngineData &engine_working_data;
public:
AlternativeRouting(SearchEngineData &engine_working_data)
: engine_working_data(engine_working_data)
{
}
virtual ~AlternativeRouting() {}
void operator()(const FacadeT &facade,
const PhantomNodes &phantom_node_pair,
InternalRouteResult &raw_route_data);
private:
// unpack alternate <s,..,v,..,t> by exploring search spaces from v
void RetrievePackedAlternatePath(const QueryHeap &forward_heap1,
const QueryHeap &reverse_heap1,
const QueryHeap &forward_heap2,
const QueryHeap &reverse_heap2,
const NodeID s_v_middle,
const NodeID v_t_middle,
std::vector<NodeID> &packed_path) const;
// TODO: reorder parameters
// compute and unpack <s,..,v> and <v,..,t> by exploring search spaces
// from v and intersecting against queues. only half-searches have to be
// done at this stage
void ComputeLengthAndSharingOfViaPath(const FacadeT &facade,
const NodeID via_node,
int *real_length_of_via_path,
int *sharing_of_via_path,
const std::vector<NodeID> &packed_shortest_path,
const EdgeWeight min_edge_offset);
// todo: reorder parameters
template <bool is_forward_directed>
void AlternativeRoutingStep(const FacadeT &facade,
QueryHeap &heap1,
QueryHeap &heap2,
NodeID *middle_node,
EdgeWeight *upper_bound_to_shortest_path_weight,
std::vector<NodeID> &search_space_intersection,
std::vector<SearchSpaceEdge> &search_space,
const EdgeWeight min_edge_offset) const
{
QueryHeap &forward_heap = (is_forward_directed ? heap1 : heap2);
QueryHeap &reverse_heap = (is_forward_directed ? heap2 : heap1);
const NodeID node = forward_heap.DeleteMin();
const EdgeWeight weight = forward_heap.GetKey(node);
// const NodeID parentnode = forward_heap.GetData(node).parent;
// util::Log() << (is_forward_directed ? "[fwd] " : "[rev] ") << "settled
// edge ("
// << parentnode << "," << node << "), dist: " << weight;
const auto scaled_weight =
static_cast<EdgeWeight>((weight + min_edge_offset) / (1. + VIAPATH_EPSILON));
if ((INVALID_EDGE_WEIGHT != *upper_bound_to_shortest_path_weight) &&
(scaled_weight > *upper_bound_to_shortest_path_weight))
{
forward_heap.DeleteAll();
return;
}
search_space.emplace_back(forward_heap.GetData(node).parent, node);
if (reverse_heap.WasInserted(node))
{
search_space_intersection.emplace_back(node);
const EdgeWeight new_weight = reverse_heap.GetKey(node) + weight;
if (new_weight < *upper_bound_to_shortest_path_weight)
{
if (new_weight >= 0)
{
*middle_node = node;
*upper_bound_to_shortest_path_weight = new_weight;
// util::Log() << "accepted middle_node " << *middle_node
// << " at
// weight " << new_weight;
// } else {
// util::Log() << "discarded middle_node " << *middle_node
// << "
// at weight " << new_weight;
}
else
{
// check whether there is a loop present at the node
const auto loop_weight = super::GetLoopWeight<false>(facade, node);
const EdgeWeight new_weight_with_loop = new_weight + loop_weight;
if (loop_weight != INVALID_EDGE_WEIGHT &&
new_weight_with_loop <= *upper_bound_to_shortest_path_weight)
{
*middle_node = node;
*upper_bound_to_shortest_path_weight = loop_weight;
}
}
}
}
for (auto edge : facade.GetAdjacentEdgeRange(node))
{
const auto &data = facade.GetEdgeData(edge);
const bool edge_is_forward_directed =
(is_forward_directed ? data.forward : data.backward);
if (edge_is_forward_directed)
{
const NodeID to = facade.GetTarget(edge);
const EdgeWeight edge_weight = data.weight;
BOOST_ASSERT(edge_weight > 0);
const EdgeWeight to_weight = weight + edge_weight;
// New Node discovered -> Add to Heap + Node Info Storage
if (!forward_heap.WasInserted(to))
{
forward_heap.Insert(to, to_weight, node);
}
// Found a shorter Path -> Update weight
else if (to_weight < forward_heap.GetKey(to))
{
// new parent
forward_heap.GetData(to).parent = node;
// decreased weight
forward_heap.DecreaseKey(to, to_weight);
}
}
}
}
// conduct T-Test
bool ViaNodeCandidatePassesTTest(const FacadeT &facade,
QueryHeap &existing_forward_heap,
QueryHeap &existing_reverse_heap,
QueryHeap &new_forward_heap,
QueryHeap &new_reverse_heap,
const RankedCandidateNode &candidate,
const int length_of_shortest_path,
int *length_of_via_path,
NodeID *s_v_middle,
NodeID *v_t_middle,
const EdgeWeight min_edge_offset) const;
};
} // namespace routing_algorithms } // namespace routing_algorithms
} // namespace engine } // namespace engine
} // namespace osrm } // namespace osrm
#endif /* ALTERNATIVE_PATH_ROUTING_HPP */ #endif

View File

@ -1,10 +1,11 @@
#ifndef DIRECT_SHORTEST_PATH_HPP #ifndef DIRECT_SHORTEST_PATH_HPP
#define DIRECT_SHORTEST_PATH_HPP #define DIRECT_SHORTEST_PATH_HPP
#include "engine/routing_algorithms/routing_base.hpp"
#include "engine/algorithm.hpp" #include "engine/algorithm.hpp"
#include "engine/datafacade/contiguous_internalmem_datafacade.hpp"
#include "engine/internal_route_result.hpp"
#include "engine/search_engine_data.hpp" #include "engine/search_engine_data.hpp"
#include "util/typedefs.hpp" #include "util/typedefs.hpp"
namespace osrm namespace osrm
@ -14,34 +15,16 @@ namespace engine
namespace routing_algorithms namespace routing_algorithms
{ {
template <typename AlgorithmT> class DirectShortestPathRouting;
/// This is a striped down version of the general shortest path algorithm. /// This is a striped down version of the general shortest path algorithm.
/// The general algorithm always computes two queries for each leg. This is only /// The general algorithm always computes two queries for each leg. This is only
/// necessary in case of vias, where the directions of the start node is constrainted /// necessary in case of vias, where the directions of the start node is constrainted
/// by the previous route. /// by the previous route.
/// This variation is only an optimazation for graphs with slow queries, for example /// This variation is only an optimazation for graphs with slow queries, for example
/// not fully contracted graphs. /// not fully contracted graphs.
template <> InternalRouteResult directShortestPathSearch(
class DirectShortestPathRouting<algorithm::CH> final : public BasicRouting<algorithm::CH> SearchEngineData &engine_working_data,
{ const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
using super = BasicRouting<algorithm::CH>; const std::vector<PhantomNodes> &phantom_nodes_vector);
using FacadeT = datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH>;
using QueryHeap = SearchEngineData::QueryHeap;
SearchEngineData &engine_working_data;
public:
DirectShortestPathRouting(SearchEngineData &engine_working_data)
: engine_working_data(engine_working_data)
{
}
~DirectShortestPathRouting() {}
void operator()(const FacadeT &facade,
const std::vector<PhantomNodes> &phantom_nodes_vector,
InternalRouteResult &raw_route_data) const;
};
} // namespace routing_algorithms } // namespace routing_algorithms
} // namespace engine } // namespace engine

View File

@ -1,138 +1,28 @@
#ifndef MANY_TO_MANY_ROUTING_HPP #ifndef MANY_TO_MANY_ROUTING_HPP
#define MANY_TO_MANY_ROUTING_HPP #define MANY_TO_MANY_ROUTING_HPP
#include "engine/routing_algorithms/routing_base.hpp"
#include "engine/algorithm.hpp" #include "engine/algorithm.hpp"
#include "engine/datafacade/contiguous_internalmem_datafacade.hpp"
#include "engine/search_engine_data.hpp" #include "engine/search_engine_data.hpp"
#include "util/typedefs.hpp" #include "util/typedefs.hpp"
#include <boost/assert.hpp>
#include <limits>
#include <memory>
#include <unordered_map>
#include <vector> #include <vector>
namespace osrm namespace osrm
{ {
namespace engine namespace engine
{ {
namespace routing_algorithms namespace routing_algorithms
{ {
template <typename AlgorithmT> class ManyToManyRouting; std::vector<EdgeWeight>
manyToManySearch(SearchEngineData &engine_working_data,
template <> class ManyToManyRouting<algorithm::CH> final : public BasicRouting<algorithm::CH> const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
{ const std::vector<PhantomNode> &phantom_nodes,
using super = BasicRouting<algorithm::CH>; const std::vector<std::size_t> &source_indices,
using FacadeT = datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH>; const std::vector<std::size_t> &target_indices);
using QueryHeap = SearchEngineData::ManyToManyQueryHeap;
SearchEngineData &engine_working_data;
struct NodeBucket
{
unsigned target_id; // essentially a row in the weight matrix
EdgeWeight weight;
EdgeWeight duration;
NodeBucket(const unsigned target_id, const EdgeWeight weight, const EdgeWeight duration)
: target_id(target_id), weight(weight), duration(duration)
{
}
};
// FIXME This should be replaced by an std::unordered_multimap, though this needs benchmarking
using SearchSpaceWithBuckets = std::unordered_map<NodeID, std::vector<NodeBucket>>;
public:
ManyToManyRouting(SearchEngineData &engine_working_data)
: engine_working_data(engine_working_data)
{
}
std::vector<EdgeWeight> operator()(const FacadeT &facade,
const std::vector<PhantomNode> &phantom_nodes,
const std::vector<std::size_t> &source_indices,
const std::vector<std::size_t> &target_indices) const;
void ForwardRoutingStep(const FacadeT &facade,
const unsigned row_idx,
const unsigned number_of_targets,
QueryHeap &query_heap,
const SearchSpaceWithBuckets &search_space_with_buckets,
std::vector<EdgeWeight> &weights_table,
std::vector<EdgeWeight> &durations_table) const;
void BackwardRoutingStep(const FacadeT &facade,
const unsigned column_idx,
QueryHeap &query_heap,
SearchSpaceWithBuckets &search_space_with_buckets) const;
template <bool forward_direction>
inline void RelaxOutgoingEdges(const FacadeT &facade,
const NodeID node,
const EdgeWeight weight,
const EdgeWeight duration,
QueryHeap &query_heap) const
{
for (auto edge : facade.GetAdjacentEdgeRange(node))
{
const auto &data = facade.GetEdgeData(edge);
const bool direction_flag = (forward_direction ? data.forward : data.backward);
if (direction_flag)
{
const NodeID to = facade.GetTarget(edge);
const EdgeWeight edge_weight = data.weight;
const EdgeWeight edge_duration = data.duration;
BOOST_ASSERT_MSG(edge_weight > 0, "edge_weight invalid");
const EdgeWeight to_weight = weight + edge_weight;
const EdgeWeight to_duration = duration + edge_duration;
// New Node discovered -> Add to Heap + Node Info Storage
if (!query_heap.WasInserted(to))
{
query_heap.Insert(to, to_weight, {node, to_duration});
}
// Found a shorter Path -> Update weight
else if (to_weight < query_heap.GetKey(to))
{
// new parent
query_heap.GetData(to) = {node, to_duration};
query_heap.DecreaseKey(to, to_weight);
}
}
}
}
// Stalling
template <bool forward_direction>
inline bool StallAtNode(const FacadeT &facade,
const NodeID node,
const EdgeWeight weight,
QueryHeap &query_heap) const
{
for (auto edge : facade.GetAdjacentEdgeRange(node))
{
const auto &data = facade.GetEdgeData(edge);
const bool reverse_flag = ((!forward_direction) ? data.forward : data.backward);
if (reverse_flag)
{
const NodeID to = facade.GetTarget(edge);
const EdgeWeight edge_weight = data.weight;
BOOST_ASSERT_MSG(edge_weight > 0, "edge_weight invalid");
if (query_heap.WasInserted(to))
{
if (query_heap.GetKey(to) + edge_weight < weight)
{
return true;
}
}
}
}
return false;
}
};
} // namespace routing_algorithms } // namespace routing_algorithms
} // namespace engine } // namespace engine

View File

@ -1,25 +1,11 @@
#ifndef MAP_MATCHING_HPP #ifndef MAP_MATCHING_HPP
#define MAP_MATCHING_HPP #define MAP_MATCHING_HPP
#include "engine/routing_algorithms/routing_base.hpp"
#include "engine/algorithm.hpp" #include "engine/algorithm.hpp"
#include "engine/map_matching/hidden_markov_model.hpp" #include "engine/datafacade/contiguous_internalmem_datafacade.hpp"
#include "engine/map_matching/matching_confidence.hpp"
#include "engine/map_matching/sub_matching.hpp" #include "engine/map_matching/sub_matching.hpp"
#include "engine/search_engine_data.hpp"
#include "extractor/profile_properties.hpp"
#include "util/coordinate_calculation.hpp"
#include "util/for_each_pair.hpp"
#include <cstddef>
#include <algorithm>
#include <deque>
#include <iomanip>
#include <memory>
#include <numeric>
#include <utility>
#include <vector> #include <vector>
namespace osrm namespace osrm
@ -31,45 +17,16 @@ namespace routing_algorithms
using CandidateList = std::vector<PhantomNodeWithDistance>; using CandidateList = std::vector<PhantomNodeWithDistance>;
using CandidateLists = std::vector<CandidateList>; using CandidateLists = std::vector<CandidateList>;
using HMM = map_matching::HiddenMarkovModel<CandidateLists>;
using SubMatchingList = std::vector<map_matching::SubMatching>; using SubMatchingList = std::vector<map_matching::SubMatching>;
constexpr static const unsigned MAX_BROKEN_STATES = 10;
static const constexpr double MATCHING_BETA = 10;
constexpr static const double MAX_DISTANCE_DELTA = 2000.;
static const constexpr double DEFAULT_GPS_PRECISION = 5; static const constexpr double DEFAULT_GPS_PRECISION = 5;
template <typename AlgorithmT> class MapMatching; SubMatchingList
mapMatching(SearchEngineData &engine_working_data,
// implements a hidden markov model map matching algorithm const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
template <> class MapMatching<algorithm::CH> final : public BasicRouting<algorithm::CH> const CandidateLists &candidates_list,
{ const std::vector<util::Coordinate> &trace_coordinates,
using super = BasicRouting<algorithm::CH>; const std::vector<unsigned> &trace_timestamps,
using FacadeT = datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH>; const std::vector<boost::optional<double>> &trace_gps_precision);
using QueryHeap = SearchEngineData::QueryHeap;
SearchEngineData &engine_working_data;
map_matching::EmissionLogProbability default_emission_log_probability;
map_matching::TransitionLogProbability transition_log_probability;
map_matching::MatchingConfidence confidence;
extractor::ProfileProperties m_profile_properties;
unsigned GetMedianSampleTime(const std::vector<unsigned> &timestamps) const;
public:
MapMatching(SearchEngineData &engine_working_data)
: engine_working_data(engine_working_data),
default_emission_log_probability(DEFAULT_GPS_PRECISION),
transition_log_probability(MATCHING_BETA)
{
}
SubMatchingList
operator()(const FacadeT &facade,
const CandidateLists &candidates_list,
const std::vector<util::Coordinate> &trace_coordinates,
const std::vector<unsigned> &trace_timestamps,
const std::vector<boost::optional<double>> &trace_gps_precision) const;
};
} }
} }
} }

View File

@ -5,7 +5,6 @@
#include "engine/algorithm.hpp" #include "engine/algorithm.hpp"
#include "engine/datafacade/contiguous_internalmem_datafacade.hpp" #include "engine/datafacade/contiguous_internalmem_datafacade.hpp"
#include "engine/edge_unpacker.hpp"
#include "engine/internal_route_result.hpp" #include "engine/internal_route_result.hpp"
#include "engine/search_engine_data.hpp" #include "engine/search_engine_data.hpp"
@ -35,402 +34,476 @@ namespace engine
namespace routing_algorithms namespace routing_algorithms
{ {
template <typename AlgorithmT> class BasicRouting; /*
min_edge_offset is needed in case we use multiple
nodes as start/target nodes with different (even negative) offsets.
In that case the termination criterion is not correct
anymore.
// TODO: There is no reason these functions are contained in a class other then for namespace Example:
// purposes. This should be a namespace with free functions. forward heap: a(-100), b(0),
template <> class BasicRouting<algorithm::CH> reverse heap: c(0), d(100)
{
protected:
using FacadeT = datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH>;
using EdgeData = typename FacadeT::EdgeData;
public: a --- d
/* \ /
min_edge_offset is needed in case we use multiple / \
nodes as start/target nodes with different (even negative) offsets. b --- c
In that case the termination criterion is not correct
anymore.
Example: This is equivalent to running a bi-directional Dijkstra on the following graph:
forward heap: a(-100), b(0),
reverse heap: c(0), d(100)
a --- d a --- d
\ / / \ / \
/ \ y x z
\ / \ /
b --- c b --- c
This is equivalent to running a bi-directional Dijkstra on the following graph: The graph is constructed by inserting nodes y and z that are connected to the initial nodes
using edges (y, a) with weight -100, (y, b) with weight 0 and,
(d, z) with weight 100, (c, z) with weight 0 corresponding.
Since we are dealing with a graph that contains _negative_ edges,
we need to add an offset to the termination criterion.
*/
void routingStep(const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
SearchEngineData::QueryHeap &forward_heap,
SearchEngineData::QueryHeap &reverse_heap,
NodeID &middle_node_id,
std::int32_t &upper_bound,
std::int32_t min_edge_offset,
const bool forward_direction,
const bool stalling,
const bool force_loop_forward,
const bool force_loop_reverse);
a --- d template <bool UseDuration>
/ \ / \ EdgeWeight
y x z getLoopWeight(const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
\ / \ / NodeID node)
b --- c {
EdgeWeight loop_weight = UseDuration ? MAXIMAL_EDGE_DURATION : INVALID_EDGE_WEIGHT;
The graph is constructed by inserting nodes y and z that are connected to the initial nodes for (auto edge : facade.GetAdjacentEdgeRange(node))
using edges (y, a) with weight -100, (y, b) with weight 0 and,
(d, z) with weight 100, (c, z) with weight 0 corresponding.
Since we are dealing with a graph that contains _negative_ edges,
we need to add an offset to the termination criterion.
*/
void RoutingStep(const FacadeT &facade,
SearchEngineData::QueryHeap &forward_heap,
SearchEngineData::QueryHeap &reverse_heap,
NodeID &middle_node_id,
std::int32_t &upper_bound,
std::int32_t min_edge_offset,
const bool forward_direction,
const bool stalling,
const bool force_loop_forward,
const bool force_loop_reverse) const;
template <bool UseDuration> EdgeWeight GetLoopWeight(const FacadeT &facade, NodeID node) const
{ {
EdgeWeight loop_weight = UseDuration ? MAXIMAL_EDGE_DURATION : INVALID_EDGE_WEIGHT; const auto &data = facade.GetEdgeData(edge);
for (auto edge : facade.GetAdjacentEdgeRange(node)) if (data.forward)
{ {
const auto &data = facade.GetEdgeData(edge); const NodeID to = facade.GetTarget(edge);
if (data.forward) if (to == node)
{ {
const NodeID to = facade.GetTarget(edge); const auto value = UseDuration ? data.duration : data.weight;
if (to == node) loop_weight = std::min(loop_weight, value);
{
const auto value = UseDuration ? data.duration : data.weight;
loop_weight = std::min(loop_weight, value);
}
} }
} }
return loop_weight; }
return loop_weight;
}
/**
* Given a sequence of connected `NodeID`s in the CH graph, performs a depth-first unpacking of
* the shortcut
* edges. For every "original" edge found, it calls the `callback` with the two NodeIDs for the
* edge, and the EdgeData
* for that edge.
*
* The primary purpose of this unpacking is to expand a path through the CH into the original
* route through the
* pre-contracted graph.
*
* Because of the depth-first-search, the `callback` will effectively be called in sequence for
* the original route
* from beginning to end.
*
* @param packed_path_begin iterator pointing to the start of the NodeID list
* @param packed_path_end iterator pointing to the end of the NodeID list
* @param callback void(const std::pair<NodeID, NodeID>, const EdgeData &) called for each
* original edge found.
*/
template <typename BidirectionalIterator, typename Callback>
void unpackPath(const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
BidirectionalIterator packed_path_begin,
BidirectionalIterator packed_path_end,
Callback &&callback)
{
// make sure we have at least something to unpack
if (packed_path_begin == packed_path_end)
return;
std::stack<std::pair<NodeID, NodeID>> recursion_stack;
// We have to push the path in reverse order onto the stack because it's LIFO.
for (auto current = std::prev(packed_path_end); current != packed_path_begin;
current = std::prev(current))
{
recursion_stack.emplace(*std::prev(current), *current);
} }
template <typename RandomIter> std::pair<NodeID, NodeID> edge;
void UnpackPath(const FacadeT &facade, while (!recursion_stack.empty())
RandomIter packed_path_begin,
RandomIter packed_path_end,
const PhantomNodes &phantom_node_pair,
std::vector<PathData> &unpacked_path) const
{ {
BOOST_ASSERT(std::distance(packed_path_begin, packed_path_end) > 0); edge = recursion_stack.top();
recursion_stack.pop();
const bool start_traversed_in_reverse = // Look for an edge on the forward CH graph (.forward)
(*packed_path_begin != phantom_node_pair.source_phantom.forward_segment_id.id); EdgeID smaller_edge_id = facade.FindSmallestEdge(
const bool target_traversed_in_reverse = edge.first, edge.second, [](const auto &data) { return data.forward; });
(*std::prev(packed_path_end) != phantom_node_pair.target_phantom.forward_segment_id.id);
BOOST_ASSERT(*packed_path_begin == phantom_node_pair.source_phantom.forward_segment_id.id || // If we didn't find one there, the we might be looking at a part of the path that
*packed_path_begin == phantom_node_pair.source_phantom.reverse_segment_id.id); // was found using the backward search. Here, we flip the node order (.second, .first)
BOOST_ASSERT( // and only consider edges with the `.backward` flag.
*std::prev(packed_path_end) == phantom_node_pair.target_phantom.forward_segment_id.id || if (SPECIAL_EDGEID == smaller_edge_id)
*std::prev(packed_path_end) == phantom_node_pair.target_phantom.reverse_segment_id.id);
UnpackCHPath(
facade,
packed_path_begin,
packed_path_end,
[this,
&facade,
&unpacked_path,
&phantom_node_pair,
&start_traversed_in_reverse,
&target_traversed_in_reverse](std::pair<NodeID, NodeID> & /* edge */,
const EdgeData &edge_data) {
BOOST_ASSERT_MSG(!edge_data.shortcut, "original edge flagged as shortcut");
const auto name_index = facade.GetNameIndexFromEdgeID(edge_data.id);
const auto turn_instruction = facade.GetTurnInstructionForEdgeID(edge_data.id);
const extractor::TravelMode travel_mode =
(unpacked_path.empty() && start_traversed_in_reverse)
? phantom_node_pair.source_phantom.backward_travel_mode
: facade.GetTravelModeForEdgeID(edge_data.id);
const auto geometry_index = facade.GetGeometryIndexForEdgeID(edge_data.id);
std::vector<NodeID> id_vector;
std::vector<EdgeWeight> weight_vector;
std::vector<EdgeWeight> duration_vector;
std::vector<DatasourceID> datasource_vector;
if (geometry_index.forward)
{
id_vector = facade.GetUncompressedForwardGeometry(geometry_index.id);
weight_vector = facade.GetUncompressedForwardWeights(geometry_index.id);
duration_vector = facade.GetUncompressedForwardDurations(geometry_index.id);
datasource_vector = facade.GetUncompressedForwardDatasources(geometry_index.id);
}
else
{
id_vector = facade.GetUncompressedReverseGeometry(geometry_index.id);
weight_vector = facade.GetUncompressedReverseWeights(geometry_index.id);
duration_vector = facade.GetUncompressedReverseDurations(geometry_index.id);
datasource_vector = facade.GetUncompressedReverseDatasources(geometry_index.id);
}
BOOST_ASSERT(id_vector.size() > 0);
BOOST_ASSERT(datasource_vector.size() > 0);
BOOST_ASSERT(weight_vector.size() == id_vector.size() - 1);
BOOST_ASSERT(duration_vector.size() == id_vector.size() - 1);
const bool is_first_segment = unpacked_path.empty();
const std::size_t start_index =
(is_first_segment
? ((start_traversed_in_reverse)
? weight_vector.size() -
phantom_node_pair.source_phantom.fwd_segment_position - 1
: phantom_node_pair.source_phantom.fwd_segment_position)
: 0);
const std::size_t end_index = weight_vector.size();
BOOST_ASSERT(start_index >= 0);
BOOST_ASSERT(start_index < end_index);
for (std::size_t segment_idx = start_index; segment_idx < end_index; ++segment_idx)
{
unpacked_path.push_back(
PathData{id_vector[segment_idx + 1],
name_index,
weight_vector[segment_idx],
duration_vector[segment_idx],
extractor::guidance::TurnInstruction::NO_TURN(),
{{0, INVALID_LANEID}, INVALID_LANE_DESCRIPTIONID},
travel_mode,
INVALID_ENTRY_CLASSID,
datasource_vector[segment_idx],
util::guidance::TurnBearing(0),
util::guidance::TurnBearing(0)});
}
BOOST_ASSERT(unpacked_path.size() > 0);
if (facade.hasLaneData(edge_data.id))
unpacked_path.back().lane_data = facade.GetLaneData(edge_data.id);
unpacked_path.back().entry_classid = facade.GetEntryClassID(edge_data.id);
unpacked_path.back().turn_instruction = turn_instruction;
unpacked_path.back().duration_until_turn +=
facade.GetDurationPenaltyForEdgeID(edge_data.id);
unpacked_path.back().weight_until_turn +=
facade.GetWeightPenaltyForEdgeID(edge_data.id);
unpacked_path.back().pre_turn_bearing = facade.PreTurnBearing(edge_data.id);
unpacked_path.back().post_turn_bearing = facade.PostTurnBearing(edge_data.id);
});
std::size_t start_index = 0, end_index = 0;
std::vector<unsigned> id_vector;
std::vector<EdgeWeight> weight_vector;
std::vector<EdgeWeight> duration_vector;
std::vector<DatasourceID> datasource_vector;
const bool is_local_path = (phantom_node_pair.source_phantom.packed_geometry_id ==
phantom_node_pair.target_phantom.packed_geometry_id) &&
unpacked_path.empty();
if (target_traversed_in_reverse)
{ {
id_vector = facade.GetUncompressedReverseGeometry( smaller_edge_id = facade.FindSmallestEdge(
phantom_node_pair.target_phantom.packed_geometry_id); edge.second, edge.first, [](const auto &data) { return data.backward; });
}
weight_vector = facade.GetUncompressedReverseWeights( // If we didn't find anything *still*, then something is broken and someone has
phantom_node_pair.target_phantom.packed_geometry_id); // called this function with bad values.
BOOST_ASSERT_MSG(smaller_edge_id != SPECIAL_EDGEID, "Invalid smaller edge ID");
duration_vector = facade.GetUncompressedReverseDurations( const auto &data = facade.GetEdgeData(smaller_edge_id);
phantom_node_pair.target_phantom.packed_geometry_id); BOOST_ASSERT_MSG(data.weight != std::numeric_limits<EdgeWeight>::max(),
"edge weight invalid");
datasource_vector = facade.GetUncompressedReverseDatasources( // If the edge is a shortcut, we need to add the two halfs to the stack.
phantom_node_pair.target_phantom.packed_geometry_id); if (data.shortcut)
{ // unpack
if (is_local_path) const NodeID middle_node_id = data.id;
{ // Note the order here - we're adding these to a stack, so we
start_index = weight_vector.size() - // want the first->middle to get visited before middle->second
phantom_node_pair.source_phantom.fwd_segment_position - 1; recursion_stack.emplace(middle_node_id, edge.second);
} recursion_stack.emplace(edge.first, middle_node_id);
end_index =
weight_vector.size() - phantom_node_pair.target_phantom.fwd_segment_position - 1;
} }
else else
{ {
if (is_local_path) // We found an original edge, call our callback.
{ std::forward<Callback>(callback)(edge, data);
start_index = phantom_node_pair.source_phantom.fwd_segment_position;
}
end_index = phantom_node_pair.target_phantom.fwd_segment_position;
id_vector = facade.GetUncompressedForwardGeometry(
phantom_node_pair.target_phantom.packed_geometry_id);
weight_vector = facade.GetUncompressedForwardWeights(
phantom_node_pair.target_phantom.packed_geometry_id);
duration_vector = facade.GetUncompressedForwardDurations(
phantom_node_pair.target_phantom.packed_geometry_id);
datasource_vector = facade.GetUncompressedForwardDatasources(
phantom_node_pair.target_phantom.packed_geometry_id);
}
// Given the following compressed geometry:
// U---v---w---x---y---Z
// s t
// s: fwd_segment 0
// t: fwd_segment 3
// -> (U, v), (v, w), (w, x)
// note that (x, t) is _not_ included but needs to be added later.
for (std::size_t segment_idx = start_index; segment_idx != end_index;
(start_index < end_index ? ++segment_idx : --segment_idx))
{
BOOST_ASSERT(segment_idx < id_vector.size() - 1);
BOOST_ASSERT(phantom_node_pair.target_phantom.forward_travel_mode > 0);
unpacked_path.push_back(PathData{
id_vector[start_index < end_index ? segment_idx + 1 : segment_idx - 1],
phantom_node_pair.target_phantom.name_id,
weight_vector[segment_idx],
duration_vector[segment_idx],
extractor::guidance::TurnInstruction::NO_TURN(),
{{0, INVALID_LANEID}, INVALID_LANE_DESCRIPTIONID},
target_traversed_in_reverse ? phantom_node_pair.target_phantom.backward_travel_mode
: phantom_node_pair.target_phantom.forward_travel_mode,
INVALID_ENTRY_CLASSID,
datasource_vector[segment_idx],
util::guidance::TurnBearing(0),
util::guidance::TurnBearing(0)});
}
if (unpacked_path.size() > 0)
{
const auto source_weight = start_traversed_in_reverse
? phantom_node_pair.source_phantom.reverse_weight
: phantom_node_pair.source_phantom.forward_weight;
const auto source_duration = start_traversed_in_reverse
? phantom_node_pair.source_phantom.reverse_duration
: phantom_node_pair.source_phantom.forward_duration;
// The above code will create segments for (v, w), (w,x), (x, y) and (y, Z).
// However the first segment duration needs to be adjusted to the fact that the source
// phantom is in the middle of the segment. We do this by subtracting v--s from the
// duration.
// Since it's possible duration_until_turn can be less than source_weight here if
// a negative enough turn penalty is used to modify this edge weight during
// osrm-contract, we clamp to 0 here so as not to return a negative duration
// for this segment.
// TODO this creates a scenario where it's possible the duration from a phantom
// node to the first turn would be the same as from end to end of a segment,
// which is obviously incorrect and not ideal...
unpacked_path.front().weight_until_turn =
std::max(unpacked_path.front().weight_until_turn - source_weight, 0);
unpacked_path.front().duration_until_turn =
std::max(unpacked_path.front().duration_until_turn - source_duration, 0);
}
// there is no equivalent to a node-based node in an edge-expanded graph.
// two equivalent routes may start (or end) at different node-based edges
// as they are added with the offset how much "weight" on the edge
// has already been traversed. Depending on offset one needs to remove
// the last node.
if (unpacked_path.size() > 1)
{
const std::size_t last_index = unpacked_path.size() - 1;
const std::size_t second_to_last_index = last_index - 1;
if (unpacked_path[last_index].turn_via_node ==
unpacked_path[second_to_last_index].turn_via_node)
{
unpacked_path.pop_back();
}
BOOST_ASSERT(!unpacked_path.empty());
} }
} }
}
/** // Should work both for CH and not CH if the unpackPath function above is implemented a proper
* Unpacks a single edge (NodeID->NodeID) from the CH graph down to it's original non-shortcut // implementation.
* route. template <typename RandomIter, typename FacadeT>
* @param from the node the CH edge starts at void unpackPath(const FacadeT &facade,
* @param to the node the CH edge finishes at RandomIter packed_path_begin,
* @param unpacked_path the sequence of original NodeIDs that make up the expanded CH edge RandomIter packed_path_end,
*/ const PhantomNodes &phantom_node_pair,
void UnpackEdge(const FacadeT &facade, std::vector<PathData> &unpacked_path)
const NodeID from, {
const NodeID to, BOOST_ASSERT(std::distance(packed_path_begin, packed_path_end) > 0);
std::vector<NodeID> &unpacked_path) const;
void RetrievePackedPathFromHeap(const SearchEngineData::QueryHeap &forward_heap, const bool start_traversed_in_reverse =
const SearchEngineData::QueryHeap &reverse_heap, (*packed_path_begin != phantom_node_pair.source_phantom.forward_segment_id.id);
const NodeID middle_node_id, const bool target_traversed_in_reverse =
std::vector<NodeID> &packed_path) const; (*std::prev(packed_path_end) != phantom_node_pair.target_phantom.forward_segment_id.id);
void RetrievePackedPathFromSingleHeap(const SearchEngineData::QueryHeap &search_heap, BOOST_ASSERT(*packed_path_begin == phantom_node_pair.source_phantom.forward_segment_id.id ||
const NodeID middle_node_id, *packed_path_begin == phantom_node_pair.source_phantom.reverse_segment_id.id);
std::vector<NodeID> &packed_path) const; BOOST_ASSERT(
*std::prev(packed_path_end) == phantom_node_pair.target_phantom.forward_segment_id.id ||
*std::prev(packed_path_end) == phantom_node_pair.target_phantom.reverse_segment_id.id);
// assumes that heaps are already setup correctly. unpackPath(
// ATTENTION: This only works if no additional offset is supplied next to the Phantom Node facade,
// Offsets. packed_path_begin,
// In case additional offsets are supplied, you might have to force a loop first. packed_path_end,
// A forced loop might be necessary, if source and target are on the same segment. [&facade,
// If this is the case and the offsets of the respective direction are larger for the source &unpacked_path,
// than the target &phantom_node_pair,
// then a force loop is required (e.g. source_phantom.forward_segment_id == &start_traversed_in_reverse,
// target_phantom.forward_segment_id &target_traversed_in_reverse](std::pair<NodeID, NodeID> & /* edge */,
// && source_phantom.GetForwardWeightPlusOffset() > target_phantom.GetForwardWeightPlusOffset()) const auto &edge_data) {
// requires
// a force loop, if the heaps have been initialized with positive offsets.
void Search(const FacadeT &facade,
SearchEngineData::QueryHeap &forward_heap,
SearchEngineData::QueryHeap &reverse_heap,
std::int32_t &weight,
std::vector<NodeID> &packed_leg,
const bool force_loop_forward,
const bool force_loop_reverse,
const int duration_upper_bound = INVALID_EDGE_WEIGHT) const;
// assumes that heaps are already setup correctly. BOOST_ASSERT_MSG(!edge_data.shortcut, "original edge flagged as shortcut");
// A forced loop might be necessary, if source and target are on the same segment. const auto name_index = facade.GetNameIndexFromEdgeID(edge_data.id);
// If this is the case and the offsets of the respective direction are larger for the source const auto turn_instruction = facade.GetTurnInstructionForEdgeID(edge_data.id);
// than the target const extractor::TravelMode travel_mode =
// then a force loop is required (e.g. source_phantom.forward_segment_id == (unpacked_path.empty() && start_traversed_in_reverse)
// target_phantom.forward_segment_id ? phantom_node_pair.source_phantom.backward_travel_mode
// && source_phantom.GetForwardWeightPlusOffset() > target_phantom.GetForwardWeightPlusOffset()) : facade.GetTravelModeForEdgeID(edge_data.id);
// requires
// a force loop, if the heaps have been initialized with positive offsets.
void SearchWithCore(const FacadeT &facade,
SearchEngineData::QueryHeap &forward_heap,
SearchEngineData::QueryHeap &reverse_heap,
SearchEngineData::QueryHeap &forward_core_heap,
SearchEngineData::QueryHeap &reverse_core_heap,
int &weight,
std::vector<NodeID> &packed_leg,
const bool force_loop_forward,
const bool force_loop_reverse,
int duration_upper_bound = INVALID_EDGE_WEIGHT) const;
bool NeedsLoopForward(const PhantomNode &source_phantom, const auto geometry_index = facade.GetGeometryIndexForEdgeID(edge_data.id);
const PhantomNode &target_phantom) const; std::vector<NodeID> id_vector;
bool NeedsLoopBackwards(const PhantomNode &source_phantom, std::vector<EdgeWeight> weight_vector;
const PhantomNode &target_phantom) const; std::vector<EdgeWeight> duration_vector;
std::vector<DatasourceID> datasource_vector;
if (geometry_index.forward)
{
id_vector = facade.GetUncompressedForwardGeometry(geometry_index.id);
weight_vector = facade.GetUncompressedForwardWeights(geometry_index.id);
duration_vector = facade.GetUncompressedForwardDurations(geometry_index.id);
datasource_vector = facade.GetUncompressedForwardDatasources(geometry_index.id);
}
else
{
id_vector = facade.GetUncompressedReverseGeometry(geometry_index.id);
weight_vector = facade.GetUncompressedReverseWeights(geometry_index.id);
duration_vector = facade.GetUncompressedReverseDurations(geometry_index.id);
datasource_vector = facade.GetUncompressedReverseDatasources(geometry_index.id);
}
BOOST_ASSERT(id_vector.size() > 0);
BOOST_ASSERT(datasource_vector.size() > 0);
BOOST_ASSERT(weight_vector.size() == id_vector.size() - 1);
BOOST_ASSERT(duration_vector.size() == id_vector.size() - 1);
const bool is_first_segment = unpacked_path.empty();
double GetPathDistance(const FacadeT &facade, const std::size_t start_index =
const std::vector<NodeID> &packed_path, (is_first_segment
const PhantomNode &source_phantom, ? ((start_traversed_in_reverse)
const PhantomNode &target_phantom) const; ? weight_vector.size() -
phantom_node_pair.source_phantom.fwd_segment_position - 1
: phantom_node_pair.source_phantom.fwd_segment_position)
: 0);
const std::size_t end_index = weight_vector.size();
// Requires the heaps for be empty BOOST_ASSERT(start_index >= 0);
// If heaps should be adjusted to be initialized outside of this function, BOOST_ASSERT(start_index < end_index);
// the addition of force_loop parameters might be required for (std::size_t segment_idx = start_index; segment_idx < end_index; ++segment_idx)
double GetNetworkDistanceWithCore(const FacadeT &facade, {
SearchEngineData::QueryHeap &forward_heap, unpacked_path.push_back(PathData{id_vector[segment_idx + 1],
SearchEngineData::QueryHeap &reverse_heap, name_index,
SearchEngineData::QueryHeap &forward_core_heap, weight_vector[segment_idx],
SearchEngineData::QueryHeap &reverse_core_heap, duration_vector[segment_idx],
const PhantomNode &source_phantom, extractor::guidance::TurnInstruction::NO_TURN(),
const PhantomNode &target_phantom, {{0, INVALID_LANEID}, INVALID_LANE_DESCRIPTIONID},
int duration_upper_bound = INVALID_EDGE_WEIGHT) const; travel_mode,
INVALID_ENTRY_CLASSID,
datasource_vector[segment_idx],
util::guidance::TurnBearing(0),
util::guidance::TurnBearing(0)});
}
BOOST_ASSERT(unpacked_path.size() > 0);
if (facade.hasLaneData(edge_data.id))
unpacked_path.back().lane_data = facade.GetLaneData(edge_data.id);
// Requires the heaps for be empty unpacked_path.back().entry_classid = facade.GetEntryClassID(edge_data.id);
// If heaps should be adjusted to be initialized outside of this function, unpacked_path.back().turn_instruction = turn_instruction;
// the addition of force_loop parameters might be required unpacked_path.back().duration_until_turn +=
double GetNetworkDistance(const FacadeT &facade, facade.GetDurationPenaltyForEdgeID(edge_data.id);
SearchEngineData::QueryHeap &forward_heap, unpacked_path.back().weight_until_turn +=
SearchEngineData::QueryHeap &reverse_heap, facade.GetWeightPenaltyForEdgeID(edge_data.id);
const PhantomNode &source_phantom, unpacked_path.back().pre_turn_bearing = facade.PreTurnBearing(edge_data.id);
const PhantomNode &target_phantom, unpacked_path.back().post_turn_bearing = facade.PostTurnBearing(edge_data.id);
int duration_upper_bound = INVALID_EDGE_WEIGHT) const; });
};
std::size_t start_index = 0, end_index = 0;
std::vector<unsigned> id_vector;
std::vector<EdgeWeight> weight_vector;
std::vector<EdgeWeight> duration_vector;
std::vector<DatasourceID> datasource_vector;
const bool is_local_path = (phantom_node_pair.source_phantom.packed_geometry_id ==
phantom_node_pair.target_phantom.packed_geometry_id) &&
unpacked_path.empty();
if (target_traversed_in_reverse)
{
id_vector = facade.GetUncompressedReverseGeometry(
phantom_node_pair.target_phantom.packed_geometry_id);
weight_vector = facade.GetUncompressedReverseWeights(
phantom_node_pair.target_phantom.packed_geometry_id);
duration_vector = facade.GetUncompressedReverseDurations(
phantom_node_pair.target_phantom.packed_geometry_id);
datasource_vector = facade.GetUncompressedReverseDatasources(
phantom_node_pair.target_phantom.packed_geometry_id);
if (is_local_path)
{
start_index =
weight_vector.size() - phantom_node_pair.source_phantom.fwd_segment_position - 1;
}
end_index =
weight_vector.size() - phantom_node_pair.target_phantom.fwd_segment_position - 1;
}
else
{
if (is_local_path)
{
start_index = phantom_node_pair.source_phantom.fwd_segment_position;
}
end_index = phantom_node_pair.target_phantom.fwd_segment_position;
id_vector = facade.GetUncompressedForwardGeometry(
phantom_node_pair.target_phantom.packed_geometry_id);
weight_vector = facade.GetUncompressedForwardWeights(
phantom_node_pair.target_phantom.packed_geometry_id);
duration_vector = facade.GetUncompressedForwardDurations(
phantom_node_pair.target_phantom.packed_geometry_id);
datasource_vector = facade.GetUncompressedForwardDatasources(
phantom_node_pair.target_phantom.packed_geometry_id);
}
// Given the following compressed geometry:
// U---v---w---x---y---Z
// s t
// s: fwd_segment 0
// t: fwd_segment 3
// -> (U, v), (v, w), (w, x)
// note that (x, t) is _not_ included but needs to be added later.
for (std::size_t segment_idx = start_index; segment_idx != end_index;
(start_index < end_index ? ++segment_idx : --segment_idx))
{
BOOST_ASSERT(segment_idx < id_vector.size() - 1);
BOOST_ASSERT(phantom_node_pair.target_phantom.forward_travel_mode > 0);
unpacked_path.push_back(PathData{
id_vector[start_index < end_index ? segment_idx + 1 : segment_idx - 1],
phantom_node_pair.target_phantom.name_id,
weight_vector[segment_idx],
duration_vector[segment_idx],
extractor::guidance::TurnInstruction::NO_TURN(),
{{0, INVALID_LANEID}, INVALID_LANE_DESCRIPTIONID},
target_traversed_in_reverse ? phantom_node_pair.target_phantom.backward_travel_mode
: phantom_node_pair.target_phantom.forward_travel_mode,
INVALID_ENTRY_CLASSID,
datasource_vector[segment_idx],
util::guidance::TurnBearing(0),
util::guidance::TurnBearing(0)});
}
if (unpacked_path.size() > 0)
{
const auto source_weight = start_traversed_in_reverse
? phantom_node_pair.source_phantom.reverse_weight
: phantom_node_pair.source_phantom.forward_weight;
const auto source_duration = start_traversed_in_reverse
? phantom_node_pair.source_phantom.reverse_duration
: phantom_node_pair.source_phantom.forward_duration;
// The above code will create segments for (v, w), (w,x), (x, y) and (y, Z).
// However the first segment duration needs to be adjusted to the fact that the source
// phantom is in the middle of the segment. We do this by subtracting v--s from the
// duration.
// Since it's possible duration_until_turn can be less than source_weight here if
// a negative enough turn penalty is used to modify this edge weight during
// osrm-contract, we clamp to 0 here so as not to return a negative duration
// for this segment.
// TODO this creates a scenario where it's possible the duration from a phantom
// node to the first turn would be the same as from end to end of a segment,
// which is obviously incorrect and not ideal...
unpacked_path.front().weight_until_turn =
std::max(unpacked_path.front().weight_until_turn - source_weight, 0);
unpacked_path.front().duration_until_turn =
std::max(unpacked_path.front().duration_until_turn - source_duration, 0);
}
// there is no equivalent to a node-based node in an edge-expanded graph.
// two equivalent routes may start (or end) at different node-based edges
// as they are added with the offset how much "weight" on the edge
// has already been traversed. Depending on offset one needs to remove
// the last node.
if (unpacked_path.size() > 1)
{
const std::size_t last_index = unpacked_path.size() - 1;
const std::size_t second_to_last_index = last_index - 1;
if (unpacked_path[last_index].turn_via_node ==
unpacked_path[second_to_last_index].turn_via_node)
{
unpacked_path.pop_back();
}
BOOST_ASSERT(!unpacked_path.empty());
}
}
/**
* Unpacks a single edge (NodeID->NodeID) from the CH graph down to it's original non-shortcut
* route.
* @param from the node the CH edge starts at
* @param to the node the CH edge finishes at
* @param unpacked_path the sequence of original NodeIDs that make up the expanded CH edge
*/
void unpackEdge(const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
const NodeID from,
const NodeID to,
std::vector<NodeID> &unpacked_path);
void retrievePackedPathFromHeap(const SearchEngineData::QueryHeap &forward_heap,
const SearchEngineData::QueryHeap &reverse_heap,
const NodeID middle_node_id,
std::vector<NodeID> &packed_path);
void retrievePackedPathFromSingleHeap(const SearchEngineData::QueryHeap &search_heap,
const NodeID middle_node_id,
std::vector<NodeID> &packed_path);
// assumes that heaps are already setup correctly.
// ATTENTION: This only works if no additional offset is supplied next to the Phantom Node
// Offsets.
// In case additional offsets are supplied, you might have to force a loop first.
// A forced loop might be necessary, if source and target are on the same segment.
// If this is the case and the offsets of the respective direction are larger for the source
// than the target
// then a force loop is required (e.g. source_phantom.forward_segment_id ==
// target_phantom.forward_segment_id
// && source_phantom.GetForwardWeightPlusOffset() > target_phantom.GetForwardWeightPlusOffset())
// requires
// a force loop, if the heaps have been initialized with positive offsets.
void search(const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
SearchEngineData::QueryHeap &forward_heap,
SearchEngineData::QueryHeap &reverse_heap,
std::int32_t &weight,
std::vector<NodeID> &packed_leg,
const bool force_loop_forward,
const bool force_loop_reverse,
const int duration_upper_bound = INVALID_EDGE_WEIGHT);
// assumes that heaps are already setup correctly.
// A forced loop might be necessary, if source and target are on the same segment.
// If this is the case and the offsets of the respective direction are larger for the source
// than the target
// then a force loop is required (e.g. source_phantom.forward_segment_id ==
// target_phantom.forward_segment_id
// && source_phantom.GetForwardWeightPlusOffset() > target_phantom.GetForwardWeightPlusOffset())
// requires
// a force loop, if the heaps have been initialized with positive offsets.
void searchWithCore(const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
SearchEngineData::QueryHeap &forward_heap,
SearchEngineData::QueryHeap &reverse_heap,
SearchEngineData::QueryHeap &forward_core_heap,
SearchEngineData::QueryHeap &reverse_core_heap,
int &weight,
std::vector<NodeID> &packed_leg,
const bool force_loop_forward,
const bool force_loop_reverse,
int duration_upper_bound = INVALID_EDGE_WEIGHT);
bool needsLoopForward(const PhantomNode &source_phantom, const PhantomNode &target_phantom);
bool needsLoopBackwards(const PhantomNode &source_phantom, const PhantomNode &target_phantom);
double getPathDistance(const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
const std::vector<NodeID> &packed_path,
const PhantomNode &source_phantom,
const PhantomNode &target_phantom);
// Requires the heaps for be empty
// If heaps should be adjusted to be initialized outside of this function,
// the addition of force_loop parameters might be required
double getNetworkDistanceWithCore(
const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
SearchEngineData::QueryHeap &forward_heap,
SearchEngineData::QueryHeap &reverse_heap,
SearchEngineData::QueryHeap &forward_core_heap,
SearchEngineData::QueryHeap &reverse_core_heap,
const PhantomNode &source_phantom,
const PhantomNode &target_phantom,
int duration_upper_bound = INVALID_EDGE_WEIGHT);
// Requires the heaps for be empty
// If heaps should be adjusted to be initialized outside of this function,
// the addition of force_loop parameters might be required
double
getNetworkDistance(const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
SearchEngineData::QueryHeap &forward_heap,
SearchEngineData::QueryHeap &reverse_heap,
const PhantomNode &source_phantom,
const PhantomNode &target_phantom,
int duration_upper_bound = INVALID_EDGE_WEIGHT);
} // namespace routing_algorithms } // namespace routing_algorithms
} // namespace engine } // namespace engine

View File

@ -4,13 +4,8 @@
#include "engine/algorithm.hpp" #include "engine/algorithm.hpp"
#include "engine/routing_algorithms/routing_base.hpp" #include "engine/routing_algorithms/routing_base.hpp"
#include "engine/search_engine_data.hpp" #include "engine/search_engine_data.hpp"
#include "util/integer_range.hpp"
#include "util/typedefs.hpp" #include "util/typedefs.hpp"
#include <boost/assert.hpp>
#include <boost/optional.hpp>
#include <memory>
namespace osrm namespace osrm
{ {
namespace engine namespace engine
@ -18,75 +13,12 @@ namespace engine
namespace routing_algorithms namespace routing_algorithms
{ {
template <typename AlgorithmT> class ShortestPathRouting; InternalRouteResult
shortestPathSearch(SearchEngineData &engine_working_data,
const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
const std::vector<PhantomNodes> &phantom_nodes_vector,
const boost::optional<bool> continue_straight_at_waypoint);
template <> class ShortestPathRouting<algorithm::CH> final : public BasicRouting<algorithm::CH>
{
using super = BasicRouting<algorithm::CH>;
using FacadeT = datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH>;
using QueryHeap = SearchEngineData::QueryHeap;
SearchEngineData &engine_working_data;
const static constexpr bool DO_NOT_FORCE_LOOP = false;
public:
ShortestPathRouting(SearchEngineData &engine_working_data)
: engine_working_data(engine_working_data)
{
}
~ShortestPathRouting() {}
// allows a uturn at the target_phantom
// searches source forward/reverse -> target forward/reverse
void SearchWithUTurn(const FacadeT &facade,
QueryHeap &forward_heap,
QueryHeap &reverse_heap,
QueryHeap &forward_core_heap,
QueryHeap &reverse_core_heap,
const bool search_from_forward_node,
const bool search_from_reverse_node,
const bool search_to_forward_node,
const bool search_to_reverse_node,
const PhantomNode &source_phantom,
const PhantomNode &target_phantom,
const int total_weight_to_forward,
const int total_weight_to_reverse,
int &new_total_weight,
std::vector<NodeID> &leg_packed_path) const;
// searches shortest path between:
// source forward/reverse -> target forward
// source forward/reverse -> target reverse
void Search(const FacadeT &facade,
QueryHeap &forward_heap,
QueryHeap &reverse_heap,
QueryHeap &forward_core_heap,
QueryHeap &reverse_core_heap,
const bool search_from_forward_node,
const bool search_from_reverse_node,
const bool search_to_forward_node,
const bool search_to_reverse_node,
const PhantomNode &source_phantom,
const PhantomNode &target_phantom,
const int total_weight_to_forward,
const int total_weight_to_reverse,
int &new_total_weight_to_forward,
int &new_total_weight_to_reverse,
std::vector<NodeID> &leg_packed_path_forward,
std::vector<NodeID> &leg_packed_path_reverse) const;
void UnpackLegs(const FacadeT &facade,
const std::vector<PhantomNodes> &phantom_nodes_vector,
const std::vector<NodeID> &total_packed_path,
const std::vector<std::size_t> &packed_leg_begin,
const int shortest_path_length,
InternalRouteResult &raw_route_data) const;
void operator()(const FacadeT &facade,
const std::vector<PhantomNodes> &phantom_nodes_vector,
const boost::optional<bool> continue_straight_at_waypoint,
InternalRouteResult &raw_route_data) const;
};
} // namespace routing_algorithms } // namespace routing_algorithms
} // namespace engine } // namespace engine
} // namespace osrm } // namespace osrm

View File

@ -1,12 +1,14 @@
#ifndef OSRM_ENGINE_ROUTING_ALGORITHMS_TILE_TURNS_HPP #ifndef OSRM_ENGINE_ROUTING_ALGORITHMS_TILE_TURNS_HPP
#define OSRM_ENGINE_ROUTING_ALGORITHMS_TILE_TURNS_HPP #define OSRM_ENGINE_ROUTING_ALGORITHMS_TILE_TURNS_HPP
#include "engine/routing_algorithms/routing_base.hpp"
#include "engine/algorithm.hpp" #include "engine/algorithm.hpp"
#include "engine/search_engine_data.hpp" #include "engine/datafacade/contiguous_internalmem_datafacade.hpp"
#include "util/coordinate.hpp"
#include "util/typedefs.hpp" #include "util/typedefs.hpp"
#include <vector>
namespace osrm namespace osrm
{ {
namespace engine namespace engine
@ -14,8 +16,6 @@ namespace engine
namespace routing_algorithms namespace routing_algorithms
{ {
template <typename AlgorithmT> class TileTurns;
// Used to accumulate all the information we want in the tile about a turn. // Used to accumulate all the information we want in the tile about a turn.
struct TurnData final struct TurnData final
{ {
@ -25,19 +25,12 @@ struct TurnData final
const int weight; const int weight;
}; };
/// This class is used to extract turn information for the tile plugin from a CH graph using RTreeLeaf = datafacade::BaseDataFacade::RTreeLeaf;
template <> class TileTurns<algorithm::CH> final : public BasicRouting<algorithm::CH>
{
using super = BasicRouting<algorithm::CH>;
using FacadeT = datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH>;
using RTreeLeaf = datafacade::BaseDataFacade::RTreeLeaf; std::vector<TurnData>
getTileTurns(const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
public: const std::vector<RTreeLeaf> &edges,
std::vector<TurnData> operator()(const FacadeT &facade, const std::vector<std::size_t> &sorted_edge_indexes);
const std::vector<RTreeLeaf> &edges,
const std::vector<std::size_t> &sorted_edge_indexes) const;
};
} // namespace routing_algorithms } // namespace routing_algorithms
} // namespace engine } // namespace engine

View File

@ -208,8 +208,8 @@ Status MatchPlugin::HandleRequest(const datafacade::ContiguousInternalMemoryData
// force uturns to be on, since we split the phantom nodes anyway and only have // force uturns to be on, since we split the phantom nodes anyway and only have
// bi-directional // bi-directional
// phantom nodes for possible uturns // phantom nodes for possible uturns
algorithms.ShortestRouting( sub_routes[index] =
sub_routes[index].segment_end_coordinates, {false}, sub_routes[index]); algorithms.ShortestRouting(sub_routes[index].segment_end_coordinates, {false});
BOOST_ASSERT(sub_routes[index].shortest_path_length != INVALID_EDGE_WEIGHT); BOOST_ASSERT(sub_routes[index].shortest_path_length != INVALID_EDGE_WEIGHT);
} }

View File

@ -1,5 +1,4 @@
#include "engine/plugins/tile.hpp" #include "engine/plugins/tile.hpp"
#include "engine/edge_unpacker.hpp"
#include "engine/plugins/plugin_base.hpp" #include "engine/plugins/plugin_base.hpp"
#include "util/coordinate_calculation.hpp" #include "util/coordinate_calculation.hpp"

View File

@ -85,7 +85,7 @@ InternalRouteResult TripPlugin::ComputeRoute(const RoutingAlgorithmsInterface &a
BOOST_ASSERT(min_route.segment_end_coordinates.size() == trip.size() - 1); BOOST_ASSERT(min_route.segment_end_coordinates.size() == trip.size() - 1);
} }
algorithms.ShortestRouting(min_route.segment_end_coordinates, {false}, min_route); min_route = algorithms.ShortestRouting(min_route.segment_end_coordinates, {false});
BOOST_ASSERT_MSG(min_route.shortest_path_length < INVALID_EDGE_WEIGHT, "unroutable route"); BOOST_ASSERT_MSG(min_route.shortest_path_length < INVALID_EDGE_WEIGHT, "unroutable route");
return min_route; return min_route;
} }

View File

@ -89,17 +89,17 @@ ViaRoutePlugin::HandleRequest(const datafacade::ContiguousInternalMemoryDataFaca
{ {
if (route_parameters.alternatives && algorithms.HasAlternativeRouting()) if (route_parameters.alternatives && algorithms.HasAlternativeRouting())
{ {
algorithms.AlternativeRouting(raw_route.segment_end_coordinates.front(), raw_route); raw_route = algorithms.AlternativeRouting(raw_route.segment_end_coordinates.front());
} }
else else
{ {
algorithms.DirectShortestPathRouting(raw_route.segment_end_coordinates, raw_route); raw_route = algorithms.DirectShortestPathRouting(raw_route.segment_end_coordinates);
} }
} }
else else
{ {
algorithms.ShortestRouting( raw_route = algorithms.ShortestRouting(raw_route.segment_end_coordinates,
raw_route.segment_end_coordinates, route_parameters.continue_straight, raw_route); route_parameters.continue_straight);
} }
// we can only know this after the fact, different SCC ids still // we can only know this after the fact, different SCC ids still

File diff suppressed because it is too large Load Diff

View File

@ -1,5 +1,7 @@
#include "engine/routing_algorithms/direct_shortest_path.hpp" #include "engine/routing_algorithms/direct_shortest_path.hpp"
#include "engine/routing_algorithms/routing_base.hpp"
namespace osrm namespace osrm
{ {
namespace engine namespace engine
@ -13,11 +15,12 @@ namespace routing_algorithms
/// by the previous route. /// by the previous route.
/// This variation is only an optimazation for graphs with slow queries, for example /// This variation is only an optimazation for graphs with slow queries, for example
/// not fully contracted graphs. /// not fully contracted graphs.
void DirectShortestPathRouting<algorithm::CH>:: InternalRouteResult directShortestPathSearch(
operator()(const FacadeT &facade, SearchEngineData &engine_working_data,
const std::vector<PhantomNodes> &phantom_nodes_vector, const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
InternalRouteResult &raw_route_data) const const std::vector<PhantomNodes> &phantom_nodes_vector)
{ {
InternalRouteResult raw_route_data;
// Get weight to next pair of target nodes. // Get weight to next pair of target nodes.
BOOST_ASSERT_MSG(1 == phantom_nodes_vector.size(), BOOST_ASSERT_MSG(1 == phantom_nodes_vector.size(),
"Direct Shortest Path Query only accepts a single source and target pair. " "Direct Shortest Path Query only accepts a single source and target pair. "
@ -27,8 +30,8 @@ operator()(const FacadeT &facade,
const auto &target_phantom = phantom_node_pair.target_phantom; const auto &target_phantom = phantom_node_pair.target_phantom;
engine_working_data.InitializeOrClearFirstThreadLocalStorage(facade.GetNumberOfNodes()); engine_working_data.InitializeOrClearFirstThreadLocalStorage(facade.GetNumberOfNodes());
QueryHeap &forward_heap = *(engine_working_data.forward_heap_1); auto &forward_heap = *(engine_working_data.forward_heap_1);
QueryHeap &reverse_heap = *(engine_working_data.reverse_heap_1); auto &reverse_heap = *(engine_working_data.reverse_heap_1);
forward_heap.Clear(); forward_heap.Clear();
reverse_heap.Clear(); reverse_heap.Clear();
@ -71,30 +74,30 @@ operator()(const FacadeT &facade,
if (facade.GetCoreSize() > 0) if (facade.GetCoreSize() > 0)
{ {
engine_working_data.InitializeOrClearSecondThreadLocalStorage(facade.GetNumberOfNodes()); engine_working_data.InitializeOrClearSecondThreadLocalStorage(facade.GetNumberOfNodes());
QueryHeap &forward_core_heap = *(engine_working_data.forward_heap_2); auto &forward_core_heap = *(engine_working_data.forward_heap_2);
QueryHeap &reverse_core_heap = *(engine_working_data.reverse_heap_2); auto &reverse_core_heap = *(engine_working_data.reverse_heap_2);
forward_core_heap.Clear(); forward_core_heap.Clear();
reverse_core_heap.Clear(); reverse_core_heap.Clear();
super::SearchWithCore(facade, searchWithCore(facade,
forward_heap, forward_heap,
reverse_heap, reverse_heap,
forward_core_heap, forward_core_heap,
reverse_core_heap, reverse_core_heap,
weight, weight,
packed_leg, packed_leg,
DO_NOT_FORCE_LOOPS, DO_NOT_FORCE_LOOPS,
DO_NOT_FORCE_LOOPS); DO_NOT_FORCE_LOOPS);
} }
else else
{ {
super::Search(facade, search(facade,
forward_heap, forward_heap,
reverse_heap, reverse_heap,
weight, weight,
packed_leg, packed_leg,
DO_NOT_FORCE_LOOPS, DO_NOT_FORCE_LOOPS,
DO_NOT_FORCE_LOOPS); DO_NOT_FORCE_LOOPS);
} }
// No path found for both target nodes? // No path found for both target nodes?
@ -102,7 +105,7 @@ operator()(const FacadeT &facade,
{ {
raw_route_data.shortest_path_length = INVALID_EDGE_WEIGHT; raw_route_data.shortest_path_length = INVALID_EDGE_WEIGHT;
raw_route_data.alternative_path_length = INVALID_EDGE_WEIGHT; raw_route_data.alternative_path_length = INVALID_EDGE_WEIGHT;
return; return raw_route_data;
} }
BOOST_ASSERT_MSG(!packed_leg.empty(), "packed path empty"); BOOST_ASSERT_MSG(!packed_leg.empty(), "packed path empty");
@ -114,11 +117,13 @@ operator()(const FacadeT &facade,
raw_route_data.target_traversed_in_reverse.push_back( raw_route_data.target_traversed_in_reverse.push_back(
(packed_leg.back() != phantom_node_pair.target_phantom.forward_segment_id.id)); (packed_leg.back() != phantom_node_pair.target_phantom.forward_segment_id.id));
super::UnpackPath(facade, unpackPath(facade,
packed_leg.begin(), packed_leg.begin(),
packed_leg.end(), packed_leg.end(),
phantom_node_pair, phantom_node_pair,
raw_route_data.unpacked_path_segments.front()); raw_route_data.unpacked_path_segments.front());
return raw_route_data;
} }
} // namespace routing_algorithms } // namespace routing_algorithms
} // namespace engine } // namespace engine

View File

@ -1,4 +1,12 @@
#include "engine/routing_algorithms/many_to_many.hpp" #include "engine/routing_algorithms/many_to_many.hpp"
#include "engine/routing_algorithms/routing_base.hpp"
#include <boost/assert.hpp>
#include <limits>
#include <memory>
#include <unordered_map>
#include <vector>
namespace osrm namespace osrm
{ {
@ -7,11 +15,172 @@ namespace engine
namespace routing_algorithms namespace routing_algorithms
{ {
std::vector<EdgeWeight> ManyToManyRouting<algorithm::CH>:: using QueryHeap = SearchEngineData::ManyToManyQueryHeap;
operator()(const FacadeT &facade,
const std::vector<PhantomNode> &phantom_nodes, namespace
const std::vector<std::size_t> &source_indices, {
const std::vector<std::size_t> &target_indices) const struct NodeBucket
{
unsigned target_id; // essentially a row in the weight matrix
EdgeWeight weight;
EdgeWeight duration;
NodeBucket(const unsigned target_id, const EdgeWeight weight, const EdgeWeight duration)
: target_id(target_id), weight(weight), duration(duration)
{
}
};
// FIXME This should be replaced by an std::unordered_multimap, though this needs benchmarking
using SearchSpaceWithBuckets = std::unordered_map<NodeID, std::vector<NodeBucket>>;
template <bool forward_direction>
void relaxOutgoingEdges(const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
const NodeID node,
const EdgeWeight weight,
const EdgeWeight duration,
QueryHeap &query_heap)
{
for (auto edge : facade.GetAdjacentEdgeRange(node))
{
const auto &data = facade.GetEdgeData(edge);
const bool direction_flag = (forward_direction ? data.forward : data.backward);
if (direction_flag)
{
const NodeID to = facade.GetTarget(edge);
const EdgeWeight edge_weight = data.weight;
const EdgeWeight edge_duration = data.duration;
BOOST_ASSERT_MSG(edge_weight > 0, "edge_weight invalid");
const EdgeWeight to_weight = weight + edge_weight;
const EdgeWeight to_duration = duration + edge_duration;
// New Node discovered -> Add to Heap + Node Info Storage
if (!query_heap.WasInserted(to))
{
query_heap.Insert(to, to_weight, {node, to_duration});
}
// Found a shorter Path -> Update weight
else if (to_weight < query_heap.GetKey(to))
{
// new parent
query_heap.GetData(to) = {node, to_duration};
query_heap.DecreaseKey(to, to_weight);
}
}
}
}
// Stalling
template <bool forward_direction>
bool stallAtNode(const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
const NodeID node,
const EdgeWeight weight,
QueryHeap &query_heap)
{
for (auto edge : facade.GetAdjacentEdgeRange(node))
{
const auto &data = facade.GetEdgeData(edge);
const bool reverse_flag = ((!forward_direction) ? data.forward : data.backward);
if (reverse_flag)
{
const NodeID to = facade.GetTarget(edge);
const EdgeWeight edge_weight = data.weight;
BOOST_ASSERT_MSG(edge_weight > 0, "edge_weight invalid");
if (query_heap.WasInserted(to))
{
if (query_heap.GetKey(to) + edge_weight < weight)
{
return true;
}
}
}
}
return false;
}
void ForwardRoutingStep(const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
const unsigned row_idx,
const unsigned number_of_targets,
QueryHeap &query_heap,
const SearchSpaceWithBuckets &search_space_with_buckets,
std::vector<EdgeWeight> &weights_table,
std::vector<EdgeWeight> &durations_table)
{
const NodeID node = query_heap.DeleteMin();
const EdgeWeight source_weight = query_heap.GetKey(node);
const EdgeWeight source_duration = query_heap.GetData(node).duration;
// check if each encountered node has an entry
const auto bucket_iterator = search_space_with_buckets.find(node);
// iterate bucket if there exists one
if (bucket_iterator != search_space_with_buckets.end())
{
const std::vector<NodeBucket> &bucket_list = bucket_iterator->second;
for (const NodeBucket &current_bucket : bucket_list)
{
// get target id from bucket entry
const unsigned column_idx = current_bucket.target_id;
const EdgeWeight target_weight = current_bucket.weight;
const EdgeWeight target_duration = current_bucket.duration;
auto &current_weight = weights_table[row_idx * number_of_targets + column_idx];
auto &current_duration = durations_table[row_idx * number_of_targets + column_idx];
// check if new weight is better
const EdgeWeight new_weight = source_weight + target_weight;
if (new_weight < 0)
{
const EdgeWeight loop_weight = getLoopWeight<false>(facade, node);
const EdgeWeight new_weight_with_loop = new_weight + loop_weight;
if (loop_weight != INVALID_EDGE_WEIGHT && new_weight_with_loop >= 0)
{
current_weight = std::min(current_weight, new_weight_with_loop);
current_duration = std::min(current_duration,
source_duration + target_duration +
getLoopWeight<true>(facade, node));
}
}
else if (new_weight < current_weight)
{
current_weight = new_weight;
current_duration = source_duration + target_duration;
}
}
}
if (stallAtNode<true>(facade, node, source_weight, query_heap))
{
return;
}
relaxOutgoingEdges<true>(facade, node, source_weight, source_duration, query_heap);
}
void backwardRoutingStep(
const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
const unsigned column_idx,
QueryHeap &query_heap,
SearchSpaceWithBuckets &search_space_with_buckets)
{
const NodeID node = query_heap.DeleteMin();
const EdgeWeight target_weight = query_heap.GetKey(node);
const EdgeWeight target_duration = query_heap.GetData(node).duration;
// store settled nodes in search space bucket
search_space_with_buckets[node].emplace_back(column_idx, target_weight, target_duration);
if (stallAtNode<false>(facade, node, target_weight, query_heap))
{
return;
}
relaxOutgoingEdges<false>(facade, node, target_weight, target_duration, query_heap);
}
}
std::vector<EdgeWeight>
manyToManySearch(SearchEngineData &engine_working_data,
const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
const std::vector<PhantomNode> &phantom_nodes,
const std::vector<std::size_t> &source_indices,
const std::vector<std::size_t> &target_indices)
{ {
const auto number_of_sources = const auto number_of_sources =
source_indices.empty() ? phantom_nodes.size() : source_indices.size(); source_indices.empty() ? phantom_nodes.size() : source_indices.size();
@ -24,7 +193,7 @@ operator()(const FacadeT &facade,
engine_working_data.InitializeOrClearManyToManyThreadLocalStorage(facade.GetNumberOfNodes()); engine_working_data.InitializeOrClearManyToManyThreadLocalStorage(facade.GetNumberOfNodes());
QueryHeap &query_heap = *(engine_working_data.many_to_many_heap); auto &query_heap = *(engine_working_data.many_to_many_heap);
SearchSpaceWithBuckets search_space_with_buckets; SearchSpaceWithBuckets search_space_with_buckets;
@ -49,7 +218,7 @@ operator()(const FacadeT &facade,
// explore search space // explore search space
while (!query_heap.Empty()) while (!query_heap.Empty())
{ {
BackwardRoutingStep(facade, column_idx, query_heap, search_space_with_buckets); backwardRoutingStep(facade, column_idx, query_heap, search_space_with_buckets);
} }
++column_idx; ++column_idx;
}; };
@ -122,84 +291,6 @@ operator()(const FacadeT &facade,
return durations_table; return durations_table;
} }
void ManyToManyRouting<algorithm::CH>::ForwardRoutingStep(
const FacadeT &facade,
const unsigned row_idx,
const unsigned number_of_targets,
QueryHeap &query_heap,
const SearchSpaceWithBuckets &search_space_with_buckets,
std::vector<EdgeWeight> &weights_table,
std::vector<EdgeWeight> &durations_table) const
{
const NodeID node = query_heap.DeleteMin();
const EdgeWeight source_weight = query_heap.GetKey(node);
const EdgeWeight source_duration = query_heap.GetData(node).duration;
// check if each encountered node has an entry
const auto bucket_iterator = search_space_with_buckets.find(node);
// iterate bucket if there exists one
if (bucket_iterator != search_space_with_buckets.end())
{
const std::vector<NodeBucket> &bucket_list = bucket_iterator->second;
for (const NodeBucket &current_bucket : bucket_list)
{
// get target id from bucket entry
const unsigned column_idx = current_bucket.target_id;
const EdgeWeight target_weight = current_bucket.weight;
const EdgeWeight target_duration = current_bucket.duration;
auto &current_weight = weights_table[row_idx * number_of_targets + column_idx];
auto &current_duration = durations_table[row_idx * number_of_targets + column_idx];
// check if new weight is better
const EdgeWeight new_weight = source_weight + target_weight;
if (new_weight < 0)
{
const EdgeWeight loop_weight = super::GetLoopWeight<false>(facade, node);
const EdgeWeight new_weight_with_loop = new_weight + loop_weight;
if (loop_weight != INVALID_EDGE_WEIGHT && new_weight_with_loop >= 0)
{
current_weight = std::min(current_weight, new_weight_with_loop);
current_duration = std::min(current_duration,
source_duration + target_duration +
super::GetLoopWeight<true>(facade, node));
}
}
else if (new_weight < current_weight)
{
current_weight = new_weight;
current_duration = source_duration + target_duration;
}
}
}
if (StallAtNode<true>(facade, node, source_weight, query_heap))
{
return;
}
RelaxOutgoingEdges<true>(facade, node, source_weight, source_duration, query_heap);
}
void ManyToManyRouting<algorithm::CH>::BackwardRoutingStep(
const FacadeT &facade,
const unsigned column_idx,
QueryHeap &query_heap,
SearchSpaceWithBuckets &search_space_with_buckets) const
{
const NodeID node = query_heap.DeleteMin();
const EdgeWeight target_weight = query_heap.GetKey(node);
const EdgeWeight target_duration = query_heap.GetData(node).duration;
// store settled nodes in search space bucket
search_space_with_buckets[node].emplace_back(column_idx, target_weight, target_duration);
if (StallAtNode<false>(facade, node, target_weight, query_heap))
{
return;
}
RelaxOutgoingEdges<false>(facade, node, target_weight, target_duration, query_heap);
}
} // namespace routing_algorithms } // namespace routing_algorithms
} // namespace engine } // namespace engine
} // namespace osrm } // namespace osrm

View File

@ -1,4 +1,20 @@
#include "engine/routing_algorithms/map_matching.hpp" #include "engine/routing_algorithms/map_matching.hpp"
#include "engine/routing_algorithms/routing_base.hpp"
#include "engine/map_matching/hidden_markov_model.hpp"
#include "engine/map_matching/matching_confidence.hpp"
#include "engine/map_matching/sub_matching.hpp"
#include "util/coordinate_calculation.hpp"
#include "util/for_each_pair.hpp"
#include <algorithm>
#include <cstddef>
#include <deque>
#include <iomanip>
#include <memory>
#include <numeric>
#include <utility>
namespace osrm namespace osrm
{ {
@ -7,8 +23,15 @@ namespace engine
namespace routing_algorithms namespace routing_algorithms
{ {
unsigned namespace
MapMatching<algorithm::CH>::GetMedianSampleTime(const std::vector<unsigned> &timestamps) const {
using HMM = map_matching::HiddenMarkovModel<CandidateLists>;
constexpr static const unsigned MAX_BROKEN_STATES = 10;
constexpr static const double MATCHING_BETA = 10;
constexpr static const double MAX_DISTANCE_DELTA = 2000.;
unsigned getMedianSampleTime(const std::vector<unsigned> &timestamps)
{ {
BOOST_ASSERT(timestamps.size() > 1); BOOST_ASSERT(timestamps.size() > 1);
@ -22,14 +45,20 @@ MapMatching<algorithm::CH>::GetMedianSampleTime(const std::vector<unsigned> &tim
std::nth_element(first_elem, median, sample_times.end()); std::nth_element(first_elem, median, sample_times.end());
return *median; return *median;
} }
}
SubMatchingList MapMatching<algorithm::CH>:: SubMatchingList
operator()(const FacadeT &facade, mapMatching(SearchEngineData &engine_working_data,
const CandidateLists &candidates_list, const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
const std::vector<util::Coordinate> &trace_coordinates, const CandidateLists &candidates_list,
const std::vector<unsigned> &trace_timestamps, const std::vector<util::Coordinate> &trace_coordinates,
const std::vector<boost::optional<double>> &trace_gps_precision) const const std::vector<unsigned> &trace_timestamps,
const std::vector<boost::optional<double>> &trace_gps_precision)
{ {
map_matching::MatchingConfidence confidence;
map_matching::EmissionLogProbability default_emission_log_probability(DEFAULT_GPS_PRECISION);
map_matching::TransitionLogProbability transition_log_probability(MATCHING_BETA);
SubMatchingList sub_matchings; SubMatchingList sub_matchings;
BOOST_ASSERT(candidates_list.size() == trace_coordinates.size()); BOOST_ASSERT(candidates_list.size() == trace_coordinates.size());
@ -40,7 +69,7 @@ operator()(const FacadeT &facade,
const auto median_sample_time = [&] { const auto median_sample_time = [&] {
if (use_timestamps) if (use_timestamps)
{ {
return std::max(1u, GetMedianSampleTime(trace_timestamps)); return std::max(1u, getMedianSampleTime(trace_timestamps));
} }
else else
{ {
@ -68,7 +97,7 @@ operator()(const FacadeT &facade,
std::transform(candidates_list[t].begin(), std::transform(candidates_list[t].begin(),
candidates_list[t].end(), candidates_list[t].end(),
emission_log_probabilities[t].begin(), emission_log_probabilities[t].begin(),
[this](const PhantomNodeWithDistance &candidate) { [&](const PhantomNodeWithDistance &candidate) {
return default_emission_log_probability(candidate.distance); return default_emission_log_probability(candidate.distance);
}); });
} }
@ -95,7 +124,7 @@ operator()(const FacadeT &facade,
std::transform(candidates_list[t].begin(), std::transform(candidates_list[t].begin(),
candidates_list[t].end(), candidates_list[t].end(),
emission_log_probabilities[t].begin(), emission_log_probabilities[t].begin(),
[this](const PhantomNodeWithDistance &candidate) { [&](const PhantomNodeWithDistance &candidate) {
return default_emission_log_probability(candidate.distance); return default_emission_log_probability(candidate.distance);
}); });
} }
@ -113,10 +142,10 @@ operator()(const FacadeT &facade,
engine_working_data.InitializeOrClearFirstThreadLocalStorage(facade.GetNumberOfNodes()); engine_working_data.InitializeOrClearFirstThreadLocalStorage(facade.GetNumberOfNodes());
engine_working_data.InitializeOrClearSecondThreadLocalStorage(facade.GetNumberOfNodes()); engine_working_data.InitializeOrClearSecondThreadLocalStorage(facade.GetNumberOfNodes());
QueryHeap &forward_heap = *(engine_working_data.forward_heap_1); auto &forward_heap = *(engine_working_data.forward_heap_1);
QueryHeap &reverse_heap = *(engine_working_data.reverse_heap_1); auto &reverse_heap = *(engine_working_data.reverse_heap_1);
QueryHeap &forward_core_heap = *(engine_working_data.forward_heap_2); auto &forward_core_heap = *(engine_working_data.forward_heap_2);
QueryHeap &reverse_core_heap = *(engine_working_data.reverse_heap_2); auto &reverse_core_heap = *(engine_working_data.reverse_heap_2);
std::size_t breakage_begin = map_matching::INVALID_STATE; std::size_t breakage_begin = map_matching::INVALID_STATE;
std::vector<std::size_t> split_points; std::vector<std::size_t> split_points;
@ -187,7 +216,7 @@ operator()(const FacadeT &facade,
{ {
forward_core_heap.Clear(); forward_core_heap.Clear();
reverse_core_heap.Clear(); reverse_core_heap.Clear();
network_distance = super::GetNetworkDistanceWithCore( network_distance = getNetworkDistanceWithCore(
facade, facade,
forward_heap, forward_heap,
reverse_heap, reverse_heap,
@ -199,12 +228,12 @@ operator()(const FacadeT &facade,
} }
else else
{ {
network_distance = super::GetNetworkDistance( network_distance =
facade, getNetworkDistance(facade,
forward_heap, forward_heap,
reverse_heap, reverse_heap,
prev_unbroken_timestamps_list[s].phantom_node, prev_unbroken_timestamps_list[s].phantom_node,
current_timestamps_list[s_prime].phantom_node); current_timestamps_list[s_prime].phantom_node);
} }
// get distance diff between loc1/2 and locs/s_prime // get distance diff between loc1/2 and locs/s_prime

View File

@ -7,16 +7,16 @@ namespace engine
namespace routing_algorithms namespace routing_algorithms
{ {
void BasicRouting<algorithm::CH>::RoutingStep(const FacadeT &facade, void routingStep(const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
SearchEngineData::QueryHeap &forward_heap, SearchEngineData::QueryHeap &forward_heap,
SearchEngineData::QueryHeap &reverse_heap, SearchEngineData::QueryHeap &reverse_heap,
NodeID &middle_node_id, NodeID &middle_node_id,
EdgeWeight &upper_bound, EdgeWeight &upper_bound,
EdgeWeight min_edge_offset, EdgeWeight min_edge_offset,
const bool forward_direction, const bool forward_direction,
const bool stalling, const bool stalling,
const bool force_loop_forward, const bool force_loop_forward,
const bool force_loop_reverse) const const bool force_loop_reverse)
{ {
const NodeID node = forward_heap.DeleteMin(); const NodeID node = forward_heap.DeleteMin();
const EdgeWeight weight = forward_heap.GetKey(node); const EdgeWeight weight = forward_heap.GetKey(node);
@ -36,7 +36,7 @@ void BasicRouting<algorithm::CH>::RoutingStep(const FacadeT &facade,
// check whether there is a loop present at the node // check whether there is a loop present at the node
for (const auto edge : facade.GetAdjacentEdgeRange(node)) for (const auto edge : facade.GetAdjacentEdgeRange(node))
{ {
const EdgeData &data = facade.GetEdgeData(edge); const auto &data = facade.GetEdgeData(edge);
bool forward_directionFlag = (forward_direction ? data.forward : data.backward); bool forward_directionFlag = (forward_direction ? data.forward : data.backward);
if (forward_directionFlag) if (forward_directionFlag)
{ {
@ -78,7 +78,7 @@ void BasicRouting<algorithm::CH>::RoutingStep(const FacadeT &facade,
{ {
for (const auto edge : facade.GetAdjacentEdgeRange(node)) for (const auto edge : facade.GetAdjacentEdgeRange(node))
{ {
const EdgeData &data = facade.GetEdgeData(edge); const auto &data = facade.GetEdgeData(edge);
const bool reverse_flag = ((!forward_direction) ? data.forward : data.backward); const bool reverse_flag = ((!forward_direction) ? data.forward : data.backward);
if (reverse_flag) if (reverse_flag)
{ {
@ -100,7 +100,7 @@ void BasicRouting<algorithm::CH>::RoutingStep(const FacadeT &facade,
for (const auto edge : facade.GetAdjacentEdgeRange(node)) for (const auto edge : facade.GetAdjacentEdgeRange(node))
{ {
const EdgeData &data = facade.GetEdgeData(edge); const auto &data = facade.GetEdgeData(edge);
bool forward_directionFlag = (forward_direction ? data.forward : data.backward); bool forward_directionFlag = (forward_direction ? data.forward : data.backward);
if (forward_directionFlag) if (forward_directionFlag)
{ {
@ -133,38 +133,35 @@ void BasicRouting<algorithm::CH>::RoutingStep(const FacadeT &facade,
* @param to the node the CH edge finishes at * @param to the node the CH edge finishes at
* @param unpacked_path the sequence of original NodeIDs that make up the expanded CH edge * @param unpacked_path the sequence of original NodeIDs that make up the expanded CH edge
*/ */
void BasicRouting<algorithm::CH>::UnpackEdge(const FacadeT &facade, void unpackEdge(const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
const NodeID from, const NodeID from,
const NodeID to, const NodeID to,
std::vector<NodeID> &unpacked_path) const std::vector<NodeID> &unpacked_path)
{ {
std::array<NodeID, 2> path{{from, to}}; std::array<NodeID, 2> path{{from, to}};
UnpackCHPath( unpackPath(facade,
facade, path.begin(),
path.begin(), path.end(),
path.end(), [&unpacked_path](const std::pair<NodeID, NodeID> &edge, const auto & /* data */) {
[&unpacked_path](const std::pair<NodeID, NodeID> &edge, const EdgeData & /* data */) { unpacked_path.emplace_back(edge.first);
unpacked_path.emplace_back(edge.first); });
});
unpacked_path.emplace_back(to); unpacked_path.emplace_back(to);
} }
void BasicRouting<algorithm::CH>::RetrievePackedPathFromHeap( void retrievePackedPathFromHeap(const SearchEngineData::QueryHeap &forward_heap,
const SearchEngineData::QueryHeap &forward_heap, const SearchEngineData::QueryHeap &reverse_heap,
const SearchEngineData::QueryHeap &reverse_heap, const NodeID middle_node_id,
const NodeID middle_node_id, std::vector<NodeID> &packed_path)
std::vector<NodeID> &packed_path) const
{ {
RetrievePackedPathFromSingleHeap(forward_heap, middle_node_id, packed_path); retrievePackedPathFromSingleHeap(forward_heap, middle_node_id, packed_path);
std::reverse(packed_path.begin(), packed_path.end()); std::reverse(packed_path.begin(), packed_path.end());
packed_path.emplace_back(middle_node_id); packed_path.emplace_back(middle_node_id);
RetrievePackedPathFromSingleHeap(reverse_heap, middle_node_id, packed_path); retrievePackedPathFromSingleHeap(reverse_heap, middle_node_id, packed_path);
} }
void BasicRouting<algorithm::CH>::RetrievePackedPathFromSingleHeap( void retrievePackedPathFromSingleHeap(const SearchEngineData::QueryHeap &search_heap,
const SearchEngineData::QueryHeap &search_heap, const NodeID middle_node_id,
const NodeID middle_node_id, std::vector<NodeID> &packed_path)
std::vector<NodeID> &packed_path) const
{ {
NodeID current_node_id = middle_node_id; NodeID current_node_id = middle_node_id;
// all initial nodes will have itself as parent, or a node not in the heap // all initial nodes will have itself as parent, or a node not in the heap
@ -191,14 +188,14 @@ void BasicRouting<algorithm::CH>::RetrievePackedPathFromSingleHeap(
// && source_phantom.GetForwardWeightPlusOffset() > target_phantom.GetForwardWeightPlusOffset()) // && source_phantom.GetForwardWeightPlusOffset() > target_phantom.GetForwardWeightPlusOffset())
// requires // requires
// a force loop, if the heaps have been initialized with positive offsets. // a force loop, if the heaps have been initialized with positive offsets.
void BasicRouting<algorithm::CH>::Search(const FacadeT &facade, void search(const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
SearchEngineData::QueryHeap &forward_heap, SearchEngineData::QueryHeap &forward_heap,
SearchEngineData::QueryHeap &reverse_heap, SearchEngineData::QueryHeap &reverse_heap,
EdgeWeight &weight, EdgeWeight &weight,
std::vector<NodeID> &packed_leg, std::vector<NodeID> &packed_leg,
const bool force_loop_forward, const bool force_loop_forward,
const bool force_loop_reverse, const bool force_loop_reverse,
const EdgeWeight weight_upper_bound) const const EdgeWeight weight_upper_bound)
{ {
NodeID middle = SPECIAL_NODEID; NodeID middle = SPECIAL_NODEID;
weight = weight_upper_bound; weight = weight_upper_bound;
@ -215,7 +212,7 @@ void BasicRouting<algorithm::CH>::Search(const FacadeT &facade,
{ {
if (!forward_heap.Empty()) if (!forward_heap.Empty())
{ {
RoutingStep(facade, routingStep(facade,
forward_heap, forward_heap,
reverse_heap, reverse_heap,
middle, middle,
@ -228,7 +225,7 @@ void BasicRouting<algorithm::CH>::Search(const FacadeT &facade,
} }
if (!reverse_heap.Empty()) if (!reverse_heap.Empty())
{ {
RoutingStep(facade, routingStep(facade,
reverse_heap, reverse_heap,
forward_heap, forward_heap,
middle, middle,
@ -260,7 +257,7 @@ void BasicRouting<algorithm::CH>::Search(const FacadeT &facade,
} }
else else
{ {
RetrievePackedPathFromHeap(forward_heap, reverse_heap, middle, packed_leg); retrievePackedPathFromHeap(forward_heap, reverse_heap, middle, packed_leg);
} }
} }
@ -273,16 +270,16 @@ void BasicRouting<algorithm::CH>::Search(const FacadeT &facade,
// && source_phantom.GetForwardWeightPlusOffset() > target_phantom.GetForwardWeightPlusOffset()) // && source_phantom.GetForwardWeightPlusOffset() > target_phantom.GetForwardWeightPlusOffset())
// requires // requires
// a force loop, if the heaps have been initialized with positive offsets. // a force loop, if the heaps have been initialized with positive offsets.
void BasicRouting<algorithm::CH>::SearchWithCore(const FacadeT &facade, void searchWithCore(const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
SearchEngineData::QueryHeap &forward_heap, SearchEngineData::QueryHeap &forward_heap,
SearchEngineData::QueryHeap &reverse_heap, SearchEngineData::QueryHeap &reverse_heap,
SearchEngineData::QueryHeap &forward_core_heap, SearchEngineData::QueryHeap &forward_core_heap,
SearchEngineData::QueryHeap &reverse_core_heap, SearchEngineData::QueryHeap &reverse_core_heap,
EdgeWeight &weight, EdgeWeight &weight,
std::vector<NodeID> &packed_leg, std::vector<NodeID> &packed_leg,
const bool force_loop_forward, const bool force_loop_forward,
const bool force_loop_reverse, const bool force_loop_reverse,
EdgeWeight weight_upper_bound) const EdgeWeight weight_upper_bound)
{ {
NodeID middle = SPECIAL_NODEID; NodeID middle = SPECIAL_NODEID;
weight = weight_upper_bound; weight = weight_upper_bound;
@ -310,7 +307,7 @@ void BasicRouting<algorithm::CH>::SearchWithCore(const FacadeT &facade,
} }
else else
{ {
RoutingStep(facade, routingStep(facade,
forward_heap, forward_heap,
reverse_heap, reverse_heap,
middle, middle,
@ -332,7 +329,7 @@ void BasicRouting<algorithm::CH>::SearchWithCore(const FacadeT &facade,
} }
else else
{ {
RoutingStep(facade, routingStep(facade,
reverse_heap, reverse_heap,
forward_heap, forward_heap,
middle, middle,
@ -385,7 +382,7 @@ void BasicRouting<algorithm::CH>::SearchWithCore(const FacadeT &facade,
while (0 < forward_core_heap.Size() && 0 < reverse_core_heap.Size() && while (0 < forward_core_heap.Size() && 0 < reverse_core_heap.Size() &&
weight > (forward_core_heap.MinKey() + reverse_core_heap.MinKey())) weight > (forward_core_heap.MinKey() + reverse_core_heap.MinKey()))
{ {
RoutingStep(facade, routingStep(facade,
forward_core_heap, forward_core_heap,
reverse_core_heap, reverse_core_heap,
middle, middle,
@ -396,7 +393,7 @@ void BasicRouting<algorithm::CH>::SearchWithCore(const FacadeT &facade,
force_loop_forward, force_loop_forward,
force_loop_reverse); force_loop_reverse);
RoutingStep(facade, routingStep(facade,
reverse_core_heap, reverse_core_heap,
forward_core_heap, forward_core_heap,
middle, middle,
@ -432,13 +429,13 @@ void BasicRouting<algorithm::CH>::SearchWithCore(const FacadeT &facade,
else else
{ {
std::vector<NodeID> packed_core_leg; std::vector<NodeID> packed_core_leg;
RetrievePackedPathFromHeap( retrievePackedPathFromHeap(
forward_core_heap, reverse_core_heap, middle, packed_core_leg); forward_core_heap, reverse_core_heap, middle, packed_core_leg);
BOOST_ASSERT(packed_core_leg.size() > 0); BOOST_ASSERT(packed_core_leg.size() > 0);
RetrievePackedPathFromSingleHeap(forward_heap, packed_core_leg.front(), packed_leg); retrievePackedPathFromSingleHeap(forward_heap, packed_core_leg.front(), packed_leg);
std::reverse(packed_leg.begin(), packed_leg.end()); std::reverse(packed_leg.begin(), packed_leg.end());
packed_leg.insert(packed_leg.end(), packed_core_leg.begin(), packed_core_leg.end()); packed_leg.insert(packed_leg.end(), packed_core_leg.begin(), packed_core_leg.end());
RetrievePackedPathFromSingleHeap(reverse_heap, packed_core_leg.back(), packed_leg); retrievePackedPathFromSingleHeap(reverse_heap, packed_core_leg.back(), packed_leg);
} }
} }
else else
@ -453,13 +450,12 @@ void BasicRouting<algorithm::CH>::SearchWithCore(const FacadeT &facade,
} }
else else
{ {
RetrievePackedPathFromHeap(forward_heap, reverse_heap, middle, packed_leg); retrievePackedPathFromHeap(forward_heap, reverse_heap, middle, packed_leg);
} }
} }
} }
bool BasicRouting<algorithm::CH>::NeedsLoopForward(const PhantomNode &source_phantom, bool needsLoopForward(const PhantomNode &source_phantom, const PhantomNode &target_phantom)
const PhantomNode &target_phantom) const
{ {
return source_phantom.forward_segment_id.enabled && target_phantom.forward_segment_id.enabled && return source_phantom.forward_segment_id.enabled && target_phantom.forward_segment_id.enabled &&
source_phantom.forward_segment_id.id == target_phantom.forward_segment_id.id && source_phantom.forward_segment_id.id == target_phantom.forward_segment_id.id &&
@ -467,8 +463,7 @@ bool BasicRouting<algorithm::CH>::NeedsLoopForward(const PhantomNode &source_pha
target_phantom.GetForwardWeightPlusOffset(); target_phantom.GetForwardWeightPlusOffset();
} }
bool BasicRouting<algorithm::CH>::NeedsLoopBackwards(const PhantomNode &source_phantom, bool needsLoopBackwards(const PhantomNode &source_phantom, const PhantomNode &target_phantom)
const PhantomNode &target_phantom) const
{ {
return source_phantom.reverse_segment_id.enabled && target_phantom.reverse_segment_id.enabled && return source_phantom.reverse_segment_id.enabled && target_phantom.reverse_segment_id.enabled &&
source_phantom.reverse_segment_id.id == target_phantom.reverse_segment_id.id && source_phantom.reverse_segment_id.id == target_phantom.reverse_segment_id.id &&
@ -476,16 +471,16 @@ bool BasicRouting<algorithm::CH>::NeedsLoopBackwards(const PhantomNode &source_p
target_phantom.GetReverseWeightPlusOffset(); target_phantom.GetReverseWeightPlusOffset();
} }
double BasicRouting<algorithm::CH>::GetPathDistance(const FacadeT &facade, double getPathDistance(const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
const std::vector<NodeID> &packed_path, const std::vector<NodeID> &packed_path,
const PhantomNode &source_phantom, const PhantomNode &source_phantom,
const PhantomNode &target_phantom) const const PhantomNode &target_phantom)
{ {
std::vector<PathData> unpacked_path; std::vector<PathData> unpacked_path;
PhantomNodes nodes; PhantomNodes nodes;
nodes.source_phantom = source_phantom; nodes.source_phantom = source_phantom;
nodes.target_phantom = target_phantom; nodes.target_phantom = target_phantom;
UnpackPath(facade, packed_path.begin(), packed_path.end(), nodes, unpacked_path); unpackPath(facade, packed_path.begin(), packed_path.end(), nodes, unpacked_path);
using util::coordinate_calculation::detail::DEGREE_TO_RAD; using util::coordinate_calculation::detail::DEGREE_TO_RAD;
using util::coordinate_calculation::detail::EARTH_RADIUS; using util::coordinate_calculation::detail::EARTH_RADIUS;
@ -535,15 +530,15 @@ double BasicRouting<algorithm::CH>::GetPathDistance(const FacadeT &facade,
// Requires the heaps for be empty // Requires the heaps for be empty
// If heaps should be adjusted to be initialized outside of this function, // If heaps should be adjusted to be initialized outside of this function,
// the addition of force_loop parameters might be required // the addition of force_loop parameters might be required
double BasicRouting<algorithm::CH>::GetNetworkDistanceWithCore( double getNetworkDistanceWithCore(
const FacadeT &facade, const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
SearchEngineData::QueryHeap &forward_heap, SearchEngineData::QueryHeap &forward_heap,
SearchEngineData::QueryHeap &reverse_heap, SearchEngineData::QueryHeap &reverse_heap,
SearchEngineData::QueryHeap &forward_core_heap, SearchEngineData::QueryHeap &forward_core_heap,
SearchEngineData::QueryHeap &reverse_core_heap, SearchEngineData::QueryHeap &reverse_core_heap,
const PhantomNode &source_phantom, const PhantomNode &source_phantom,
const PhantomNode &target_phantom, const PhantomNode &target_phantom,
EdgeWeight weight_upper_bound) const EdgeWeight weight_upper_bound)
{ {
BOOST_ASSERT(forward_heap.Empty()); BOOST_ASSERT(forward_heap.Empty());
BOOST_ASSERT(reverse_heap.Empty()); BOOST_ASSERT(reverse_heap.Empty());
@ -579,7 +574,7 @@ double BasicRouting<algorithm::CH>::GetNetworkDistanceWithCore(
EdgeWeight weight = INVALID_EDGE_WEIGHT; EdgeWeight weight = INVALID_EDGE_WEIGHT;
std::vector<NodeID> packed_path; std::vector<NodeID> packed_path;
SearchWithCore(facade, searchWithCore(facade,
forward_heap, forward_heap,
reverse_heap, reverse_heap,
forward_core_heap, forward_core_heap,
@ -593,7 +588,7 @@ double BasicRouting<algorithm::CH>::GetNetworkDistanceWithCore(
double distance = std::numeric_limits<double>::max(); double distance = std::numeric_limits<double>::max();
if (weight != INVALID_EDGE_WEIGHT) if (weight != INVALID_EDGE_WEIGHT)
{ {
return GetPathDistance(facade, packed_path, source_phantom, target_phantom); return getPathDistance(facade, packed_path, source_phantom, target_phantom);
} }
return distance; return distance;
} }
@ -601,12 +596,13 @@ double BasicRouting<algorithm::CH>::GetNetworkDistanceWithCore(
// Requires the heaps for be empty // Requires the heaps for be empty
// If heaps should be adjusted to be initialized outside of this function, // If heaps should be adjusted to be initialized outside of this function,
// the addition of force_loop parameters might be required // the addition of force_loop parameters might be required
double BasicRouting<algorithm::CH>::GetNetworkDistance(const FacadeT &facade, double
SearchEngineData::QueryHeap &forward_heap, getNetworkDistance(const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
SearchEngineData::QueryHeap &reverse_heap, SearchEngineData::QueryHeap &forward_heap,
const PhantomNode &source_phantom, SearchEngineData::QueryHeap &reverse_heap,
const PhantomNode &target_phantom, const PhantomNode &source_phantom,
EdgeWeight weight_upper_bound) const const PhantomNode &target_phantom,
EdgeWeight weight_upper_bound)
{ {
BOOST_ASSERT(forward_heap.Empty()); BOOST_ASSERT(forward_heap.Empty());
BOOST_ASSERT(reverse_heap.Empty()); BOOST_ASSERT(reverse_heap.Empty());
@ -642,7 +638,7 @@ double BasicRouting<algorithm::CH>::GetNetworkDistance(const FacadeT &facade,
EdgeWeight weight = INVALID_EDGE_WEIGHT; EdgeWeight weight = INVALID_EDGE_WEIGHT;
std::vector<NodeID> packed_path; std::vector<NodeID> packed_path;
Search(facade, search(facade,
forward_heap, forward_heap,
reverse_heap, reverse_heap,
weight, weight,
@ -656,7 +652,7 @@ double BasicRouting<algorithm::CH>::GetNetworkDistance(const FacadeT &facade,
return std::numeric_limits<double>::max(); return std::numeric_limits<double>::max();
} }
return GetPathDistance(facade, packed_path, source_phantom, target_phantom); return getPathDistance(facade, packed_path, source_phantom, target_phantom);
} }
} // namespace routing_algorithms } // namespace routing_algorithms

View File

@ -1,4 +1,9 @@
#include "engine/routing_algorithms/shortest_path.hpp" #include "engine/routing_algorithms/shortest_path.hpp"
#include "engine/routing_algorithms/routing_base.hpp"
#include <boost/assert.hpp>
#include <boost/optional.hpp>
#include <memory>
namespace osrm namespace osrm
{ {
@ -7,23 +12,26 @@ namespace engine
namespace routing_algorithms namespace routing_algorithms
{ {
const static constexpr bool DO_NOT_FORCE_LOOP = false;
using QueryHeap = SearchEngineData::QueryHeap;
// allows a uturn at the target_phantom // allows a uturn at the target_phantom
// searches source forward/reverse -> target forward/reverse // searches source forward/reverse -> target forward/reverse
void ShortestPathRouting<algorithm::CH>::SearchWithUTurn(const FacadeT &facade, void searchWithUTurn(const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
QueryHeap &forward_heap, QueryHeap &forward_heap,
QueryHeap &reverse_heap, QueryHeap &reverse_heap,
QueryHeap &forward_core_heap, QueryHeap &forward_core_heap,
QueryHeap &reverse_core_heap, QueryHeap &reverse_core_heap,
const bool search_from_forward_node, const bool search_from_forward_node,
const bool search_from_reverse_node, const bool search_from_reverse_node,
const bool search_to_forward_node, const bool search_to_forward_node,
const bool search_to_reverse_node, const bool search_to_reverse_node,
const PhantomNode &source_phantom, const PhantomNode &source_phantom,
const PhantomNode &target_phantom, const PhantomNode &target_phantom,
const int total_weight_to_forward, const int total_weight_to_forward,
const int total_weight_to_reverse, const int total_weight_to_reverse,
int &new_total_weight, int &new_total_weight,
std::vector<NodeID> &leg_packed_path) const std::vector<NodeID> &leg_packed_path)
{ {
forward_heap.Clear(); forward_heap.Clear();
reverse_heap.Clear(); reverse_heap.Clear();
@ -59,35 +67,34 @@ void ShortestPathRouting<algorithm::CH>::SearchWithUTurn(const FacadeT &facade,
auto is_oneway_source = !(search_from_forward_node && search_from_reverse_node); auto is_oneway_source = !(search_from_forward_node && search_from_reverse_node);
auto is_oneway_target = !(search_to_forward_node && search_to_reverse_node); auto is_oneway_target = !(search_to_forward_node && search_to_reverse_node);
// we only enable loops here if we can't search from forward to backward node // we only enable loops here if we can't search from forward to backward node
auto needs_loop_forwad = auto needs_loop_forwad = is_oneway_source && needsLoopForward(source_phantom, target_phantom);
is_oneway_source && super::NeedsLoopForward(source_phantom, target_phantom);
auto needs_loop_backwards = auto needs_loop_backwards =
is_oneway_target && super::NeedsLoopBackwards(source_phantom, target_phantom); is_oneway_target && needsLoopBackwards(source_phantom, target_phantom);
if (facade.GetCoreSize() > 0) if (facade.GetCoreSize() > 0)
{ {
forward_core_heap.Clear(); forward_core_heap.Clear();
reverse_core_heap.Clear(); reverse_core_heap.Clear();
BOOST_ASSERT(forward_core_heap.Size() == 0); BOOST_ASSERT(forward_core_heap.Size() == 0);
BOOST_ASSERT(reverse_core_heap.Size() == 0); BOOST_ASSERT(reverse_core_heap.Size() == 0);
super::SearchWithCore(facade, searchWithCore(facade,
forward_heap, forward_heap,
reverse_heap, reverse_heap,
forward_core_heap, forward_core_heap,
reverse_core_heap, reverse_core_heap,
new_total_weight, new_total_weight,
leg_packed_path, leg_packed_path,
needs_loop_forwad, needs_loop_forwad,
needs_loop_backwards); needs_loop_backwards);
} }
else else
{ {
super::Search(facade, search(facade,
forward_heap, forward_heap,
reverse_heap, reverse_heap,
new_total_weight, new_total_weight,
leg_packed_path, leg_packed_path,
needs_loop_forwad, needs_loop_forwad,
needs_loop_backwards); needs_loop_backwards);
} }
// if no route is found between two parts of the via-route, the entire route becomes // if no route is found between two parts of the via-route, the entire route becomes
// invalid. Adding to invalid edge weight sadly doesn't return an invalid edge weight. Here // invalid. Adding to invalid edge weight sadly doesn't return an invalid edge weight. Here
@ -99,23 +106,23 @@ void ShortestPathRouting<algorithm::CH>::SearchWithUTurn(const FacadeT &facade,
// searches shortest path between: // searches shortest path between:
// source forward/reverse -> target forward // source forward/reverse -> target forward
// source forward/reverse -> target reverse // source forward/reverse -> target reverse
void ShortestPathRouting<algorithm::CH>::Search(const FacadeT &facade, void Search(const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
QueryHeap &forward_heap, QueryHeap &forward_heap,
QueryHeap &reverse_heap, QueryHeap &reverse_heap,
QueryHeap &forward_core_heap, QueryHeap &forward_core_heap,
QueryHeap &reverse_core_heap, QueryHeap &reverse_core_heap,
const bool search_from_forward_node, const bool search_from_forward_node,
const bool search_from_reverse_node, const bool search_from_reverse_node,
const bool search_to_forward_node, const bool search_to_forward_node,
const bool search_to_reverse_node, const bool search_to_reverse_node,
const PhantomNode &source_phantom, const PhantomNode &source_phantom,
const PhantomNode &target_phantom, const PhantomNode &target_phantom,
const int total_weight_to_forward, const int total_weight_to_forward,
const int total_weight_to_reverse, const int total_weight_to_reverse,
int &new_total_weight_to_forward, int &new_total_weight_to_forward,
int &new_total_weight_to_reverse, int &new_total_weight_to_reverse,
std::vector<NodeID> &leg_packed_path_forward, std::vector<NodeID> &leg_packed_path_forward,
std::vector<NodeID> &leg_packed_path_reverse) const std::vector<NodeID> &leg_packed_path_reverse)
{ {
if (search_to_forward_node) if (search_to_forward_node)
{ {
@ -148,25 +155,25 @@ void ShortestPathRouting<algorithm::CH>::Search(const FacadeT &facade,
reverse_core_heap.Clear(); reverse_core_heap.Clear();
BOOST_ASSERT(forward_core_heap.Size() == 0); BOOST_ASSERT(forward_core_heap.Size() == 0);
BOOST_ASSERT(reverse_core_heap.Size() == 0); BOOST_ASSERT(reverse_core_heap.Size() == 0);
super::SearchWithCore(facade, searchWithCore(facade,
forward_heap, forward_heap,
reverse_heap, reverse_heap,
forward_core_heap, forward_core_heap,
reverse_core_heap, reverse_core_heap,
new_total_weight_to_forward, new_total_weight_to_forward,
leg_packed_path_forward, leg_packed_path_forward,
super::NeedsLoopForward(source_phantom, target_phantom), needsLoopForward(source_phantom, target_phantom),
DO_NOT_FORCE_LOOP); DO_NOT_FORCE_LOOP);
} }
else else
{ {
super::Search(facade, search(facade,
forward_heap, forward_heap,
reverse_heap, reverse_heap,
new_total_weight_to_forward, new_total_weight_to_forward,
leg_packed_path_forward, leg_packed_path_forward,
super::NeedsLoopForward(source_phantom, target_phantom), needsLoopForward(source_phantom, target_phantom),
DO_NOT_FORCE_LOOP); DO_NOT_FORCE_LOOP);
} }
} }
@ -199,36 +206,35 @@ void ShortestPathRouting<algorithm::CH>::Search(const FacadeT &facade,
reverse_core_heap.Clear(); reverse_core_heap.Clear();
BOOST_ASSERT(forward_core_heap.Size() == 0); BOOST_ASSERT(forward_core_heap.Size() == 0);
BOOST_ASSERT(reverse_core_heap.Size() == 0); BOOST_ASSERT(reverse_core_heap.Size() == 0);
super::SearchWithCore(facade, searchWithCore(facade,
forward_heap, forward_heap,
reverse_heap, reverse_heap,
forward_core_heap, forward_core_heap,
reverse_core_heap, reverse_core_heap,
new_total_weight_to_reverse, new_total_weight_to_reverse,
leg_packed_path_reverse, leg_packed_path_reverse,
DO_NOT_FORCE_LOOP, DO_NOT_FORCE_LOOP,
super::NeedsLoopBackwards(source_phantom, target_phantom)); needsLoopBackwards(source_phantom, target_phantom));
} }
else else
{ {
super::Search(facade, search(facade,
forward_heap, forward_heap,
reverse_heap, reverse_heap,
new_total_weight_to_reverse, new_total_weight_to_reverse,
leg_packed_path_reverse, leg_packed_path_reverse,
DO_NOT_FORCE_LOOP, DO_NOT_FORCE_LOOP,
super::NeedsLoopBackwards(source_phantom, target_phantom)); needsLoopBackwards(source_phantom, target_phantom));
} }
} }
} }
void ShortestPathRouting<algorithm::CH>::UnpackLegs( void unpackLegs(const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
const FacadeT &facade, const std::vector<PhantomNodes> &phantom_nodes_vector,
const std::vector<PhantomNodes> &phantom_nodes_vector, const std::vector<NodeID> &total_packed_path,
const std::vector<NodeID> &total_packed_path, const std::vector<std::size_t> &packed_leg_begin,
const std::vector<std::size_t> &packed_leg_begin, const int shortest_path_length,
const int shortest_path_length, InternalRouteResult &raw_route_data)
InternalRouteResult &raw_route_data) const
{ {
raw_route_data.unpacked_path_segments.resize(packed_leg_begin.size() - 1); raw_route_data.unpacked_path_segments.resize(packed_leg_begin.size() - 1);
@ -239,11 +245,11 @@ void ShortestPathRouting<algorithm::CH>::UnpackLegs(
auto leg_begin = total_packed_path.begin() + packed_leg_begin[current_leg]; auto leg_begin = total_packed_path.begin() + packed_leg_begin[current_leg];
auto leg_end = total_packed_path.begin() + packed_leg_begin[current_leg + 1]; auto leg_end = total_packed_path.begin() + packed_leg_begin[current_leg + 1];
const auto &unpack_phantom_node_pair = phantom_nodes_vector[current_leg]; const auto &unpack_phantom_node_pair = phantom_nodes_vector[current_leg];
super::UnpackPath(facade, unpackPath(facade,
leg_begin, leg_begin,
leg_end, leg_end,
unpack_phantom_node_pair, unpack_phantom_node_pair,
raw_route_data.unpacked_path_segments[current_leg]); raw_route_data.unpacked_path_segments[current_leg]);
raw_route_data.source_traversed_in_reverse.push_back( raw_route_data.source_traversed_in_reverse.push_back(
(*leg_begin != phantom_nodes_vector[current_leg].source_phantom.forward_segment_id.id)); (*leg_begin != phantom_nodes_vector[current_leg].source_phantom.forward_segment_id.id));
@ -253,12 +259,13 @@ void ShortestPathRouting<algorithm::CH>::UnpackLegs(
} }
} }
void ShortestPathRouting<algorithm::CH>:: InternalRouteResult
operator()(const FacadeT &facade, shortestPathSearch(SearchEngineData &engine_working_data,
const std::vector<PhantomNodes> &phantom_nodes_vector, const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
const boost::optional<bool> continue_straight_at_waypoint, const std::vector<PhantomNodes> &phantom_nodes_vector,
InternalRouteResult &raw_route_data) const const boost::optional<bool> continue_straight_at_waypoint)
{ {
InternalRouteResult raw_route_data;
const bool allow_uturn_at_waypoint = const bool allow_uturn_at_waypoint =
!(continue_straight_at_waypoint ? *continue_straight_at_waypoint !(continue_straight_at_waypoint ? *continue_straight_at_waypoint
: facade.GetContinueStraightDefault()); : facade.GetContinueStraightDefault());
@ -312,7 +319,7 @@ operator()(const FacadeT &facade,
{ {
if (allow_uturn_at_waypoint) if (allow_uturn_at_waypoint)
{ {
SearchWithUTurn(facade, searchWithUTurn(facade,
forward_heap, forward_heap,
reverse_heap, reverse_heap,
forward_core_heap, forward_core_heap,
@ -370,7 +377,7 @@ operator()(const FacadeT &facade,
{ {
raw_route_data.shortest_path_length = INVALID_EDGE_WEIGHT; raw_route_data.shortest_path_length = INVALID_EDGE_WEIGHT;
raw_route_data.alternative_path_length = INVALID_EDGE_WEIGHT; raw_route_data.alternative_path_length = INVALID_EDGE_WEIGHT;
return; return raw_route_data;
} }
// we need to figure out how the new legs connect to the previous ones // we need to figure out how the new legs connect to the previous ones
@ -473,7 +480,7 @@ operator()(const FacadeT &facade,
packed_leg_to_reverse_begin.push_back(total_packed_path_to_reverse.size()); packed_leg_to_reverse_begin.push_back(total_packed_path_to_reverse.size());
BOOST_ASSERT(packed_leg_to_reverse_begin.size() == phantom_nodes_vector.size() + 1); BOOST_ASSERT(packed_leg_to_reverse_begin.size() == phantom_nodes_vector.size() + 1);
UnpackLegs(facade, unpackLegs(facade,
phantom_nodes_vector, phantom_nodes_vector,
total_packed_path_to_reverse, total_packed_path_to_reverse,
packed_leg_to_reverse_begin, packed_leg_to_reverse_begin,
@ -486,13 +493,15 @@ operator()(const FacadeT &facade,
packed_leg_to_forward_begin.push_back(total_packed_path_to_forward.size()); packed_leg_to_forward_begin.push_back(total_packed_path_to_forward.size());
BOOST_ASSERT(packed_leg_to_forward_begin.size() == phantom_nodes_vector.size() + 1); BOOST_ASSERT(packed_leg_to_forward_begin.size() == phantom_nodes_vector.size() + 1);
UnpackLegs(facade, unpackLegs(facade,
phantom_nodes_vector, phantom_nodes_vector,
total_packed_path_to_forward, total_packed_path_to_forward,
packed_leg_to_forward_begin, packed_leg_to_forward_begin,
total_weight_to_forward, total_weight_to_forward,
raw_route_data); raw_route_data);
} }
return raw_route_data;
} }
} // namespace routing_algorithms } // namespace routing_algorithms

View File

@ -7,10 +7,10 @@ namespace engine
namespace routing_algorithms namespace routing_algorithms
{ {
std::vector<TurnData> TileTurns<algorithm::CH>:: std::vector<TurnData>
operator()(const FacadeT &facade, getTileTurns(const datafacade::ContiguousInternalMemoryDataFacade<algorithm::CH> &facade,
const std::vector<RTreeLeaf> &edges, const std::vector<RTreeLeaf> &edges,
const std::vector<std::size_t> &sorted_edge_indexes) const const std::vector<std::size_t> &sorted_edge_indexes)
{ {
std::vector<TurnData> all_turn_data; std::vector<TurnData> all_turn_data;