First compiling version of map_match plugin

This commit is contained in:
Patrick Niklaus 2016-02-21 04:27:26 +01:00
parent e05a45b080
commit 35b098e656
19 changed files with 587 additions and 457 deletions

View File

@ -26,7 +26,7 @@ class BaseAPI
{
}
virtual util::json::Array
util::json::Array
MakeWaypoints(const std::vector<PhantomNodes> &segment_end_coordinates) const
{
BOOST_ASSERT(parameters.coordinates.size() > 0);
@ -47,7 +47,7 @@ class BaseAPI
}
protected:
virtual util::json::Object MakeWaypoint(const util::FixedPointCoordinate input_coordinate,
util::json::Object MakeWaypoint(const util::FixedPointCoordinate input_coordinate,
const PhantomNode &phantom) const
{
return json::makeWaypoint(phantom.location, facade.get_name_for_id(phantom.name_id),

View File

@ -0,0 +1,116 @@
#ifndef ENGINE_API_MATCH_HPP
#define ENGINE_API_MATCH_HPP
#include "engine/api/route_api.hpp"
#include "engine/api/match_parameters.hpp"
#include "engine/datafacade/datafacade_base.hpp"
#include "engine/internal_route_result.hpp"
#include "engine/map_matching/sub_matching.hpp"
#include "util/integer_range.hpp"
namespace osrm
{
namespace engine
{
namespace api
{
class MatchAPI final : public RouteAPI
{
public:
MatchAPI(const datafacade::BaseDataFacade &facade_, const MatchParameters &parameters_)
: RouteAPI(facade_, parameters_), parameters(parameters_)
{
}
void MakeResponse(const std::vector<map_matching::SubMatching> &sub_matchings,
const std::vector<InternalRouteResult> &sub_routes,
util::json::Object &response) const
{
auto number_of_routes = sub_matchings.size();
util::json::Array routes;
routes.values.reserve(number_of_routes);
BOOST_ASSERT(sub_matchings.size() == sub_routes.size());
for (auto index : util::irange<std::size_t>(0UL, sub_matchings.size()))
{
auto route = MakeRoute(sub_routes[index].segment_end_coordinates,
sub_routes[index].unpacked_path_segments,
sub_routes[index].source_traversed_in_reverse,
sub_routes[index].target_traversed_in_reverse);
route.values["confidence"] = sub_matchings[index].confidence;
}
response.values["tracepoints"] = MakeTracepoints(sub_matchings);
response.values["routes"] = std::move(routes);
response.values["code"] = "ok";
}
protected:
// FIXME this logic is a little backwards. We should change the output format of the
// map_matching
// routing algorithm to be easier to consume here.
util::json::Array
MakeTracepoints(const std::vector<map_matching::SubMatching> &sub_matchings) const
{
util::json::Array waypoints;
waypoints.values.reserve(parameters.coordinates.size());
struct MatchingIndex
{
MatchingIndex() = default;
MatchingIndex(unsigned sub_matching_index_, unsigned point_index_)
: sub_matching_index(sub_matching_index_), point_index(point_index_)
{
}
unsigned sub_matching_index = std::numeric_limits<unsigned>::max();
unsigned point_index = std::numeric_limits<unsigned>::max();
bool NotMatched()
{
return sub_matching_index == std::numeric_limits<unsigned>::max() &&
point_index == std::numeric_limits<unsigned>::max();
}
};
std::vector<MatchingIndex> trace_idx_to_matching_idx(parameters.coordinates.size());
for (auto sub_matching_index :
util::irange(0u, static_cast<unsigned>(sub_matchings.size())))
{
for (auto point_index : util::irange(
0u, static_cast<unsigned>(sub_matchings[sub_matching_index].indices.size())))
{
trace_idx_to_matching_idx[sub_matchings[sub_matching_index].indices[point_index]] =
MatchingIndex{sub_matching_index, point_index};
}
}
for (auto trace_index : util::irange(0UL, parameters.coordinates.size()))
{
auto matching_index = trace_idx_to_matching_idx[trace_index];
if (matching_index.NotMatched())
{
waypoints.values.push_back(util::json::Null());
continue;
}
const auto &phantom =
sub_matchings[matching_index.sub_matching_index].nodes[matching_index.point_index];
auto waypoint = BaseAPI::MakeWaypoint(parameters.coordinates[trace_index], phantom);
waypoint.values["matchings_index"] = matching_index.sub_matching_index;
waypoint.values["waypoint_index"] = matching_index.point_index;
waypoints.values.push_back(std::move(waypoint));
}
return waypoints;
}
const MatchParameters &parameters;
};
} // ns api
} // ns engine
} // ns osrm
#endif

View File

@ -14,10 +14,10 @@ namespace api
struct MatchParameters : public RouteParameters
{
std::vector<boost::optional<unsigned>> timestamps;
std::vector<unsigned> timestamps;
bool IsValid() const
{
return timestamps.empty() || timestamps.size() == coordinates.size();
return RouteParameters::IsValid() && (timestamps.empty() || timestamps.size() == coordinates.size());
}
};

View File

@ -24,7 +24,7 @@ namespace engine
namespace api
{
class RouteAPI final : public BaseAPI
class RouteAPI : public BaseAPI
{
public:
RouteAPI(const datafacade::BaseDataFacade &facade_, const RouteParameters &parameters_)
@ -32,8 +32,7 @@ class RouteAPI final : public BaseAPI
{
}
virtual void MakeResponse(const InternalRouteResult &raw_route,
util::json::Object &response) const
void MakeResponse(const InternalRouteResult &raw_route, util::json::Object &response) const
{
auto number_of_routes = raw_route.has_alternative() ? 2UL : 1UL;
util::json::Array routes;
@ -67,11 +66,10 @@ class RouteAPI final : public BaseAPI
return json::makeGeoJSONLineString(begin, end);
}
virtual util::json::Object
MakeRoute(const std::vector<PhantomNodes> &segment_end_coordinates,
const std::vector<std::vector<PathData>> &unpacked_path_segments,
const std::vector<bool> &source_traversed_in_reverse,
const std::vector<bool> &target_traversed_in_reverse) const
util::json::Object MakeRoute(const std::vector<PhantomNodes> &segment_end_coordinates,
const std::vector<std::vector<PathData>> &unpacked_path_segments,
const std::vector<bool> &source_traversed_in_reverse,
const std::vector<bool> &target_traversed_in_reverse) const
{
std::vector<guidance::RouteLeg> legs;
std::vector<guidance::LegGeometry> leg_geometries;

View File

@ -86,8 +86,12 @@ class BaseDataFacade
virtual std::vector<PhantomNodeWithDistance>
NearestPhantomNodesInRange(const util::FixedPointCoordinate input_coordinate,
const float max_distance,
const int bearing = 0,
const int bearing_range = 180) = 0;
const int bearing,
const int bearing_range) = 0;
virtual std::vector<PhantomNodeWithDistance>
NearestPhantomNodesInRange(const util::FixedPointCoordinate input_coordinate,
const float max_distance) = 0;
virtual std::vector<PhantomNodeWithDistance>
NearestPhantomNodes(const util::FixedPointCoordinate input_coordinate,

View File

@ -354,11 +354,24 @@ class InternalDataFacade final : public BaseDataFacade
return m_geospatial_query->Search(bbox);
}
std::vector<PhantomNodeWithDistance>
NearestPhantomNodesInRange(const util::FixedPointCoordinate input_coordinate,
const float max_distance) override final
{
if (!m_static_rtree.get())
{
LoadRTree();
BOOST_ASSERT(m_geospatial_query.get());
}
return m_geospatial_query->NearestPhantomNodesInRange(input_coordinate, max_distance);
}
std::vector<PhantomNodeWithDistance>
NearestPhantomNodesInRange(const util::FixedPointCoordinate input_coordinate,
const float max_distance,
const int bearing = 0,
const int bearing_range = 180) override final
const int bearing,
const int bearing_range) override final
{
if (!m_static_rtree.get())
{

View File

@ -421,11 +421,24 @@ class SharedDataFacade final : public BaseDataFacade
return m_geospatial_query->Search(bbox);
}
std::vector<PhantomNodeWithDistance>
NearestPhantomNodesInRange(const util::FixedPointCoordinate input_coordinate,
const float max_distance) override final
{
if (!m_static_rtree.get() || CURRENT_TIMESTAMP != m_static_rtree->first)
{
LoadRTree();
BOOST_ASSERT(m_geospatial_query.get());
}
return m_geospatial_query->NearestPhantomNodesInRange(input_coordinate, max_distance);
}
std::vector<PhantomNodeWithDistance>
NearestPhantomNodesInRange(const util::FixedPointCoordinate input_coordinate,
const float max_distance,
const int bearing = 0,
const int bearing_range = 180) override final
const int bearing,
const int bearing_range) override final
{
if (!m_static_rtree.get() || CURRENT_TIMESTAMP != m_static_rtree->first)
{

View File

@ -74,7 +74,7 @@ class Engine final
std::unique_ptr<plugins::TablePlugin> table_plugin;
std::unique_ptr<plugins::NearestPlugin> nearest_plugin;
// std::unique_ptr<plugins::TripPlugin> trip_plugin;
// std::unique_ptr<plugins::MatchPlugin> match_plugin;
std::unique_ptr<plugins::MatchPlugin> match_plugin;
std::unique_ptr<datafacade::BaseDataFacade> query_data_facade;
};

View File

@ -38,13 +38,30 @@ template <typename RTreeT, typename DataFacadeT> class GeospatialQuery
return rtree.SearchInBox(bbox);
}
// Returns nearest PhantomNodes in the given bearing range within max_distance.
// Does not filter by small/big component!
std::vector<PhantomNodeWithDistance>
NearestPhantomNodesInRange(const util::FixedPointCoordinate input_coordinate,
const double max_distance)
{
auto results =
rtree.Nearest(input_coordinate,
[] (const EdgeData &) { return std::make_pair(true, true); },
[max_distance](const std::size_t, const double min_dist)
{
return min_dist > max_distance;
});
return MakePhantomNodes(input_coordinate, results);
}
// Returns nearest PhantomNodes in the given bearing range within max_distance.
// Does not filter by small/big component!
std::vector<PhantomNodeWithDistance>
NearestPhantomNodesInRange(const util::FixedPointCoordinate input_coordinate,
const double max_distance,
const int bearing = 0,
const int bearing_range = 180)
const int bearing,
const int bearing_range)
{
auto results =
rtree.Nearest(input_coordinate,

View File

@ -52,23 +52,21 @@ template <class CandidateLists> struct HiddenMarkovModel
{
std::vector<std::vector<double>> viterbi;
std::vector<std::vector<std::pair<unsigned, unsigned>>> parents;
std::vector<std::vector<float>> path_lengths;
std::vector<std::vector<float>> path_distances;
std::vector<std::vector<bool>> pruned;
std::vector<std::vector<bool>> suspicious;
std::vector<bool> breakage;
const CandidateLists &candidates_list;
const EmissionLogProbability &emission_log_probability;
const std::vector<std::vector<double>> &emission_log_probabilities;
HiddenMarkovModel(const CandidateLists &candidates_list,
const EmissionLogProbability &emission_log_probability)
const std::vector<std::vector<double>> &emission_log_probabilities)
: breakage(candidates_list.size()), candidates_list(candidates_list),
emission_log_probability(emission_log_probability)
emission_log_probabilities(emission_log_probabilities)
{
viterbi.resize(candidates_list.size());
parents.resize(candidates_list.size());
path_lengths.resize(candidates_list.size());
suspicious.resize(candidates_list.size());
path_distances.resize(candidates_list.size());
pruned.resize(candidates_list.size());
breakage.resize(candidates_list.size());
for (const auto i : util::irange<std::size_t>(0u, candidates_list.size()))
@ -79,8 +77,7 @@ template <class CandidateLists> struct HiddenMarkovModel
{
viterbi[i].resize(num_candidates);
parents[i].resize(num_candidates);
path_lengths[i].resize(num_candidates);
suspicious[i].resize(num_candidates);
path_distances[i].resize(num_candidates);
pruned[i].resize(num_candidates);
}
}
@ -90,15 +87,14 @@ template <class CandidateLists> struct HiddenMarkovModel
void clear(std::size_t initial_timestamp)
{
BOOST_ASSERT(viterbi.size() == parents.size() && parents.size() == path_lengths.size() &&
path_lengths.size() == pruned.size() && pruned.size() == breakage.size());
BOOST_ASSERT(viterbi.size() == parents.size() && parents.size() == path_distances.size() &&
path_distances.size() == pruned.size() && pruned.size() == breakage.size());
for (const auto t : util::irange(initial_timestamp, viterbi.size()))
{
std::fill(viterbi[t].begin(), viterbi[t].end(), IMPOSSIBLE_LOG_PROB);
std::fill(parents[t].begin(), parents[t].end(), std::make_pair(0u, 0u));
std::fill(path_lengths[t].begin(), path_lengths[t].end(), 0);
std::fill(suspicious[t].begin(), suspicious[t].end(), true);
std::fill(path_distances[t].begin(), path_distances[t].end(), 0);
std::fill(pruned[t].begin(), pruned[t].end(), true);
}
std::fill(breakage.begin() + initial_timestamp, breakage.end(), true);
@ -113,11 +109,9 @@ template <class CandidateLists> struct HiddenMarkovModel
for (const auto s : util::irange<std::size_t>(0u, viterbi[initial_timestamp].size()))
{
viterbi[initial_timestamp][s] =
emission_log_probability(candidates_list[initial_timestamp][s].distance);
viterbi[initial_timestamp][s] = emission_log_probabilities[initial_timestamp][s];
parents[initial_timestamp][s] = std::make_pair(initial_timestamp, s);
pruned[initial_timestamp][s] = viterbi[initial_timestamp][s] < MINIMAL_LOG_PROB;
suspicious[initial_timestamp][s] = false;
breakage[initial_timestamp] =
breakage[initial_timestamp] && pruned[initial_timestamp][s];

View File

@ -0,0 +1,58 @@
#ifndef ENGINE_MAP_MATCHING_CONFIDENCE_HPP
#define ENGINE_MAP_MATCHING_CONFIDENCE_HPP
#include "engine/map_matching/bayes_classifier.hpp"
#include <cmath>
namespace osrm
{
namespace engine
{
namespace map_matching
{
struct MatchingConfidence
{
private:
using ClassifierT = BayesClassifier<LaplaceDistribution, LaplaceDistribution, double>;
using TraceClassification = ClassifierT::ClassificationT;
public:
MatchingConfidence()
: // the values were derived from fitting a laplace distribution
// to the values of manually classified traces
classifier(map_matching::LaplaceDistribution(0.005986, 0.016646),
map_matching::LaplaceDistribution(0.054385, 0.458432),
0.696774) // valid apriori probability
{
}
double operator()(const float trace_length, const float matched_length) const
{
const double distance_feature = -std::log(trace_length) + std::log(matched_length);
// matched to the same point
if (!std::isfinite(distance_feature))
{
return 0;
}
const auto label_with_confidence = classifier.classify(distance_feature);
if (label_with_confidence.first == ClassifierT::ClassLabel::POSITIVE)
{
return label_with_confidence.second;
}
BOOST_ASSERT(label_with_confidence.first == ClassifierT::ClassLabel::NEGATIVE);
return 1 - label_with_confidence.second;
}
private:
ClassifierT classifier;
};
}
}
}
#endif

View File

@ -0,0 +1,26 @@
#ifndef MAP_MATCHING_SUB_MATCHING_HPP
#define MAP_MATCHING_SUB_MATCHING_HPP
#include "engine/phantom_node.hpp"
#include <vector>
namespace osrm
{
namespace engine
{
namespace map_matching
{
struct SubMatching
{
std::vector<PhantomNode> nodes;
std::vector<unsigned> indices;
double confidence;
};
}
}
}
#endif

View File

@ -6,6 +6,7 @@
#include "engine/map_matching/bayes_classifier.hpp"
#include "engine/routing_algorithms/map_matching.hpp"
#include "engine/routing_algorithms/shortest_path.hpp"
#include "util/json_util.hpp"
#include <vector>
@ -17,33 +18,28 @@ namespace engine
namespace plugins
{
class MatchingPlugin : public BasePlugin
class MatchPlugin : public BasePlugin
{
using SubMatching = routing_algorithms::SubMatching;
public:
using SubMatching = map_matching::SubMatching;
using SubMatchingList = routing_algorithms::SubMatchingList;
using CandidateLists = routing_algorithms::CandidateLists;
using ClassifierT = map_matching::BayesClassifier<map_matching::LaplaceDistribution,
map_matching::LaplaceDistribution,
double>;
using TraceClassification = ClassifierT::ClassificationT;
static const constexpr double DEFAULT_GPS_PRECISION = 5;
static const constexpr double RADIUS_MULTIPLIER = 3;
public:
MatchingPlugin(datafacade::BaseDataFacade &facade_, const int max_locations_map_matching)
: BasePlugin(facade_),
max_locations_map_matching(max_locations_map_matching),
// the values were derived from fitting a laplace distribution
// to the values of manually classified traces
classifier(map_matching::LaplaceDistribution(0.005986, 0.016646),
map_matching::LaplaceDistribution(0.054385, 0.458432),
0.696774) // valid apriori probability
MatchPlugin(datafacade::BaseDataFacade &facade_, const int max_locations_map_matching)
: BasePlugin(facade_), map_matching(&facade_, heaps, DEFAULT_GPS_PRECISION),
shortest_path(&facade_, heaps), max_locations_map_matching(max_locations_map_matching)
{
}
Status HandleRequest(const MatchParameters &parameters, util::json::Object &json_result);
Status HandleRequest(const api::MatchParameters &parameters, util::json::Object &json_result);
private:
SearchEngineData heaps;
routing_algorithms::MapMatching<datafacade::BaseDataFacade> map_matching;
routing_algorithms::ShortestPathRouting<datafacade::BaseDataFacade> shortest_path;
int max_locations_map_matching;
ClassifierT classifier;
};
}
}

View File

@ -7,6 +7,7 @@
#include "engine/status.hpp"
#include "util/coordinate.hpp"
#include "util/coordinate_calculation.hpp"
#include "util/json_container.hpp"
#include "util/integer_range.hpp"
@ -30,10 +31,10 @@ class BasePlugin
bool CheckAllCoordinates(const std::vector<util::FixedPointCoordinate> &coordinates)
{
return !std::any_of(std::begin(coordinates), std::end(coordinates),
[](const util::FixedPointCoordinate &coordinate)
{
return !coordinate.IsValid();
});
[](const util::FixedPointCoordinate &coordinate)
{
return !coordinate.IsValid();
});
}
Status Error(const std::string &code,
@ -109,6 +110,46 @@ class BasePlugin
return snapped_phantoms;
}
// Falls back to default_radius for non-set radii
std::vector<std::vector<PhantomNodeWithDistance>>
GetPhantomNodesInRange(const api::BaseParameters &parameters,
const std::vector<double> radiuses) const
{
std::vector<std::vector<PhantomNodeWithDistance>> phantom_nodes(
parameters.coordinates.size());
BOOST_ASSERT(parameters.radiuses.size() == parameters.coordinates.size());
const bool use_hints = !parameters.hints.empty();
const bool use_bearings = !parameters.bearings.empty();
for (const auto i : util::irange<std::size_t>(0, parameters.coordinates.size()))
{
if (use_hints && parameters.hints[i] &&
parameters.hints[i]->IsValid(parameters.coordinates[i], facade))
{
phantom_nodes[i].push_back(PhantomNodeWithDistance{
parameters.hints[i]->phantom,
util::coordinate_calculation::haversineDistance(
parameters.coordinates[i], parameters.hints[i]->phantom.location),
});
continue;
}
if (use_bearings && parameters.bearings[i])
{
phantom_nodes[i] = facade.NearestPhantomNodesInRange(
parameters.coordinates[i], radiuses[i], parameters.bearings[i]->bearing,
parameters.bearings[i]->range);
}
else
{
phantom_nodes[i] =
facade.NearestPhantomNodesInRange(parameters.coordinates[i], radiuses[i]);
}
}
return phantom_nodes;
}
std::vector<PhantomNodePair> GetPhantomNodes(const api::BaseParameters &parameters)
{
std::vector<PhantomNodePair> phantom_node_pairs(parameters.coordinates.size());
@ -138,11 +179,11 @@ class BasePlugin
parameters.bearings[i]->bearing, parameters.bearings[i]->range);
}
else
{
phantom_node_pairs[i] =
facade.NearestPhantomNodeWithAlternativeFromBigComponent(
parameters.coordinates[i], parameters.bearings[i]->bearing,
parameters.bearings[i]->range);
{
}
}
else
@ -154,10 +195,10 @@ class BasePlugin
parameters.coordinates[i], *parameters.radiuses[i]);
}
else
{
phantom_node_pairs[i] =
facade.NearestPhantomNodeWithAlternativeFromBigComponent(
parameters.coordinates[i]);
{
}
}

View File

@ -3,9 +3,13 @@
#include "engine/routing_algorithms/routing_base.hpp"
#include "util/coordinate_calculation.hpp"
#include "engine/map_matching/hidden_markov_model.hpp"
#include "engine/map_matching/sub_matching.hpp"
#include "engine/map_matching/matching_confidence.hpp"
#include "util/coordinate_calculation.hpp"
#include "util/json_logger.hpp"
#include "util/for_each_pair.hpp"
#include "util/matching_debug_info.hpp"
#include <cstddef>
@ -24,22 +28,14 @@ namespace engine
namespace routing_algorithms
{
struct SubMatching
{
std::vector<PhantomNode> nodes;
std::vector<unsigned> indices;
double length;
double confidence;
};
using CandidateList = std::vector<PhantomNodeWithDistance>;
using CandidateLists = std::vector<CandidateList>;
using HMM = map_matching::HiddenMarkovModel<CandidateLists>;
using SubMatchingList = std::vector<SubMatching>;
using SubMatchingList = std::vector<map_matching::SubMatching>;
constexpr static const unsigned MAX_BROKEN_STATES = 10;
constexpr static const double MAX_SPEED = 180 / 3.6; // 180km -> m/s
constexpr static const unsigned SUSPICIOUS_DISTANCE_DELTA = 100;
static const constexpr double MATCHING_BETA = 10;
constexpr static const double MAX_DISTANCE_DELTA = 2000.;
// implements a hidden markov model map matching algorithm
@ -49,6 +45,9 @@ class MapMatching final : public BasicRoutingInterface<DataFacadeT, MapMatching<
using super = BasicRoutingInterface<DataFacadeT, MapMatching<DataFacadeT>>;
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;
unsigned GetMedianSampleTime(const std::vector<unsigned> &timestamps) const
{
@ -66,18 +65,23 @@ class MapMatching final : public BasicRoutingInterface<DataFacadeT, MapMatching<
}
public:
MapMatching(DataFacadeT *facade, SearchEngineData &engine_working_data)
: super(facade), engine_working_data(engine_working_data)
MapMatching(DataFacadeT *facade,
SearchEngineData &engine_working_data,
const double default_gps_precision)
: super(facade), engine_working_data(engine_working_data),
default_emission_log_probability(default_gps_precision),
transition_log_probability(MATCHING_BETA)
{
}
void operator()(const CandidateLists &candidates_list,
const std::vector<util::FixedPointCoordinate> &trace_coordinates,
const std::vector<unsigned> &trace_timestamps,
const double matching_beta,
const double gps_precision,
SubMatchingList &sub_matchings) const
SubMatchingList
operator()(const CandidateLists &candidates_list,
const std::vector<util::FixedPointCoordinate> &trace_coordinates,
const std::vector<unsigned> &trace_timestamps,
const std::vector<boost::optional<double>> &trace_gps_precision) const
{
SubMatchingList sub_matchings;
BOOST_ASSERT(candidates_list.size() == trace_coordinates.size());
BOOST_ASSERT(candidates_list.size() > 1);
@ -107,16 +111,55 @@ class MapMatching final : public BasicRoutingInterface<DataFacadeT, MapMatching<
}
}();
// TODO replace default values with table lookup based on sampling frequency
map_matching::EmissionLogProbability emission_log_probability(gps_precision);
map_matching::TransitionLogProbability transition_log_probability(matching_beta);
std::vector<std::vector<double>> emission_log_probabilities(trace_coordinates.size());
if (trace_gps_precision.empty())
{
for (auto t = 0UL; t < candidates_list.size(); ++t)
{
emission_log_probabilities[t].resize(candidates_list.size());
std::transform(candidates_list[t].begin(), candidates_list[t].end(),
emission_log_probabilities[t].begin(),
[this](const PhantomNodeWithDistance &candidate)
{
return default_emission_log_probability(candidate.distance);
});
}
}
else
{
for (auto t = 0UL; t < candidates_list.size(); ++t)
{
emission_log_probabilities[t].resize(candidates_list.size());
if (trace_gps_precision[t])
{
map_matching::EmissionLogProbability emission_log_probability(
*trace_gps_precision[t]);
std::transform(
candidates_list[t].begin(), candidates_list[t].end(),
emission_log_probabilities[t].begin(),
[&emission_log_probability](const PhantomNodeWithDistance &candidate)
{
return emission_log_probability(candidate.distance);
});
}
else
{
std::transform(candidates_list[t].begin(), candidates_list[t].end(),
emission_log_probabilities[t].begin(),
[this](const PhantomNodeWithDistance &candidate)
{
return default_emission_log_probability(candidate.distance);
});
}
}
}
HMM model(candidates_list, emission_log_probability);
HMM model(candidates_list, emission_log_probabilities);
std::size_t initial_timestamp = model.initialize(0);
if (initial_timestamp == map_matching::INVALID_STATE)
{
return;
return sub_matchings;
}
util::MatchingDebugInfo matching_debug(util::json::Logger::get());
@ -193,9 +236,8 @@ class MapMatching final : public BasicRoutingInterface<DataFacadeT, MapMatching<
auto &current_viterbi = model.viterbi[t];
auto &current_pruned = model.pruned[t];
auto &current_suspicious = model.suspicious[t];
auto &current_parents = model.parents[t];
auto &current_lengths = model.path_lengths[t];
auto &current_lengths = model.path_distances[t];
const auto &current_timestamps_list = candidates_list[t];
const auto &current_coordinate = trace_coordinates[t];
@ -214,10 +256,7 @@ class MapMatching final : public BasicRoutingInterface<DataFacadeT, MapMatching<
for (const auto s_prime : util::irange<std::size_t>(0u, current_viterbi.size()))
{
// how likely is candidate s_prime at time t to be emitted?
// FIXME this can be pre-computed
const double emission_pr =
emission_log_probability(candidates_list[t][s_prime].distance);
const double emission_pr = emission_log_probabilities[t][s_prime];
double new_value = prev_viterbi[s] + emission_pr;
if (current_viterbi[s_prime] > new_value)
{
@ -268,7 +307,6 @@ class MapMatching final : public BasicRoutingInterface<DataFacadeT, MapMatching<
current_parents[s_prime] = std::make_pair(prev_unbroken_timestamp, s);
current_lengths[s_prime] = network_distance;
current_pruned[s_prime] = false;
current_suspicious[s_prime] = d_t > SUSPICIOUS_DISTANCE_DELTA;
model.breakage[t] = false;
}
}
@ -292,7 +330,7 @@ class MapMatching final : public BasicRoutingInterface<DataFacadeT, MapMatching<
}
}
matching_debug.set_viterbi(model.viterbi, model.pruned, model.suspicious);
matching_debug.set_viterbi(model.viterbi, model.pruned);
if (!prev_unbroken_timestamps.empty())
{
@ -302,7 +340,7 @@ class MapMatching final : public BasicRoutingInterface<DataFacadeT, MapMatching<
std::size_t sub_matching_begin = initial_timestamp;
for (const auto sub_matching_end : split_points)
{
SubMatching matching;
map_matching::SubMatching matching;
std::size_t parent_timestamp_index = sub_matching_end - 1;
while (parent_timestamp_index >= sub_matching_begin &&
@ -355,25 +393,39 @@ class MapMatching final : public BasicRoutingInterface<DataFacadeT, MapMatching<
continue;
}
matching.length = 0.0;
matching.nodes.resize(reconstructed_indices.size());
matching.indices.resize(reconstructed_indices.size());
for (const auto i : util::irange<std::size_t>(0u, reconstructed_indices.size()))
auto matching_distance = 0.0;
auto trace_distance = 0.0;
matching.nodes.reserve(reconstructed_indices.size());
matching.indices.reserve(reconstructed_indices.size());
for (const auto idx : reconstructed_indices)
{
const auto timestamp_index = reconstructed_indices[i].first;
const auto location_index = reconstructed_indices[i].second;
const auto timestamp_index = idx.first;
const auto location_index = idx.second;
matching.indices[i] = timestamp_index;
matching.nodes[i] = candidates_list[timestamp_index][location_index].phantom_node;
matching.length += model.path_lengths[timestamp_index][location_index];
matching.indices.push_back(timestamp_index);
matching.nodes.push_back(
candidates_list[timestamp_index][location_index].phantom_node);
matching_distance += model.path_distances[timestamp_index][location_index];
matching_debug.add_chosen(timestamp_index, location_index);
}
util::for_each_pair(
reconstructed_indices, [&trace_distance, &trace_coordinates](
const std::pair<std::size_t, std::size_t> &prev,
const std::pair<std::size_t, std::size_t> &curr)
{
trace_distance += util::coordinate_calculation::haversineDistance(
trace_coordinates[prev.first], trace_coordinates[curr.first]);
});
matching.confidence = confidence(trace_distance, matching_distance);
sub_matchings.push_back(matching);
sub_matching_begin = sub_matching_end;
}
matching_debug.add_breakage(model.breakage);
return sub_matchings;
}
};
}

View File

@ -13,7 +13,6 @@ namespace util
{
namespace json
{
// Make sure we don't have inf and NaN values
template <typename T> T clamp_float(T d)
{
@ -47,16 +46,17 @@ template <typename T> Array make_array(const std::vector<T> &vector)
return a;
}
// template specialization needed as clang does not play nice
template <> Array make_array(const std::vector<bool> &vector)
{
Array a;
for (const bool v : vector)
{
a.values.emplace_back(v);
}
return a;
}
//// template specialization needed as clang does not play nice
//// FIXME this now causes compile errors on g++ -_-
//template <> Array make_array(const std::vector<bool> &vector)
//{
// Array a;
// for (const bool v : vector)
// {
// a.values.emplace_back(v);
// }
// return a;
//}
// Easy acces to object hierachies
inline Value &get(Value &value) { return value; }

View File

@ -81,8 +81,7 @@ struct MatchingDebugInfo
}
void set_viterbi(const std::vector<std::vector<double>> &viterbi,
const std::vector<std::vector<bool>> &pruned,
const std::vector<std::vector<bool>> &suspicious)
const std::vector<std::vector<bool>> &pruned)
{
// json logger not enabled
if (!logger)
@ -98,8 +97,6 @@ struct MatchingDebugInfo
json::clamp_float(viterbi[t][s_prime]);
json::get(*object, "states", t, s_prime, "pruned") =
static_cast<unsigned>(pruned[t][s_prime]);
json::get(*object, "states", t, s_prime, "suspicious") =
static_cast<unsigned>(suspicious[t][s_prime]);
}
}
}

View File

@ -9,8 +9,8 @@
//#include "engine/plugins/timestamp.hpp"
//#include "engine/plugins/trip.hpp"
#include "engine/plugins/viaroute.hpp"
//#include "engine/plugins/match.hpp"
//#include "engine/plugins/tile.hpp"
#include "engine/plugins/match.hpp"
#include "engine/datafacade/datafacade_base.hpp"
#include "engine/datafacade/internal_datafacade.hpp"
@ -147,7 +147,7 @@ Engine::Engine(EngineConfig &config)
table_plugin = create<TablePlugin>(*query_data_facade, config.max_locations_distance_table);
nearest_plugin = create<NearestPlugin>(*query_data_facade);
// trip_plugin = ceate<TripPlugin>(*query_data_facade, config.max_locations_trip);
// match_plugin = create<MatchPlugin>(*query_data_facade, config.max_locations_map_matching);
match_plugin = create<MatchPlugin>(*query_data_facade, config.max_locations_map_matching);
}
// make sure we deallocate the unique ptr at a position where we know the size of the plugins
@ -178,8 +178,7 @@ Status Engine::Trip(const api::TripParameters &params, util::json::Object &resul
Status Engine::Match(const api::MatchParameters &params, util::json::Object &result)
{
// return RunQuery(lock, *query_data_facade, params, *match_plugin, result);
return Status::Error;
return RunQuery(lock, *query_data_facade, params, *match_plugin, result);
}
} // engine ns

View File

@ -1,14 +1,10 @@
/* TODO(daniel-j-h): fix for new server api, uncomment when this compiles
#include "engine/plugins/plugin_base.hpp"
#include "engine/plugins/match.hpp"
#include "engine/map_matching/bayes_classifier.hpp"
#include "engine/api/match_parameters.hpp"
#include "engine/api/match_api.hpp"
#include "engine/object_encoder.hpp"
#include "engine/search_engine.hpp"
#include "engine/guidance/textual_route_annotation.hpp"
#include "engine/guidance/segment_list.hpp"
#include "engine/api_response_generator.hpp"
#include "engine/routing_algorithms/map_matching.hpp"
#include "util/coordinate_calculation.hpp"
#include "util/integer_range.hpp"
#include "util/json_logger.hpp"
@ -29,359 +25,169 @@ namespace engine
namespace plugins
{
template <class DataFacadeT> class MapMatchingPlugin : public BasePlugin
// Filters PhantomNodes to obtain a set of viable candiates
void filterCandidates(const std::vector<util::FixedPointCoordinate> &coordinates,
MatchPlugin::CandidateLists &candidates_lists)
{
std::shared_ptr<SearchEngine<DataFacadeT>> search_engine_ptr;
using SubMatching = routing_algorithms::SubMatching;
using SubMatchingList = routing_algorithms::SubMatchingList;
using CandidateLists = routing_algorithms::CandidateLists;
using ClassifierT = map_matching::BayesClassifier<map_matching::LaplaceDistribution,
map_matching::LaplaceDistribution,
double>;
using TraceClassification = ClassifierT::ClassificationT;
public:
MapMatchingPlugin(DataFacadeT *facade, const int max_locations_map_matching)
: descriptor_string("match"), facade(facade),
max_locations_map_matching(max_locations_map_matching),
// the values where derived from fitting a laplace distribution
// to the values of manually classified traces
classifier(map_matching::LaplaceDistribution(0.005986, 0.016646),
map_matching::LaplaceDistribution(0.054385, 0.458432),
0.696774) // valid apriori probability
for (const auto current_coordinate : util::irange<std::size_t>(0, coordinates.size()))
{
search_engine_ptr = std::make_shared<SearchEngine<DataFacadeT>>(facade);
}
bool allow_uturn = false;
virtual ~MapMatchingPlugin() {}
const std::string GetDescriptor() const final override { return descriptor_string; }
TraceClassification
classify(const float trace_length, const float matched_length, const int removed_points) const
{
(void)removed_points; // unused
const double distance_feature = -std::log(trace_length) + std::log(matched_length);
// matched to the same point
if (!std::isfinite(distance_feature))
if (coordinates.size() - 1 > current_coordinate && 0 < current_coordinate)
{
return std::make_pair(ClassifierT::ClassLabel::NEGATIVE, 1.0);
double turn_angle = util::coordinate_calculation::computeAngle(
coordinates[current_coordinate - 1], coordinates[current_coordinate],
coordinates[current_coordinate + 1]);
// sharp turns indicate a possible uturn
if (turn_angle <= 90.0 || turn_angle >= 270.0)
{
allow_uturn = true;
}
}
const auto label_with_confidence = classifier.classify(distance_feature);
auto &candidates = candidates_lists[current_coordinate];
return label_with_confidence;
}
// sort by forward id, then by reverse id and then by distance
std::sort(
candidates.begin(), candidates.end(),
[](const PhantomNodeWithDistance &lhs, const PhantomNodeWithDistance &rhs)
{
return lhs.phantom_node.forward_node_id < rhs.phantom_node.forward_node_id ||
(lhs.phantom_node.forward_node_id == rhs.phantom_node.forward_node_id &&
(lhs.phantom_node.reverse_node_id < rhs.phantom_node.reverse_node_id ||
(lhs.phantom_node.reverse_node_id == rhs.phantom_node.reverse_node_id &&
lhs.distance < rhs.distance)));
});
CandidateLists getCandidates(
const std::vector<util::FixedPointCoordinate> &input_coords,
const std::vector<std::pair<const int, const boost::optional<int>>> &input_bearings,
const double gps_precision,
std::vector<double> &sub_trace_lengths)
{
CandidateLists candidates_lists;
auto new_end = std::unique(
candidates.begin(), candidates.end(),
[](const PhantomNodeWithDistance &lhs, const PhantomNodeWithDistance &rhs)
{
return lhs.phantom_node.forward_node_id == rhs.phantom_node.forward_node_id &&
lhs.phantom_node.reverse_node_id == rhs.phantom_node.reverse_node_id;
});
candidates.resize(new_end - candidates.begin());
// assuming gps_precision is the standard deviation of a normal distribution that
// models GPS noise (in this model), this should give us the correct search radius
// with > 99% confidence
double query_radius = 3 * gps_precision;
double last_distance =
util::coordinate_calculation::haversineDistance(input_coords[0], input_coords[1]);
sub_trace_lengths.resize(input_coords.size());
sub_trace_lengths[0] = 0;
for (const auto current_coordinate : util::irange<std::size_t>(0, input_coords.size()))
if (!allow_uturn)
{
bool allow_uturn = false;
if (0 < current_coordinate)
const auto compact_size = candidates.size();
for (const auto i : util::irange<std::size_t>(0, compact_size))
{
last_distance = util::coordinate_calculation::haversineDistance(
input_coords[current_coordinate - 1], input_coords[current_coordinate]);
sub_trace_lengths[current_coordinate] +=
sub_trace_lengths[current_coordinate - 1] + last_distance;
}
if (input_coords.size() - 1 > current_coordinate && 0 < current_coordinate)
{
double turn_angle = util::coordinate_calculation::computeAngle(
input_coords[current_coordinate - 1], input_coords[current_coordinate],
input_coords[current_coordinate + 1]);
// sharp turns indicate a possible uturn
if (turn_angle <= 90.0 || turn_angle >= 270.0)
// Split edge if it is bidirectional and append reverse direction to end of list
if (candidates[i].phantom_node.forward_node_id != SPECIAL_NODEID &&
candidates[i].phantom_node.reverse_node_id != SPECIAL_NODEID)
{
allow_uturn = true;
PhantomNode reverse_node(candidates[i].phantom_node);
reverse_node.forward_node_id = SPECIAL_NODEID;
candidates.push_back(
PhantomNodeWithDistance{reverse_node, candidates[i].distance});
candidates[i].phantom_node.reverse_node_id = SPECIAL_NODEID;
}
}
// Use bearing values if supplied, otherwise fallback to 0,180 defaults
auto bearing = input_bearings.size() > 0 ? input_bearings[current_coordinate].first : 0;
auto range = input_bearings.size() > 0
? (input_bearings[current_coordinate].second
? *input_bearings[current_coordinate].second
: 10)
: 180;
auto candidates = facade->NearestPhantomNodesInRange(input_coords[current_coordinate],
query_radius, bearing, range);
if (candidates.size() == 0)
{
break;
}
// sort by forward id, then by reverse id and then by distance
std::sort(
candidates.begin(), candidates.end(),
[](const PhantomNodeWithDistance &lhs, const PhantomNodeWithDistance &rhs)
{
return lhs.phantom_node.forward_node_id < rhs.phantom_node.forward_node_id ||
(lhs.phantom_node.forward_node_id == rhs.phantom_node.forward_node_id &&
(lhs.phantom_node.reverse_node_id < rhs.phantom_node.reverse_node_id ||
(lhs.phantom_node.reverse_node_id ==
rhs.phantom_node.reverse_node_id &&
lhs.distance < rhs.distance)));
});
auto new_end = std::unique(
candidates.begin(), candidates.end(),
[](const PhantomNodeWithDistance &lhs, const PhantomNodeWithDistance &rhs)
{
return lhs.phantom_node.forward_node_id == rhs.phantom_node.forward_node_id &&
lhs.phantom_node.reverse_node_id == rhs.phantom_node.reverse_node_id;
});
candidates.resize(new_end - candidates.begin());
if (!allow_uturn)
{
const auto compact_size = candidates.size();
for (const auto i : util::irange<std::size_t>(0, compact_size))
{
// Split edge if it is bidirectional and append reverse direction to end of list
if (candidates[i].phantom_node.forward_node_id != SPECIAL_NODEID &&
candidates[i].phantom_node.reverse_node_id != SPECIAL_NODEID)
{
PhantomNode reverse_node(candidates[i].phantom_node);
reverse_node.forward_node_id = SPECIAL_NODEID;
candidates.push_back(
PhantomNodeWithDistance{reverse_node, candidates[i].distance});
candidates[i].phantom_node.reverse_node_id = SPECIAL_NODEID;
}
}
}
// sort by distance to make pruning effective
std::sort(candidates.begin(), candidates.end(),
[](const PhantomNodeWithDistance &lhs, const PhantomNodeWithDistance &rhs)
{
return lhs.distance < rhs.distance;
});
candidates_lists.push_back(std::move(candidates));
}
return candidates_lists;
// sort by distance to make pruning effective
std::sort(candidates.begin(), candidates.end(),
[](const PhantomNodeWithDistance &lhs, const PhantomNodeWithDistance &rhs)
{
return lhs.distance < rhs.distance;
});
}
}
util::json::Object submatchingToJSON(const SubMatching &sub,
const RouteParameters &route_parameters,
const InternalRouteResult &raw_route)
Status MatchPlugin::HandleRequest(const api::MatchParameters &parameters,
util::json::Object &json_result)
{
BOOST_ASSERT(parameters.IsValid());
// enforce maximum number of locations for performance reasons
if (max_locations_map_matching > 0 &&
static_cast<int>(parameters.coordinates.size()) > max_locations_map_matching)
{
util::json::Object subtrace;
if (route_parameters.classify)
{
subtrace.values["confidence"] = sub.confidence;
}
auto response_generator = MakeApiResponseGenerator(facade);
subtrace.values["hint_data"] = response_generator.BuildHintData(raw_route);
if (route_parameters.geometry || route_parameters.print_instructions)
{
using SegmentList = guidance::SegmentList<DataFacadeT>;
// Passing false to extract_alternative extracts the route.
const constexpr bool EXTRACT_ROUTE = false;
// by passing false to segment_list, we skip the douglas peucker simplification
// and mark all segments as necessary within the generation process
const constexpr bool NO_ROUTE_SIMPLIFICATION = false;
SegmentList segment_list(raw_route, EXTRACT_ROUTE, route_parameters.zoom_level,
NO_ROUTE_SIMPLIFICATION, facade);
if (route_parameters.geometry)
{
subtrace.values["geometry"] =
response_generator.GetGeometry(route_parameters.compression, segment_list);
}
if (route_parameters.print_instructions)
{
subtrace.values["instructions"] =
guidance::AnnotateRoute<DataFacadeT>(segment_list.Get(), facade);
}
util::json::Object json_route_summary;
json_route_summary.values["total_distance"] = segment_list.GetDistance();
json_route_summary.values["total_time"] = segment_list.GetDuration();
subtrace.values["route_summary"] = json_route_summary;
}
subtrace.values["indices"] = util::json::make_array(sub.indices);
util::json::Array points;
for (const auto &node : sub.nodes)
{
points.values.emplace_back(
util::json::make_array(node.location.lat / COORDINATE_PRECISION,
node.location.lon / COORDINATE_PRECISION));
}
subtrace.values["matched_points"] = points;
util::json::Array names;
for (const auto &node : sub.nodes)
{
names.values.emplace_back(facade->get_name_for_id(node.name_id));
}
subtrace.values["matched_names"] = names;
return subtrace;
return Error("TooBig", "Too many trace coordinates", json_result);
}
Status HandleRequest(const RouteParameters &route_parameters,
util::json::Object &json_result) final override
if (!CheckAllCoordinates(parameters.coordinates))
{
// enforce maximum number of locations for performance reasons
if (max_locations_map_matching > 0 &&
static_cast<int>(route_parameters.coordinates.size()) > max_locations_map_matching)
{
json_result.values["status_message"] = "Too many coodindates";
return Status::Error;
}
// check number of parameters
if (!check_all_coordinates(route_parameters.coordinates))
{
json_result.values["status_message"] = "Invalid coordinates";
return Status::Error;
}
std::vector<double> sub_trace_lengths;
const auto &input_coords = route_parameters.coordinates;
const auto &input_timestamps = route_parameters.timestamps;
const auto &input_bearings = route_parameters.bearings;
if (input_timestamps.size() > 0 && input_coords.size() != input_timestamps.size())
{
json_result.values["status_message"] =
"Number of timestamps does not match number of coordinates";
return Status::Error;
}
if (input_bearings.size() > 0 && input_coords.size() != input_bearings.size())
{
json_result.values["status_message"] =
"Number of bearings does not match number of coordinates";
return Status::Error;
}
// at least two coordinates are needed for map matching
if (static_cast<int>(input_coords.size()) < 2)
{
json_result.values["status_message"] = "At least two coordinates needed";
return Status::Error;
}
const auto candidates_lists = getCandidates(
input_coords, input_bearings, route_parameters.gps_precision, sub_trace_lengths);
if (candidates_lists.size() != input_coords.size())
{
BOOST_ASSERT(candidates_lists.size() < input_coords.size());
json_result.values["status_message"] =
std::string("Could not find a matching segment for coordinate ") +
std::to_string(candidates_lists.size());
return Status::NoSegment;
}
// setup logging if enabled
if (util::json::Logger::get())
util::json::Logger::get()->initialize("matching");
// call the actual map matching
SubMatchingList sub_matchings;
search_engine_ptr->map_matching(candidates_lists, input_coords, input_timestamps,
route_parameters.matching_beta,
route_parameters.gps_precision, sub_matchings);
util::json::Array matchings;
for (auto &sub : sub_matchings)
{
// classify result
if (route_parameters.classify)
{
double trace_length =
sub_trace_lengths[sub.indices.back()] - sub_trace_lengths[sub.indices.front()];
TraceClassification classification =
classify(trace_length, sub.length,
(sub.indices.back() - sub.indices.front() + 1) - sub.nodes.size());
if (classification.first == ClassifierT::ClassLabel::POSITIVE)
{
sub.confidence = classification.second;
}
else
{
sub.confidence = 1 - classification.second;
}
}
BOOST_ASSERT(sub.nodes.size() > 1);
// FIXME we only run this to obtain the geometry
// The clean way would be to get this directly from the map matching plugin
InternalRouteResult raw_route;
PhantomNodes current_phantom_node_pair;
for (unsigned i = 0; i < sub.nodes.size() - 1; ++i)
{
current_phantom_node_pair.source_phantom = sub.nodes[i];
current_phantom_node_pair.target_phantom = sub.nodes[i + 1];
BOOST_ASSERT(current_phantom_node_pair.source_phantom.IsValid());
BOOST_ASSERT(current_phantom_node_pair.target_phantom.IsValid());
raw_route.segment_end_coordinates.emplace_back(current_phantom_node_pair);
}
search_engine_ptr->shortest_path(
raw_route.segment_end_coordinates,
std::vector<bool>(raw_route.segment_end_coordinates.size() + 1, true), raw_route);
BOOST_ASSERT(raw_route.shortest_path_length != INVALID_EDGE_WEIGHT);
matchings.values.emplace_back(submatchingToJSON(sub, route_parameters, raw_route));
}
if (util::json::Logger::get())
util::json::Logger::get()->render("matching", json_result);
json_result.values["matchings"] = matchings;
if (sub_matchings.empty())
{
json_result.values["status_message"] = "Cannot find matchings";
return Status::EmptyResult;
}
json_result.values["status_message"] = "Found matchings";
return Status::Ok;
return Error("InvalidValue", "Invalid coordinate value.", json_result);
}
private:
std::string descriptor_string;
DataFacadeT *facade;
int max_locations_map_matching;
ClassifierT classifier;
};
// assuming radius is the standard deviation of a normal distribution
// that models GPS noise (in this model), x3 should give us the correct
// search radius with > 99% confidence
std::vector<double> search_radiuses;
if (parameters.radiuses.empty())
{
search_radiuses.resize(parameters.coordinates.size(),
DEFAULT_GPS_PRECISION * RADIUS_MULTIPLIER);
}
else
{
search_radiuses.resize(parameters.coordinates.size());
std::transform(parameters.radiuses.begin(), parameters.radiuses.end(),
search_radiuses.begin(), [](const boost::optional<double> &maybe_radius)
{
if (maybe_radius)
{
return *maybe_radius * RADIUS_MULTIPLIER;
}
else
{
return DEFAULT_GPS_PRECISION * RADIUS_MULTIPLIER;
}
});
}
auto candidates_lists = GetPhantomNodesInRange(parameters, search_radiuses);
filterCandidates(parameters.coordinates, candidates_lists);
if (candidates_lists.size() != parameters.coordinates.size())
{
BOOST_ASSERT(candidates_lists.size() < parameters.coordinates.size());
return Error("NoSegment", std::string("Could not find a matching segment for coordinate ") +
std::to_string(candidates_lists.size()),
json_result);
}
// setup logging if enabled
if (util::json::Logger::get())
util::json::Logger::get()->initialize("matching");
// call the actual map matching
SubMatchingList sub_matchings = map_matching(candidates_lists, parameters.coordinates,
parameters.timestamps, parameters.radiuses);
std::vector<InternalRouteResult> sub_routes(sub_matchings.size());
for (auto index : util::irange(0UL, sub_matchings.size()))
{
BOOST_ASSERT(sub.nodes.size() > 1);
// FIXME we only run this to obtain the geometry
// The clean way would be to get this directly from the map matching plugin
PhantomNodes current_phantom_node_pair;
for (unsigned i = 0; i < sub_matchings[index].nodes.size() - 1; ++i)
{
current_phantom_node_pair.source_phantom = sub_matchings[index].nodes[i];
current_phantom_node_pair.target_phantom = sub_matchings[index].nodes[i + 1];
BOOST_ASSERT(current_phantom_node_pair.source_phantom.IsValid());
BOOST_ASSERT(current_phantom_node_pair.target_phantom.IsValid());
sub_routes[index].segment_end_coordinates.emplace_back(current_phantom_node_pair);
}
shortest_path(sub_routes[index].segment_end_coordinates, {}, sub_routes[index]);
BOOST_ASSERT(raw_route.shortest_path_length != INVALID_EDGE_WEIGHT);
}
api::MatchAPI match_api{BasePlugin::facade, parameters};
match_api.MakeResponse(sub_matchings, sub_routes, json_result);
if (util::json::Logger::get())
util::json::Logger::get()->render("matching", json_result);
return Status::Ok;
}
}
}
}
*/