Repo created
This commit is contained in:
parent
4af19165ec
commit
68073add76
12458 changed files with 12350765 additions and 2 deletions
58
libs/routing/routing_tests/CMakeLists.txt
Normal file
58
libs/routing/routing_tests/CMakeLists.txt
Normal file
|
|
@ -0,0 +1,58 @@
|
|||
project(routing_tests)
|
||||
|
||||
set(SRC
|
||||
lanes/lanes_parser_tests.cpp
|
||||
lanes/lanes_recommendation_tests.cpp
|
||||
applying_traffic_test.cpp
|
||||
astar_algorithm_test.cpp
|
||||
astar_progress_test.cpp
|
||||
astar_router_test.cpp
|
||||
async_router_test.cpp
|
||||
bfs_tests.cpp
|
||||
checkpoint_predictor_test.cpp
|
||||
coding_test.cpp
|
||||
cross_border_graph_tests.cpp
|
||||
cross_mwm_connector_test.cpp
|
||||
cumulative_restriction_test.cpp
|
||||
edge_estimator_tests.cpp
|
||||
fake_graph_test.cpp
|
||||
followed_polyline_test.cpp
|
||||
guides_tests.cpp
|
||||
index_graph_test.cpp
|
||||
index_graph_tools.cpp
|
||||
index_graph_tools.hpp
|
||||
maxspeeds_tests.cpp
|
||||
mwm_hierarchy_test.cpp
|
||||
nearest_edge_finder_tests.cpp
|
||||
opening_hours_serdes_tests.cpp
|
||||
position_accumulator_tests.cpp
|
||||
restriction_test.cpp
|
||||
road_access_test.cpp
|
||||
road_penalty_test.cpp
|
||||
road_graph_builder.cpp
|
||||
road_graph_builder.hpp
|
||||
road_graph_nearest_edges_test.cpp
|
||||
route_tests.cpp
|
||||
routing_algorithm.cpp
|
||||
routing_algorithm.hpp
|
||||
routing_helpers_tests.cpp
|
||||
routing_options_tests.cpp
|
||||
routing_session_test.cpp
|
||||
speed_cameras_tests.cpp
|
||||
tools.cpp
|
||||
tools.hpp
|
||||
turns_generator_test.cpp
|
||||
turns_sound_test.cpp
|
||||
turns_tts_text_tests.cpp
|
||||
uturn_restriction_tests.cpp
|
||||
world_graph_builder.cpp
|
||||
)
|
||||
|
||||
omim_add_test(${PROJECT_NAME} ${SRC})
|
||||
|
||||
target_link_libraries(${PROJECT_NAME}
|
||||
platform_tests_support
|
||||
generator_tests_support
|
||||
routing
|
||||
storage
|
||||
)
|
||||
237
libs/routing/routing_tests/applying_traffic_test.cpp
Normal file
237
libs/routing/routing_tests/applying_traffic_test.cpp
Normal file
|
|
@ -0,0 +1,237 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "generator/generator_tests_support/routing_helpers.hpp"
|
||||
|
||||
#include "routing/routing_tests/index_graph_tools.hpp"
|
||||
|
||||
#include "routing/fake_ending.hpp"
|
||||
#include "routing/geometry.hpp"
|
||||
#include "routing/index_graph.hpp"
|
||||
#include "routing/index_graph_starter.hpp"
|
||||
#include "routing/routing_session.hpp"
|
||||
#include "routing/traffic_stash.hpp"
|
||||
|
||||
#include "routing_common/car_model.hpp"
|
||||
|
||||
#include "indexer/classificator_loader.hpp"
|
||||
|
||||
#include "geometry/point2d.hpp"
|
||||
|
||||
#include "routing/base/astar_algorithm.hpp"
|
||||
|
||||
#include <memory>
|
||||
#include <vector>
|
||||
|
||||
namespace applying_traffic_test
|
||||
{
|
||||
using namespace routing;
|
||||
using namespace routing_test;
|
||||
using namespace std;
|
||||
using namespace traffic;
|
||||
|
||||
// @TODO(bykoianko) When PR with applying restricions is merged BuildXXGraph()
|
||||
// should be moved to "routing/routing_tests/index_graph_tools.hpp" and it should
|
||||
// be used by applying_traffic_test.cpp and cumulative_restriction_test.cpp.
|
||||
|
||||
// Finish
|
||||
// 3 * *
|
||||
// ↖ ↗
|
||||
// F5 F6
|
||||
// ↖ ↗
|
||||
// 2 * *
|
||||
// ↖ ↗ ↖
|
||||
// F2 F3 F4
|
||||
// ↖ ↗ ↖
|
||||
// 1 * *
|
||||
// ↗ ↖ ^
|
||||
// F0 F1 F8
|
||||
// ↗ ↖ |
|
||||
// 0 * *--F7--->*
|
||||
// ^
|
||||
// F9
|
||||
// |
|
||||
//-1 *
|
||||
// 0 1 2 3
|
||||
// Start
|
||||
//
|
||||
// Note. This graph consists of 10 one segment directed features.
|
||||
unique_ptr<WorldGraph> BuildXXGraph(shared_ptr<EdgeEstimator> estimator)
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
loader->AddRoad(0 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 0.0}, {1.0, 1.0}}));
|
||||
loader->AddRoad(1 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 0.0}, {1.0, 1.0}}));
|
||||
loader->AddRoad(2 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 1.0}, {0.0, 2.0}}));
|
||||
loader->AddRoad(3 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 1.0}, {2.0, 2.0}}));
|
||||
loader->AddRoad(4 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{3.0, 1.0}, {2.0, 2.0}}));
|
||||
loader->AddRoad(5 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 2.0}, {1.0, 3.0}}));
|
||||
loader->AddRoad(6 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 2.0}, {3.0, 3.0}}));
|
||||
loader->AddRoad(7 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 0.0}, {3.0, 0.0}}));
|
||||
loader->AddRoad(8 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{3.0, 0.0}, {3.0, 1.0}}));
|
||||
loader->AddRoad(9 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, -1.0}, {2.0, 0.0}}));
|
||||
|
||||
vector<Joint> const joints = {
|
||||
MakeJoint({{0 /* feature id */, 0 /* point id */}}), /* joint at point (0, 0) */
|
||||
MakeJoint({{1, 0}, {7, 0}, {9, 1}}), /* joint at point (2, 0) */
|
||||
MakeJoint({{0, 1}, {1, 1}, {2, 0}, {3, 0}}), /* joint at point (1, 1) */
|
||||
MakeJoint({{2, 1}}), /* joint at point (0, 2) */
|
||||
MakeJoint({{3, 1}, {4, 1}, {5, 0}, {6, 0}}), /* joint at point (2, 2) */
|
||||
MakeJoint({{4, 0}, {8, 1}}), /* joint at point (3, 1) */
|
||||
MakeJoint({{5, 1}}), /* joint at point (1, 3) */
|
||||
MakeJoint({{6, 1}}), /* joint at point (3, 3) */
|
||||
MakeJoint({{7, 1}, {8, 0}}), /* joint at point (3, 0) */
|
||||
};
|
||||
|
||||
return BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
}
|
||||
|
||||
class ApplyingTrafficTest
|
||||
{
|
||||
public:
|
||||
ApplyingTrafficTest()
|
||||
{
|
||||
classificator::Load();
|
||||
auto numMwmIds = make_shared<NumMwmIds>();
|
||||
m_trafficStash = make_shared<TrafficStash>(m_trafficCache, numMwmIds);
|
||||
m_estimator = CreateEstimatorForCar(m_trafficStash);
|
||||
}
|
||||
|
||||
void SetTrafficColoring(shared_ptr<TrafficInfo::Coloring const> coloring)
|
||||
{
|
||||
m_trafficStash->SetColoring(kTestNumMwmId, coloring);
|
||||
}
|
||||
|
||||
shared_ptr<EdgeEstimator> GetEstimator() const { return m_estimator; }
|
||||
|
||||
shared_ptr<TrafficStash> GetTrafficStash() const { return m_trafficStash; }
|
||||
|
||||
private:
|
||||
TrafficCache m_trafficCache;
|
||||
shared_ptr<EdgeEstimator> m_estimator;
|
||||
shared_ptr<TrafficStash> m_trafficStash;
|
||||
};
|
||||
|
||||
using Algorithm = AStarAlgorithm<Segment, SegmentEdge, RouteWeight>;
|
||||
|
||||
// Route through XX graph without any traffic info.
|
||||
UNIT_CLASS_TEST(ApplyingTrafficTest, XXGraph_EmptyTrafficColoring)
|
||||
{
|
||||
TEST(!GetTrafficStash()->Has(kTestNumMwmId), ());
|
||||
|
||||
unique_ptr<WorldGraph> graph = BuildXXGraph(GetEstimator());
|
||||
auto const start = MakeFakeEnding(9 /* featureId */, 0 /* segmentIdx */, m2::PointD(2.0, -1.0), *graph);
|
||||
auto const finish = MakeFakeEnding(6, 0, m2::PointD(3.0, 3.0), *graph);
|
||||
auto starter = MakeStarter(start, finish, *graph);
|
||||
vector<m2::PointD> const expectedGeom = {{2 /* x */, -1 /* y */}, {2, 0}, {1, 1}, {2, 2}, {3, 3}};
|
||||
TestRouteGeometry(*starter, Algorithm::Result::OK, expectedGeom);
|
||||
}
|
||||
|
||||
// Route through XX graph with SpeedGroup::G0 on F3.
|
||||
UNIT_CLASS_TEST(ApplyingTrafficTest, XXGraph_G0onF3)
|
||||
{
|
||||
TrafficInfo::Coloring const coloring = {
|
||||
{{3 /* feature id */, 0 /* segment id */, TrafficInfo::RoadSegmentId::kForwardDirection}, SpeedGroup::G0}};
|
||||
SetTrafficColoring(make_shared<TrafficInfo::Coloring const>(coloring));
|
||||
|
||||
unique_ptr<WorldGraph> graph = BuildXXGraph(GetEstimator());
|
||||
auto const start = MakeFakeEnding(9 /* featureId */, 0 /* segmentIdx */, m2::PointD(2.0, -1.0), *graph);
|
||||
auto const finish = MakeFakeEnding(6, 0, m2::PointD(3.0, 3.0), *graph);
|
||||
auto starter = MakeStarter(start, finish, *graph);
|
||||
vector<m2::PointD> const expectedGeom = {{2 /* x */, -1 /* y */}, {2, 0}, {3, 0}, {3, 1}, {2, 2}, {3, 3}};
|
||||
TestRouteGeometry(*starter, Algorithm::Result::OK, expectedGeom);
|
||||
}
|
||||
|
||||
// Route through XX graph with SpeedGroup::TempBlock on F3.
|
||||
UNIT_CLASS_TEST(ApplyingTrafficTest, XXGraph_TempBlockonF3)
|
||||
{
|
||||
TrafficInfo::Coloring const coloring = {
|
||||
{{3 /* feature id */, 0 /* segment id */, TrafficInfo::RoadSegmentId::kForwardDirection}, SpeedGroup::TempBlock}};
|
||||
SetTrafficColoring(make_shared<TrafficInfo::Coloring const>(coloring));
|
||||
|
||||
unique_ptr<WorldGraph> graph = BuildXXGraph(GetEstimator());
|
||||
auto const start = MakeFakeEnding(9 /* featureId */, 0 /* segmentIdx */, m2::PointD(2.0, -1.0), *graph);
|
||||
auto const finish = MakeFakeEnding(6, 0, m2::PointD(3.0, 3.0), *graph);
|
||||
auto starter = MakeStarter(start, finish, *graph);
|
||||
vector<m2::PointD> const expectedGeom = {{2 /* x */, -1 /* y */}, {2, 0}, {3, 0}, {3, 1}, {2, 2}, {3, 3}};
|
||||
TestRouteGeometry(*starter, Algorithm::Result::OK, expectedGeom);
|
||||
}
|
||||
|
||||
// Route through XX graph with SpeedGroup::G0 in reverse direction on F3.
|
||||
UNIT_CLASS_TEST(ApplyingTrafficTest, XXGraph_G0onF3ReverseDir)
|
||||
{
|
||||
TrafficInfo::Coloring const coloring = {
|
||||
{{3 /* feature id */, 0 /* segment id */, TrafficInfo::RoadSegmentId::kReverseDirection}, SpeedGroup::G0}};
|
||||
SetTrafficColoring(make_shared<TrafficInfo::Coloring const>(coloring));
|
||||
|
||||
unique_ptr<WorldGraph> graph = BuildXXGraph(GetEstimator());
|
||||
auto const start = MakeFakeEnding(9 /* featureId */, 0 /* segmentIdx */, m2::PointD(2.0, -1.0), *graph);
|
||||
auto const finish = MakeFakeEnding(6, 0, m2::PointD(3.0, 3.0), *graph);
|
||||
auto starter = MakeStarter(start, finish, *graph);
|
||||
vector<m2::PointD> const expectedGeom = {{2 /* x */, -1 /* y */}, {2, 0}, {1, 1}, {2, 2}, {3, 3}};
|
||||
TestRouteGeometry(*starter, Algorithm::Result::OK, expectedGeom);
|
||||
}
|
||||
|
||||
// Route through XX graph SpeedGroup::G1 on F3 and F6, SpeedGroup::G4 on F8 and F4.
|
||||
UNIT_CLASS_TEST(ApplyingTrafficTest, XXGraph_G0onF3andF6andG4onF8andF4)
|
||||
{
|
||||
TrafficInfo::Coloring const coloring = {
|
||||
{{3 /* feature id */, 0 /* segment id */, TrafficInfo::RoadSegmentId::kForwardDirection}, SpeedGroup::G0},
|
||||
{{6 /* feature id */, 0 /* segment id */, TrafficInfo::RoadSegmentId::kForwardDirection}, SpeedGroup::G0},
|
||||
{{8 /* feature id */, 0 /* segment id */, TrafficInfo::RoadSegmentId::kForwardDirection}, SpeedGroup::G4},
|
||||
{{7 /* feature id */, 0 /* segment id */, TrafficInfo::RoadSegmentId::kForwardDirection}, SpeedGroup::G4}};
|
||||
SetTrafficColoring(make_shared<TrafficInfo::Coloring const>(coloring));
|
||||
|
||||
unique_ptr<WorldGraph> graph = BuildXXGraph(GetEstimator());
|
||||
auto const start = MakeFakeEnding(9 /* featureId */, 0 /* segmentIdx */, m2::PointD(2.0, -1.0), *graph);
|
||||
auto const finish = MakeFakeEnding(6, 0, m2::PointD(3.0, 3.0), *graph);
|
||||
auto starter = MakeStarter(start, finish, *graph);
|
||||
vector<m2::PointD> const expectedGeom = {{2 /* x */, -1 /* y */}, {2, 0}, {3, 0}, {3, 1}, {2, 2}, {3, 3}};
|
||||
TestRouteGeometry(*starter, Algorithm::Result::OK, expectedGeom);
|
||||
}
|
||||
|
||||
// Route through XX graph with changing traffic.
|
||||
UNIT_CLASS_TEST(ApplyingTrafficTest, XXGraph_ChangingTraffic)
|
||||
{
|
||||
// No trafic at all.
|
||||
TEST(!GetTrafficStash()->Has(kTestNumMwmId), ());
|
||||
|
||||
unique_ptr<WorldGraph> graph = BuildXXGraph(GetEstimator());
|
||||
auto const start = MakeFakeEnding(9 /* featureId */, 0 /* segmentIdx */, m2::PointD(2.0, -1.0), *graph);
|
||||
auto const finish = MakeFakeEnding(6, 0, m2::PointD(3.0, 3.0), *graph);
|
||||
auto starter = MakeStarter(start, finish, *graph);
|
||||
vector<m2::PointD> const noTrafficGeom = {{2 /* x */, -1 /* y */}, {2, 0}, {1, 1}, {2, 2}, {3, 3}};
|
||||
{
|
||||
TestRouteGeometry(*starter, Algorithm::Result::OK, noTrafficGeom);
|
||||
}
|
||||
|
||||
// Heavy traffic (SpeedGroup::G0) on F3.
|
||||
TrafficInfo::Coloring const coloringHeavyF3 = {
|
||||
{{3 /* feature id */, 0 /* segment id */, TrafficInfo::RoadSegmentId::kForwardDirection}, SpeedGroup::G0}};
|
||||
SetTrafficColoring(make_shared<TrafficInfo::Coloring const>(coloringHeavyF3));
|
||||
{
|
||||
vector<m2::PointD> const heavyF3Geom = {{2 /* x */, -1 /* y */}, {2, 0}, {3, 0}, {3, 1}, {2, 2}, {3, 3}};
|
||||
TestRouteGeometry(*starter, Algorithm::Result::OK, heavyF3Geom);
|
||||
}
|
||||
|
||||
// Overloading traffic jam on F3. Middle traffic (SpeedGroup::G3) on F1, F3, F4, F7 and F8.
|
||||
TrafficInfo::Coloring const coloringMiddleF1F3F4F7F8 = {
|
||||
{{1 /* feature id */, 0 /* segment id */, TrafficInfo::RoadSegmentId::kForwardDirection}, SpeedGroup::G3},
|
||||
{{3 /* feature id */, 0 /* segment id */, TrafficInfo::RoadSegmentId::kForwardDirection}, SpeedGroup::G3},
|
||||
{{4 /* feature id */, 0 /* segment id */, TrafficInfo::RoadSegmentId::kForwardDirection}, SpeedGroup::G3},
|
||||
{{7 /* feature id */, 0 /* segment id */, TrafficInfo::RoadSegmentId::kForwardDirection}, SpeedGroup::G3},
|
||||
{{8 /* feature id */, 0 /* segment id */, TrafficInfo::RoadSegmentId::kForwardDirection}, SpeedGroup::G3}};
|
||||
SetTrafficColoring(make_shared<TrafficInfo::Coloring const>(coloringMiddleF1F3F4F7F8));
|
||||
{
|
||||
TestRouteGeometry(*starter, Algorithm::Result::OK, noTrafficGeom);
|
||||
}
|
||||
}
|
||||
} // namespace applying_traffic_test
|
||||
154
libs/routing/routing_tests/astar_algorithm_test.cpp
Normal file
154
libs/routing/routing_tests/astar_algorithm_test.cpp
Normal file
|
|
@ -0,0 +1,154 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/base/astar_algorithm.hpp"
|
||||
#include "routing/base/astar_graph.hpp"
|
||||
#include "routing/base/routing_result.hpp"
|
||||
|
||||
#include "routing/routing_tests/routing_algorithm.hpp"
|
||||
|
||||
#include <cstdint>
|
||||
#include <map>
|
||||
#include <utility>
|
||||
#include <vector>
|
||||
|
||||
namespace astar_algorithm_test
|
||||
{
|
||||
using namespace routing;
|
||||
using namespace routing_test;
|
||||
using namespace std;
|
||||
|
||||
using Algorithm = AStarAlgorithm<uint32_t, SimpleEdge, double>;
|
||||
|
||||
void TestAStar(UndirectedGraph & graph, vector<unsigned> const & expectedRoute, double const & expectedDistance)
|
||||
{
|
||||
Algorithm algo;
|
||||
|
||||
Algorithm::ParamsForTests<> params(graph, 0u /* startVertex */, 4u /* finishVertex */);
|
||||
|
||||
RoutingResult<unsigned /* Vertex */, double /* Weight */> actualRoute;
|
||||
TEST_EQUAL(Algorithm::Result::OK, algo.FindPath(params, actualRoute), ());
|
||||
TEST_EQUAL(expectedRoute, actualRoute.m_path, ());
|
||||
TEST_ALMOST_EQUAL_ULPS(expectedDistance, actualRoute.m_distance, ());
|
||||
|
||||
actualRoute.m_path.clear();
|
||||
TEST_EQUAL(Algorithm::Result::OK, algo.FindPathBidirectional(params, actualRoute), ());
|
||||
TEST_EQUAL(expectedRoute, actualRoute.m_path, ());
|
||||
TEST_ALMOST_EQUAL_ULPS(expectedDistance, actualRoute.m_distance, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(AStarAlgorithm_Sample)
|
||||
{
|
||||
UndirectedGraph graph;
|
||||
|
||||
// Inserts edges in a format: <source, target, weight>.
|
||||
graph.AddEdge(0, 1, 10);
|
||||
graph.AddEdge(1, 2, 5);
|
||||
graph.AddEdge(2, 3, 5);
|
||||
graph.AddEdge(2, 4, 10);
|
||||
graph.AddEdge(3, 4, 3);
|
||||
|
||||
vector<unsigned> const expectedRoute = {0, 1, 2, 3, 4};
|
||||
|
||||
TestAStar(graph, expectedRoute, 23);
|
||||
}
|
||||
|
||||
UNIT_TEST(AStarAlgorithm_CheckLength)
|
||||
{
|
||||
UndirectedGraph graph;
|
||||
|
||||
// Inserts edges in a format: <source, target, weight>.
|
||||
graph.AddEdge(0, 1, 10);
|
||||
graph.AddEdge(1, 2, 5);
|
||||
graph.AddEdge(2, 3, 5);
|
||||
graph.AddEdge(2, 4, 10);
|
||||
graph.AddEdge(3, 4, 3);
|
||||
|
||||
auto checkLength = [](double weight) { return weight < 23; };
|
||||
Algorithm algo;
|
||||
Algorithm::ParamsForTests<decltype(checkLength)> params(graph, 0u /* startVertex */, 4u /* finishVertex */,
|
||||
std::move(checkLength));
|
||||
|
||||
RoutingResult<unsigned /* Vertex */, double /* Weight */> routingResult;
|
||||
Algorithm::Result result = algo.FindPath(params, routingResult);
|
||||
// Best route weight is 23 so we expect to find no route with restriction |weight < 23|.
|
||||
TEST_EQUAL(result, Algorithm::Result::NoPath, ());
|
||||
|
||||
routingResult = {};
|
||||
result = algo.FindPathBidirectional(params, routingResult);
|
||||
// Best route weight is 23 so we expect to find no route with restriction |weight < 23|.
|
||||
TEST_EQUAL(result, Algorithm::Result::NoPath, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(AdjustRoute)
|
||||
{
|
||||
UndirectedGraph graph;
|
||||
|
||||
for (unsigned int i = 0; i < 5; ++i)
|
||||
graph.AddEdge(i /* from */, i + 1 /* to */, 1 /* weight */);
|
||||
|
||||
graph.AddEdge(6, 0, 1);
|
||||
graph.AddEdge(6, 1, 1);
|
||||
graph.AddEdge(6, 2, 1);
|
||||
|
||||
// Each edge contains {vertexId, weight}.
|
||||
vector<SimpleEdge> const prevRoute = {{0, 0}, {1, 1}, {2, 1}, {3, 1}, {4, 1}, {5, 1}};
|
||||
|
||||
auto checkLength = [](double weight) { return weight <= 1.0; };
|
||||
Algorithm algo;
|
||||
Algorithm::ParamsForTests<decltype(checkLength)> params(graph, 6 /* startVertex */, {} /* finishVertex */,
|
||||
std::move(checkLength));
|
||||
|
||||
RoutingResult<unsigned /* Vertex */, double /* Weight */> result;
|
||||
auto const code = algo.AdjustRoute(params, prevRoute, result);
|
||||
|
||||
vector<unsigned> const expectedRoute = {6, 2, 3, 4, 5};
|
||||
TEST_EQUAL(code, Algorithm::Result::OK, ());
|
||||
TEST_EQUAL(result.m_path, expectedRoute, ());
|
||||
TEST_EQUAL(result.m_distance, 4.0, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(AdjustRouteNoPath)
|
||||
{
|
||||
UndirectedGraph graph;
|
||||
|
||||
for (unsigned int i = 0; i < 5; ++i)
|
||||
graph.AddEdge(i /* from */, i + 1 /* to */, 1 /* weight */);
|
||||
|
||||
// Each edge contains {vertexId, weight}.
|
||||
vector<SimpleEdge> const prevRoute = {{0, 0}, {1, 1}, {2, 1}, {3, 1}, {4, 1}, {5, 1}};
|
||||
|
||||
auto checkLength = [](double weight) { return weight <= 1.0; };
|
||||
Algorithm algo;
|
||||
Algorithm::ParamsForTests<decltype(checkLength)> params(graph, 6 /* startVertex */, {} /* finishVertex */,
|
||||
std::move(checkLength));
|
||||
RoutingResult<unsigned /* Vertex */, double /* Weight */> result;
|
||||
auto const code = algo.AdjustRoute(params, prevRoute, result);
|
||||
|
||||
TEST_EQUAL(code, Algorithm::Result::NoPath, ());
|
||||
TEST(result.m_path.empty(), ());
|
||||
}
|
||||
|
||||
UNIT_TEST(AdjustRouteOutOfLimit)
|
||||
{
|
||||
UndirectedGraph graph;
|
||||
|
||||
for (unsigned int i = 0; i < 5; ++i)
|
||||
graph.AddEdge(i /* from */, i + 1 /* to */, 1 /* weight */);
|
||||
|
||||
graph.AddEdge(6, 2, 2);
|
||||
|
||||
// Each edge contains {vertexId, weight}.
|
||||
vector<SimpleEdge> const prevRoute = {{0, 0}, {1, 1}, {2, 1}, {3, 1}, {4, 1}, {5, 1}};
|
||||
|
||||
auto checkLength = [](double weight) { return weight <= 1.0; };
|
||||
Algorithm algo;
|
||||
Algorithm::ParamsForTests<decltype(checkLength)> params(graph, 6 /* startVertex */, {} /* finishVertex */,
|
||||
std::move(checkLength));
|
||||
|
||||
RoutingResult<unsigned /* Vertex */, double /* Weight */> result;
|
||||
auto const code = algo.AdjustRoute(params, prevRoute, result);
|
||||
|
||||
TEST_EQUAL(code, Algorithm::Result::NoPath, ());
|
||||
TEST(result.m_path.empty(), ());
|
||||
}
|
||||
} // namespace astar_algorithm_test
|
||||
80
libs/routing/routing_tests/astar_progress_test.cpp
Normal file
80
libs/routing/routing_tests/astar_progress_test.cpp
Normal file
|
|
@ -0,0 +1,80 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/base/astar_progress.hpp"
|
||||
|
||||
namespace routing_test
|
||||
{
|
||||
using namespace routing;
|
||||
|
||||
UNIT_TEST(DirectedAStarProgressCheck)
|
||||
{
|
||||
ms::LatLon start = ms::LatLon(0.0, 1.0);
|
||||
ms::LatLon finish = ms::LatLon(0.0, 3.0);
|
||||
ms::LatLon middle = ms::LatLon(0.0, 2.0);
|
||||
|
||||
AStarProgress progress;
|
||||
progress.AppendSubProgress({start, finish, 1.0 /* contributionCoef */});
|
||||
TEST_LESS(progress.UpdateProgress(start, finish), 0.1, ());
|
||||
TEST_LESS(progress.UpdateProgress(middle, finish), 51.0, ());
|
||||
TEST_GREATER(progress.UpdateProgress(middle, finish), 49.0, ());
|
||||
|
||||
static auto constexpr kEps = 0.001;
|
||||
TEST_GREATER(progress.UpdateProgress(finish, finish), AStarProgress::kMaxPercent - kEps, ());
|
||||
|
||||
progress.PushAndDropLastSubProgress();
|
||||
}
|
||||
|
||||
UNIT_TEST(DirectedAStarDegradationCheck)
|
||||
{
|
||||
ms::LatLon start = ms::LatLon(0.0, 1.0);
|
||||
ms::LatLon finish = ms::LatLon(0.0, 3.0);
|
||||
ms::LatLon middle = ms::LatLon(0.0, 2.0);
|
||||
|
||||
AStarProgress progressFirst;
|
||||
progressFirst.AppendSubProgress({start, finish, 1.0 /* contributionCoef */});
|
||||
auto value1 = progressFirst.UpdateProgress(middle, finish);
|
||||
auto value2 = progressFirst.UpdateProgress(start, finish);
|
||||
TEST_LESS_OR_EQUAL(value1, value2, ());
|
||||
|
||||
AStarProgress progressSecond;
|
||||
progressSecond.AppendSubProgress({start, finish, 1.0 /* contributionCoef */});
|
||||
auto value3 = progressSecond.UpdateProgress(start, finish);
|
||||
TEST_GREATER_OR_EQUAL(value1, value3, ());
|
||||
|
||||
progressFirst.PushAndDropLastSubProgress();
|
||||
progressSecond.PushAndDropLastSubProgress();
|
||||
}
|
||||
|
||||
UNIT_TEST(RangeCheckTest)
|
||||
{
|
||||
ms::LatLon start = ms::LatLon(0.0, 1.0);
|
||||
ms::LatLon finish = ms::LatLon(0.0, 3.0);
|
||||
ms::LatLon preStart = ms::LatLon(0.0, 0.0);
|
||||
ms::LatLon postFinish = ms::LatLon(0.0, 6.0);
|
||||
|
||||
AStarProgress progress;
|
||||
progress.AppendSubProgress({start, finish, 1.0 /* contributionCoef */});
|
||||
TEST_EQUAL(progress.UpdateProgress(preStart, finish), 0.0, ());
|
||||
TEST_EQUAL(progress.UpdateProgress(postFinish, finish), 0.0, ());
|
||||
TEST_EQUAL(progress.UpdateProgress(finish, finish), AStarProgress::kMaxPercent, ());
|
||||
|
||||
progress.PushAndDropLastSubProgress();
|
||||
}
|
||||
|
||||
UNIT_TEST(BidirectedAStarProgressCheck)
|
||||
{
|
||||
ms::LatLon start = ms::LatLon(0.0, 0.0);
|
||||
ms::LatLon finish = ms::LatLon(0.0, 4.0);
|
||||
ms::LatLon fWave = ms::LatLon(0.0, 1.0);
|
||||
ms::LatLon bWave = ms::LatLon(0.0, 3.0);
|
||||
|
||||
AStarProgress progress;
|
||||
progress.AppendSubProgress({start, finish, 1.0 /* contributionCoef */});
|
||||
progress.UpdateProgress(fWave, finish);
|
||||
float result = progress.UpdateProgress(bWave, start);
|
||||
TEST_GREATER(result, 49.0, ());
|
||||
TEST_LESS(result, 51.0, ());
|
||||
|
||||
progress.PushAndDropLastSubProgress();
|
||||
}
|
||||
} // namespace routing_test
|
||||
306
libs/routing/routing_tests/astar_router_test.cpp
Normal file
306
libs/routing/routing_tests/astar_router_test.cpp
Normal file
|
|
@ -0,0 +1,306 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/routing_tests/road_graph_builder.hpp"
|
||||
#include "routing/routing_tests/routing_algorithm.hpp"
|
||||
|
||||
#include "routing/features_road_graph.hpp"
|
||||
#include "routing/road_graph.hpp"
|
||||
#include "routing/route.hpp"
|
||||
#include "routing/router_delegate.hpp"
|
||||
|
||||
#include "indexer/classificator_loader.hpp"
|
||||
#include "indexer/feature_altitude.hpp"
|
||||
|
||||
#include "geometry/point2d.hpp"
|
||||
#include "geometry/point_with_altitude.hpp"
|
||||
|
||||
#include "base/logging.hpp"
|
||||
#include "base/macros.hpp"
|
||||
|
||||
#include <vector>
|
||||
|
||||
namespace astar_router_test
|
||||
{
|
||||
using namespace routing;
|
||||
using namespace routing_test;
|
||||
using namespace std;
|
||||
|
||||
void TestAStarRouterMock(geometry::PointWithAltitude const & startPos, geometry::PointWithAltitude const & finalPos,
|
||||
vector<geometry::PointWithAltitude> const & expected)
|
||||
{
|
||||
classificator::Load();
|
||||
|
||||
RoadGraphMockSource graph;
|
||||
InitRoadGraphMockSourceWithTest2(graph);
|
||||
|
||||
RoutingResult<geometry::PointWithAltitude, double /* Weight */> result;
|
||||
TestAStarBidirectionalAlgo algorithm;
|
||||
TEST_EQUAL(TestAStarBidirectionalAlgo::Result::OK, algorithm.CalculateRoute(graph, startPos, finalPos, result), ());
|
||||
|
||||
TEST_EQUAL(expected, result.m_path, ());
|
||||
}
|
||||
|
||||
void AddRoad(RoadGraphMockSource & graph, double speedKMPH, initializer_list<m2::PointD> const & points)
|
||||
{
|
||||
graph.AddRoad(routing::MakeRoadInfoForTesting(true /* bidir */, speedKMPH, points));
|
||||
}
|
||||
|
||||
void AddRoad(RoadGraphMockSource & graph, initializer_list<m2::PointD> const & points)
|
||||
{
|
||||
double const speedKMpH = graph.GetMaxSpeedKMpH();
|
||||
graph.AddRoad(routing::MakeRoadInfoForTesting(true /* bidir */, speedKMpH, points));
|
||||
}
|
||||
|
||||
UNIT_TEST(AStarRouter_Graph2_Simple1)
|
||||
{
|
||||
geometry::PointWithAltitude const startPos = geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 0));
|
||||
geometry::PointWithAltitude const finalPos = geometry::MakePointWithAltitudeForTesting(m2::PointD(80, 55));
|
||||
|
||||
vector<geometry::PointWithAltitude> const expected = {geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 0)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(5, 10)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(5, 40)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(18, 55)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(39, 55)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(80, 55))};
|
||||
|
||||
TestAStarRouterMock(startPos, finalPos, expected);
|
||||
}
|
||||
|
||||
UNIT_TEST(AStarRouter_Graph2_Simple2)
|
||||
{
|
||||
geometry::PointWithAltitude const startPos = geometry::MakePointWithAltitudeForTesting(m2::PointD(80, 55));
|
||||
geometry::PointWithAltitude const finalPos = geometry::MakePointWithAltitudeForTesting(m2::PointD(80, 0));
|
||||
|
||||
vector<geometry::PointWithAltitude> const expected = {geometry::MakePointWithAltitudeForTesting(m2::PointD(80, 55)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(39, 55)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(37, 30)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(70, 30)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(70, 10)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(70, 0)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(80, 0))};
|
||||
|
||||
TestAStarRouterMock(startPos, finalPos, expected);
|
||||
}
|
||||
|
||||
UNIT_TEST(AStarRouter_SimpleGraph_RouteIsFound)
|
||||
{
|
||||
classificator::Load();
|
||||
|
||||
RoadGraphMockSource graph;
|
||||
AddRoad(graph, {m2::PointD(0, 0), m2::PointD(40, 0)}); // feature 0
|
||||
AddRoad(graph, {m2::PointD(40, 0), m2::PointD(40, 30)}); // feature 1
|
||||
AddRoad(graph, {m2::PointD(40, 30), m2::PointD(40, 100)}); // feature 2
|
||||
AddRoad(graph, {m2::PointD(40, 100), m2::PointD(0, 60)}); // feature 3
|
||||
AddRoad(graph, {m2::PointD(0, 60), m2::PointD(0, 30)}); // feature 4
|
||||
AddRoad(graph, {m2::PointD(0, 30), m2::PointD(0, 0)}); // feature 5
|
||||
|
||||
geometry::PointWithAltitude const startPos = geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 0));
|
||||
geometry::PointWithAltitude const finalPos = geometry::MakePointWithAltitudeForTesting(m2::PointD(40, 100));
|
||||
|
||||
vector<geometry::PointWithAltitude> const expected = {geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 0)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 30)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 60)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(40, 100))};
|
||||
|
||||
RoutingResult<geometry::PointWithAltitude, double /* Weight */> result;
|
||||
TestAStarBidirectionalAlgo algorithm;
|
||||
TEST_EQUAL(TestAStarBidirectionalAlgo::Result::OK, algorithm.CalculateRoute(graph, startPos, finalPos, result), ());
|
||||
|
||||
TEST_EQUAL(expected, result.m_path, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(AStarRouter_SimpleGraph_RoutesInConnectedComponents)
|
||||
{
|
||||
classificator::Load();
|
||||
|
||||
RoadGraphMockSource graph;
|
||||
|
||||
double const speedKMpH = graph.GetMaxSpeedKMpH();
|
||||
|
||||
// Roads in the first connected component.
|
||||
vector<IRoadGraph::RoadInfo> const roadInfo_1 = {
|
||||
IRoadGraph::RoadInfo(true /* bidir */, speedKMpH,
|
||||
{geometry::MakePointWithAltitudeForTesting(m2::PointD(10, 10)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(90, 10))}), // feature 0
|
||||
IRoadGraph::RoadInfo(true /* bidir */, speedKMpH,
|
||||
{geometry::MakePointWithAltitudeForTesting(m2::PointD(90, 10)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(90, 90))}), // feature 1
|
||||
IRoadGraph::RoadInfo(true /* bidir */, speedKMpH,
|
||||
{geometry::MakePointWithAltitudeForTesting(m2::PointD(90, 90)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(10, 90))}), // feature 2
|
||||
IRoadGraph::RoadInfo(true /* bidir */, speedKMpH,
|
||||
{geometry::MakePointWithAltitudeForTesting(m2::PointD(10, 90)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(10, 10))}), // feature 3
|
||||
};
|
||||
|
||||
// Roads in the second connected component.
|
||||
vector<IRoadGraph::RoadInfo> const roadInfo_2 = {
|
||||
IRoadGraph::RoadInfo(true /* bidir */, speedKMpH,
|
||||
{geometry::MakePointWithAltitudeForTesting(m2::PointD(30, 30)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(70, 30))}), // feature 4
|
||||
IRoadGraph::RoadInfo(true /* bidir */, speedKMpH,
|
||||
{geometry::MakePointWithAltitudeForTesting(m2::PointD(70, 30)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(70, 70))}), // feature 5
|
||||
IRoadGraph::RoadInfo(true /* bidir */, speedKMpH,
|
||||
{geometry::MakePointWithAltitudeForTesting(m2::PointD(70, 70)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(30, 70))}), // feature 6
|
||||
IRoadGraph::RoadInfo(true /* bidir */, speedKMpH,
|
||||
{geometry::MakePointWithAltitudeForTesting(m2::PointD(30, 70)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(30, 30))}), // feature 7
|
||||
};
|
||||
|
||||
for (auto const & ri : roadInfo_1)
|
||||
graph.AddRoad(IRoadGraph::RoadInfo(ri));
|
||||
|
||||
for (auto const & ri : roadInfo_2)
|
||||
graph.AddRoad(IRoadGraph::RoadInfo(ri));
|
||||
|
||||
TestAStarBidirectionalAlgo algorithm;
|
||||
|
||||
// In this test we check that there is no any route between pairs from different connected components,
|
||||
// but there are routes between points in one connected component.
|
||||
|
||||
// Check if there is no any route between points in different connected components.
|
||||
for (size_t i = 0; i < roadInfo_1.size(); ++i)
|
||||
{
|
||||
geometry::PointWithAltitude const startPos = roadInfo_1[i].m_junctions[0];
|
||||
for (size_t j = 0; j < roadInfo_2.size(); ++j)
|
||||
{
|
||||
geometry::PointWithAltitude const finalPos = roadInfo_2[j].m_junctions[0];
|
||||
RoutingResult<geometry::PointWithAltitude, double /* Weight */> result;
|
||||
TEST_EQUAL(TestAStarBidirectionalAlgo::Result::NoPath,
|
||||
algorithm.CalculateRoute(graph, startPos, finalPos, result), ());
|
||||
TEST_EQUAL(TestAStarBidirectionalAlgo::Result::NoPath,
|
||||
algorithm.CalculateRoute(graph, finalPos, startPos, result), ());
|
||||
}
|
||||
}
|
||||
|
||||
// Check if there is route between points in the first connected component.
|
||||
for (size_t i = 0; i < roadInfo_1.size(); ++i)
|
||||
{
|
||||
geometry::PointWithAltitude const startPos = roadInfo_1[i].m_junctions[0];
|
||||
for (size_t j = i + 1; j < roadInfo_1.size(); ++j)
|
||||
{
|
||||
geometry::PointWithAltitude const finalPos = roadInfo_1[j].m_junctions[0];
|
||||
RoutingResult<geometry::PointWithAltitude, double /* Weight */> result;
|
||||
TEST_EQUAL(TestAStarBidirectionalAlgo::Result::OK, algorithm.CalculateRoute(graph, startPos, finalPos, result),
|
||||
());
|
||||
TEST_EQUAL(TestAStarBidirectionalAlgo::Result::OK, algorithm.CalculateRoute(graph, finalPos, startPos, result),
|
||||
());
|
||||
}
|
||||
}
|
||||
|
||||
// Check if there is route between points in the second connected component.
|
||||
for (size_t i = 0; i < roadInfo_2.size(); ++i)
|
||||
{
|
||||
geometry::PointWithAltitude const startPos = roadInfo_2[i].m_junctions[0];
|
||||
for (size_t j = i + 1; j < roadInfo_2.size(); ++j)
|
||||
{
|
||||
geometry::PointWithAltitude const finalPos = roadInfo_2[j].m_junctions[0];
|
||||
RoutingResult<geometry::PointWithAltitude, double /* Weight */> result;
|
||||
TEST_EQUAL(TestAStarBidirectionalAlgo::Result::OK, algorithm.CalculateRoute(graph, startPos, finalPos, result),
|
||||
());
|
||||
TEST_EQUAL(TestAStarBidirectionalAlgo::Result::OK, algorithm.CalculateRoute(graph, finalPos, startPos, result),
|
||||
());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
UNIT_TEST(AStarRouter_SimpleGraph_PickTheFasterRoad1)
|
||||
{
|
||||
classificator::Load();
|
||||
|
||||
RoadGraphMockSource graph;
|
||||
|
||||
AddRoad(graph, 5.0, {m2::PointD(2, 1), m2::PointD(2, 2), m2::PointD(2, 3)});
|
||||
AddRoad(graph, 5.0, {m2::PointD(10, 1), m2::PointD(10, 2), m2::PointD(10, 3)});
|
||||
|
||||
AddRoad(graph, 5.0, {m2::PointD(2, 3), m2::PointD(4, 3), m2::PointD(6, 3), m2::PointD(8, 3), m2::PointD(10, 3)});
|
||||
AddRoad(graph, 3.0, {m2::PointD(2, 2), m2::PointD(6, 2), m2::PointD(10, 2)});
|
||||
AddRoad(graph, 4.0, {m2::PointD(2, 1), m2::PointD(10, 1)});
|
||||
|
||||
// path1 = 1/5 + 8/5 + 1/5 = 2
|
||||
// path2 = 8/3 = 2.666(6)
|
||||
// path3 = 1/5 + 8/4 + 1/5 = 2.4
|
||||
|
||||
RoutingResult<geometry::PointWithAltitude, double /* Weight */> result;
|
||||
TestAStarBidirectionalAlgo algorithm;
|
||||
TEST_EQUAL(TestAStarBidirectionalAlgo::Result::OK,
|
||||
algorithm.CalculateRoute(graph, geometry::MakePointWithAltitudeForTesting(m2::PointD(2, 2)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(10, 2)), result),
|
||||
());
|
||||
TEST_EQUAL(result.m_path,
|
||||
vector<geometry::PointWithAltitude>({geometry::MakePointWithAltitudeForTesting(m2::PointD(2, 2)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(2, 3)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(4, 3)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(6, 3)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(8, 3)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(10, 3)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(10, 2))}),
|
||||
());
|
||||
TEST(AlmostEqualAbs(result.m_distance, 800451., 1.), ("Distance error:", result.m_distance));
|
||||
}
|
||||
|
||||
UNIT_TEST(AStarRouter_SimpleGraph_PickTheFasterRoad2)
|
||||
{
|
||||
classificator::Load();
|
||||
|
||||
RoadGraphMockSource graph;
|
||||
|
||||
AddRoad(graph, 5.0, {m2::PointD(2, 1), m2::PointD(2, 2), m2::PointD(2, 3)});
|
||||
AddRoad(graph, 5.0, {m2::PointD(10, 1), m2::PointD(10, 2), m2::PointD(10, 3)});
|
||||
|
||||
AddRoad(graph, 5.0, {m2::PointD(2, 3), m2::PointD(4, 3), m2::PointD(6, 3), m2::PointD(8, 3), m2::PointD(10, 3)});
|
||||
AddRoad(graph, 4.1, {m2::PointD(2, 2), m2::PointD(6, 2), m2::PointD(10, 2)});
|
||||
AddRoad(graph, 4.4, {m2::PointD(2, 1), m2::PointD(10, 1)});
|
||||
|
||||
// path1 = 1/5 + 8/5 + 1/5 = 2
|
||||
// path2 = 8/4.1 = 1.95
|
||||
// path3 = 1/5 + 8/4.4 + 1/5 = 2.2
|
||||
|
||||
RoutingResult<geometry::PointWithAltitude, double /* Weight */> result;
|
||||
TestAStarBidirectionalAlgo algorithm;
|
||||
TEST_EQUAL(TestAStarBidirectionalAlgo::Result::OK,
|
||||
algorithm.CalculateRoute(graph, geometry::MakePointWithAltitudeForTesting(m2::PointD(2, 2)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(10, 2)), result),
|
||||
());
|
||||
TEST_EQUAL(result.m_path,
|
||||
vector<geometry::PointWithAltitude>({geometry::MakePointWithAltitudeForTesting(m2::PointD(2, 2)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(6, 2)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(10, 2))}),
|
||||
());
|
||||
TEST(AlmostEqualAbs(result.m_distance, 781458., 1.), ("Distance error:", result.m_distance));
|
||||
}
|
||||
|
||||
UNIT_TEST(AStarRouter_SimpleGraph_PickTheFasterRoad3)
|
||||
{
|
||||
classificator::Load();
|
||||
|
||||
RoadGraphMockSource graph;
|
||||
|
||||
AddRoad(graph, 5.0, {m2::PointD(2, 1), m2::PointD(2, 2), m2::PointD(2, 3)});
|
||||
AddRoad(graph, 5.0, {m2::PointD(10, 1), m2::PointD(10, 2), m2::PointD(10, 3)});
|
||||
|
||||
AddRoad(graph, 4.8, {m2::PointD(2, 3), m2::PointD(4, 3), m2::PointD(6, 3), m2::PointD(8, 3), m2::PointD(10, 3)});
|
||||
AddRoad(graph, 3.9, {m2::PointD(2, 2), m2::PointD(6, 2), m2::PointD(10, 2)});
|
||||
AddRoad(graph, 4.9, {m2::PointD(2, 1), m2::PointD(10, 1)});
|
||||
|
||||
// path1 = 1/5 + 8/4.8 + 1/5 = 2.04
|
||||
// path2 = 8/3.9 = 2.05
|
||||
// path3 = 1/5 + 8/4.9 + 1/5 = 2.03
|
||||
|
||||
RoutingResult<geometry::PointWithAltitude, double /* Weight */> result;
|
||||
TestAStarBidirectionalAlgo algorithm;
|
||||
TEST_EQUAL(TestAStarBidirectionalAlgo::Result::OK,
|
||||
algorithm.CalculateRoute(graph, geometry::MakePointWithAltitudeForTesting(m2::PointD(2, 2)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(10, 2)), result),
|
||||
());
|
||||
TEST_EQUAL(result.m_path,
|
||||
vector<geometry::PointWithAltitude>({geometry::MakePointWithAltitudeForTesting(m2::PointD(2, 2)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(2, 1)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(10, 1)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(10, 2))}),
|
||||
());
|
||||
TEST(AlmostEqualAbs(result.m_distance, 814412., 1.), ("Distance error:", result.m_distance));
|
||||
}
|
||||
} // namespace astar_router_test
|
||||
146
libs/routing/routing_tests/async_router_test.cpp
Normal file
146
libs/routing/routing_tests/async_router_test.cpp
Normal file
|
|
@ -0,0 +1,146 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/routing_tests/tools.hpp"
|
||||
|
||||
#include "routing/async_router.hpp"
|
||||
#include "routing/router.hpp"
|
||||
#include "routing/routing_callbacks.hpp"
|
||||
|
||||
#include "geometry/point2d.hpp"
|
||||
|
||||
#include "platform/platform.hpp"
|
||||
|
||||
#include "base/timer.hpp"
|
||||
|
||||
#include <condition_variable>
|
||||
#include <cstdint>
|
||||
#include <memory>
|
||||
#include <mutex>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
namespace async_router_test
|
||||
{
|
||||
using namespace routing;
|
||||
using namespace std::placeholders;
|
||||
using namespace std;
|
||||
|
||||
class DummyRouter : public IRouter
|
||||
{
|
||||
RouterResultCode m_result;
|
||||
set<string> m_absent;
|
||||
|
||||
public:
|
||||
DummyRouter(RouterResultCode code, set<string> const & absent) : m_result(code), m_absent(absent) {}
|
||||
|
||||
// IRouter overrides:
|
||||
string GetName() const override { return "Dummy"; }
|
||||
void SetGuides(GuidesTracks && /* guides */) override {}
|
||||
RouterResultCode CalculateRoute(Checkpoints const & checkpoints, m2::PointD const & startDirection,
|
||||
bool adjustToPrevRoute, RouterDelegate const & delegate, Route & route) override
|
||||
{
|
||||
route = Route("dummy", checkpoints.GetPoints().cbegin(), checkpoints.GetPoints().cend(), 0 /* route id */);
|
||||
|
||||
for (auto const & absent : m_absent)
|
||||
route.AddAbsentCountry(absent);
|
||||
|
||||
return m_result;
|
||||
}
|
||||
|
||||
bool FindClosestProjectionToRoad(m2::PointD const & point, m2::PointD const & direction, double radius,
|
||||
EdgeProj & proj) override
|
||||
{
|
||||
return false;
|
||||
}
|
||||
};
|
||||
|
||||
struct DummyRoutingCallbacks
|
||||
{
|
||||
vector<RouterResultCode> m_codes;
|
||||
vector<set<string>> m_absent;
|
||||
condition_variable m_cv;
|
||||
mutex m_lock;
|
||||
uint32_t const m_expected;
|
||||
uint32_t m_called;
|
||||
|
||||
explicit DummyRoutingCallbacks(uint32_t expectedCalls) : m_expected(expectedCalls), m_called(0) {}
|
||||
|
||||
// ReadyCallbackOwnership callback
|
||||
void operator()(shared_ptr<Route> route, RouterResultCode code)
|
||||
{
|
||||
CHECK(route, ());
|
||||
m_codes.push_back(code);
|
||||
m_absent.emplace_back(route->GetAbsentCountries());
|
||||
TestAndNotifyReadyCallbacks();
|
||||
}
|
||||
|
||||
// NeedMoreMapsCallback callback
|
||||
void operator()(uint64_t routeId, set<string> const & absent)
|
||||
{
|
||||
m_codes.push_back(RouterResultCode::NeedMoreMaps);
|
||||
m_absent.emplace_back(absent);
|
||||
TestAndNotifyReadyCallbacks();
|
||||
}
|
||||
|
||||
void WaitFinish()
|
||||
{
|
||||
unique_lock<mutex> lk(m_lock);
|
||||
return m_cv.wait(lk, [this] { return m_called == m_expected; });
|
||||
}
|
||||
|
||||
void TestAndNotifyReadyCallbacks()
|
||||
{
|
||||
{
|
||||
lock_guard<mutex> calledLock(m_lock);
|
||||
++m_called;
|
||||
TEST_LESS_OR_EQUAL(m_called, m_expected, ("The result callback called more times than expected."));
|
||||
}
|
||||
m_cv.notify_all();
|
||||
}
|
||||
};
|
||||
|
||||
// TODO(o.khlopkova) Uncomment and update these tests.
|
||||
|
||||
// UNIT_CLASS_TEST(AsyncGuiThreadTest, NeedMoreMapsSignalTest)
|
||||
//{
|
||||
// set<string> const absentData({"test1", "test2"});
|
||||
// unique_ptr<IOnlineFetcher> fetcher(new DummyFetcher(absentData));
|
||||
// unique_ptr<IRouter> router(new DummyRouter(RouterResultCode::NoError, {}));
|
||||
// DummyRoutingCallbacks resultCallback(2 /* expectedCalls */);
|
||||
// AsyncRouter async(DummyStatisticsCallback, nullptr /* pointCheckCallback */);
|
||||
// async.SetRouter(std::move(router), std::move(fetcher));
|
||||
// async.CalculateRoute(Checkpoints({1, 2} /* start */, {5, 6} /* finish */), {3, 4}, false,
|
||||
// bind(ref(resultCallback), _1, _2) /* readyCallback */,
|
||||
// bind(ref(resultCallback), _1, _2) /* needMoreMapsCallback */,
|
||||
// nullptr /* removeRouteCallback */, nullptr /* progressCallback */);
|
||||
//
|
||||
// resultCallback.WaitFinish();
|
||||
//
|
||||
// TEST_EQUAL(resultCallback.m_codes.size(), 2, ());
|
||||
// TEST_EQUAL(resultCallback.m_codes[0], RouterResultCode::NoError, ());
|
||||
// TEST_EQUAL(resultCallback.m_codes[1], RouterResultCode::NeedMoreMaps, ());
|
||||
// TEST_EQUAL(resultCallback.m_absent.size(), 2, ());
|
||||
// TEST(resultCallback.m_absent[0].empty(), ());
|
||||
// TEST_EQUAL(resultCallback.m_absent[1].size(), 2, ());
|
||||
// TEST_EQUAL(resultCallback.m_absent[1], absentData, ());
|
||||
//}
|
||||
|
||||
// UNIT_CLASS_TEST(AsyncGuiThreadTest, StandardAsyncFogTest)
|
||||
//{
|
||||
// unique_ptr<IOnlineFetcher> fetcher(new DummyFetcher({}));
|
||||
// unique_ptr<IRouter> router(new DummyRouter(RouterResultCode::NoError, {}));
|
||||
// DummyRoutingCallbacks resultCallback(1 /* expectedCalls */);
|
||||
// AsyncRouter async(DummyStatisticsCallback, nullptr /* pointCheckCallback */);
|
||||
// async.SetRouter(std::move(router), std::move(fetcher));
|
||||
// async.CalculateRoute(Checkpoints({1, 2} /* start */, {5, 6} /* finish */), {3, 4}, false,
|
||||
// bind(ref(resultCallback), _1, _2), nullptr /* needMoreMapsCallback */,
|
||||
// nullptr /* progressCallback */, nullptr /* removeRouteCallback */);
|
||||
//
|
||||
// resultCallback.WaitFinish();
|
||||
//
|
||||
// TEST_EQUAL(resultCallback.m_codes.size(), 1, ());
|
||||
// TEST_EQUAL(resultCallback.m_codes[0], RouterResultCode::NoError, ());
|
||||
// TEST_EQUAL(resultCallback.m_absent.size(), 1, ());
|
||||
// TEST(resultCallback.m_absent[0].empty(), ());
|
||||
//}
|
||||
} // namespace async_router_test
|
||||
173
libs/routing/routing_tests/bfs_tests.cpp
Normal file
173
libs/routing/routing_tests/bfs_tests.cpp
Normal file
|
|
@ -0,0 +1,173 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/base/bfs.hpp"
|
||||
|
||||
#include "routing/routing_tests/routing_algorithm.hpp"
|
||||
|
||||
#include <cstdint>
|
||||
#include <set>
|
||||
#include <vector>
|
||||
|
||||
namespace
|
||||
{
|
||||
using namespace routing_test;
|
||||
|
||||
double constexpr kWeight = 1.0;
|
||||
|
||||
UndirectedGraph BuildUndirectedGraph()
|
||||
{
|
||||
UndirectedGraph graph;
|
||||
|
||||
// Inserts edges in a format: <source, target, weight>.
|
||||
graph.AddEdge(0, 4, kWeight);
|
||||
graph.AddEdge(5, 4, kWeight);
|
||||
graph.AddEdge(4, 1, kWeight);
|
||||
graph.AddEdge(4, 3, kWeight);
|
||||
graph.AddEdge(3, 2, kWeight);
|
||||
graph.AddEdge(7, 4, kWeight);
|
||||
graph.AddEdge(7, 6, kWeight);
|
||||
graph.AddEdge(7, 8, kWeight);
|
||||
graph.AddEdge(8, 9, kWeight);
|
||||
graph.AddEdge(8, 10, kWeight);
|
||||
|
||||
return graph;
|
||||
}
|
||||
|
||||
DirectedGraph BuildDirectedGraph()
|
||||
{
|
||||
DirectedGraph graph;
|
||||
|
||||
// Inserts edges in a format: <source, target, weight>.
|
||||
graph.AddEdge(0, 4, kWeight);
|
||||
graph.AddEdge(5, 4, kWeight);
|
||||
graph.AddEdge(4, 1, kWeight);
|
||||
graph.AddEdge(4, 3, kWeight);
|
||||
graph.AddEdge(3, 2, kWeight);
|
||||
graph.AddEdge(7, 4, kWeight);
|
||||
graph.AddEdge(7, 6, kWeight);
|
||||
graph.AddEdge(7, 8, kWeight);
|
||||
graph.AddEdge(8, 9, kWeight);
|
||||
graph.AddEdge(8, 10, kWeight);
|
||||
|
||||
return graph;
|
||||
}
|
||||
|
||||
DirectedGraph BuildDirectedCyclicGraph()
|
||||
{
|
||||
DirectedGraph graph;
|
||||
|
||||
// Inserts edges in a format: <source, target, weight>.
|
||||
graph.AddEdge(0, 1, kWeight);
|
||||
graph.AddEdge(1, 2, kWeight);
|
||||
graph.AddEdge(2, 3, kWeight);
|
||||
graph.AddEdge(3, 4, kWeight);
|
||||
graph.AddEdge(4, 2, kWeight);
|
||||
|
||||
return graph;
|
||||
}
|
||||
|
||||
DirectedGraph BuildSmallDirectedCyclicGraph()
|
||||
{
|
||||
DirectedGraph graph;
|
||||
|
||||
// Inserts edges in a format: <source, target, weight>.
|
||||
graph.AddEdge(0, 1, kWeight);
|
||||
graph.AddEdge(1, 2, kWeight);
|
||||
graph.AddEdge(2, 0, kWeight);
|
||||
|
||||
return graph;
|
||||
}
|
||||
} // namespace
|
||||
|
||||
namespace routing_test
|
||||
{
|
||||
using namespace routing;
|
||||
|
||||
UNIT_TEST(BFS_AllVisit_Undirected)
|
||||
{
|
||||
UndirectedGraph graph = BuildUndirectedGraph();
|
||||
|
||||
std::set<uint32_t> visited;
|
||||
|
||||
BFS<UndirectedGraph> bfs(graph);
|
||||
bfs.Run(0 /* start */, true /* isOutgoing */, [&](BFS<UndirectedGraph>::State const & state)
|
||||
{
|
||||
visited.emplace(state.m_vertex);
|
||||
return true;
|
||||
});
|
||||
|
||||
std::vector<uint32_t> const expectedInVisited = {1, 2, 3, 4, 5, 6, 7, 8, 9, 10};
|
||||
for (auto const v : expectedInVisited)
|
||||
TEST_NOT_EQUAL(visited.count(v), 0, ("vertex =", v, "was not visited."));
|
||||
}
|
||||
|
||||
UNIT_TEST(BFS_AllVisit_Directed_Forward)
|
||||
{
|
||||
DirectedGraph graph = BuildDirectedGraph();
|
||||
|
||||
std::set<uint32_t> visited;
|
||||
|
||||
BFS<DirectedGraph> bfs(graph);
|
||||
bfs.Run(0 /* start */, true /* isOutgoing */, [&](BFS<DirectedGraph>::State const & state)
|
||||
{
|
||||
visited.emplace(state.m_vertex);
|
||||
return true;
|
||||
});
|
||||
|
||||
std::vector<uint32_t> const expectedInVisited = {1, 2, 3, 4};
|
||||
for (auto const v : expectedInVisited)
|
||||
TEST_NOT_EQUAL(visited.count(v), 0, ("vertex =", v, "was not visited."));
|
||||
}
|
||||
|
||||
UNIT_TEST(BFS_AllVisit_Directed_Backward)
|
||||
{
|
||||
DirectedGraph graph = BuildDirectedGraph();
|
||||
|
||||
std::set<uint32_t> visited;
|
||||
|
||||
BFS<DirectedGraph> bfs(graph);
|
||||
bfs.Run(2 /* start */, false /* isOutgoing */, [&](BFS<DirectedGraph>::State const & state)
|
||||
{
|
||||
visited.emplace(state.m_vertex);
|
||||
return true;
|
||||
});
|
||||
|
||||
std::vector<uint32_t> expectedInVisited = {0, 3, 4, 5, 7};
|
||||
for (auto const v : expectedInVisited)
|
||||
TEST_NOT_EQUAL(visited.count(v), 0, ("vertex =", v, "was not visited."));
|
||||
}
|
||||
|
||||
UNIT_TEST(BFS_AllVisit_DirectedCyclic)
|
||||
{
|
||||
DirectedGraph graph = BuildDirectedCyclicGraph();
|
||||
|
||||
std::set<uint32_t> visited;
|
||||
|
||||
BFS<DirectedGraph> bfs(graph);
|
||||
bfs.Run(0 /* start */, true /* isOutgoing */, [&](BFS<DirectedGraph>::State const & state)
|
||||
{
|
||||
visited.emplace(state.m_vertex);
|
||||
return true;
|
||||
});
|
||||
|
||||
std::vector<uint32_t> expectedInVisited = {1, 2, 3, 4};
|
||||
for (auto const v : expectedInVisited)
|
||||
TEST_NOT_EQUAL(visited.count(v), 0, ("vertex =", v, "was not visited."));
|
||||
}
|
||||
|
||||
UNIT_TEST(BFS_ReconstructPathTest)
|
||||
{
|
||||
DirectedGraph graph = BuildSmallDirectedCyclicGraph();
|
||||
|
||||
BFS<DirectedGraph> bfs(graph);
|
||||
bfs.Run(0 /* start */, true /* isOutgoing */, [&](auto const & state) { return true; });
|
||||
|
||||
std::vector<uint32_t> path = bfs.ReconstructPath(2, false /* reverse */);
|
||||
std::vector<uint32_t> expected = {0, 1, 2};
|
||||
TEST_EQUAL(path, expected, ());
|
||||
|
||||
path = bfs.ReconstructPath(2, true /* reverse */);
|
||||
expected = {2, 1, 0};
|
||||
TEST_EQUAL(path, expected, ());
|
||||
}
|
||||
} // namespace routing_test
|
||||
81
libs/routing/routing_tests/checkpoint_predictor_test.cpp
Normal file
81
libs/routing/routing_tests/checkpoint_predictor_test.cpp
Normal file
|
|
@ -0,0 +1,81 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/checkpoint_predictor.hpp"
|
||||
|
||||
#include "geometry/point2d.hpp"
|
||||
|
||||
#include <cstdint>
|
||||
#include <utility>
|
||||
#include <vector>
|
||||
|
||||
namespace checkpoint_predictor_test
|
||||
{
|
||||
void TestAlmostEqual(double v1, double v2)
|
||||
{
|
||||
double constexpr kEpsMeters = 1.0;
|
||||
TEST(AlmostEqualAbs(v1, v2, kEpsMeters), (v1, v2));
|
||||
}
|
||||
|
||||
using routing::CheckpointPredictor;
|
||||
|
||||
class CheckpointPredictorTest
|
||||
{
|
||||
public:
|
||||
CheckpointPredictorTest() : m_predictor({0.0, 0.0} /* start */, {4.0, 0.0} /* finish */) {}
|
||||
|
||||
size_t PredictPosition(std::vector<m2::PointD> const & intermediatePoints, m2::PointD const & point) const
|
||||
{
|
||||
return m_predictor.PredictPosition(intermediatePoints, point);
|
||||
}
|
||||
|
||||
CheckpointPredictor m_predictor;
|
||||
};
|
||||
|
||||
UNIT_CLASS_TEST(CheckpointPredictorTest, CalculateDeltaMetersTest)
|
||||
{
|
||||
TestAlmostEqual(
|
||||
CheckpointPredictor::CalculateDeltaMeters({0.0, 0.0} /* from */, {2.0, 0.0} /* to */, {1.0, 0.0} /* between */),
|
||||
0.0);
|
||||
TestAlmostEqual(
|
||||
CheckpointPredictor::CalculateDeltaMeters({0.0, 0.0} /* from */, {2.0, 0.0} /* to */, {3.0, 0.0} /* between */),
|
||||
222634.0);
|
||||
TestAlmostEqual(
|
||||
CheckpointPredictor::CalculateDeltaMeters({0.0, 0.0} /* from */, {2.0, 0.0} /* to */, {-1.0, 0.0} /* between */),
|
||||
222634.0);
|
||||
}
|
||||
|
||||
// Zero intermediate point test.
|
||||
UNIT_CLASS_TEST(CheckpointPredictorTest, PredictPositionTest1)
|
||||
{
|
||||
std::vector<m2::PointD> const intermediatePoints = {};
|
||||
|
||||
TEST_EQUAL(PredictPosition(intermediatePoints, m2::PointD(-0.5, 0.5)), 0, ());
|
||||
TEST_EQUAL(PredictPosition(intermediatePoints, m2::PointD(1.5, -0.5)), 0, ());
|
||||
TEST_EQUAL(PredictPosition(intermediatePoints, m2::PointD(3.5, 0.7)), 0, ());
|
||||
TEST_EQUAL(PredictPosition(intermediatePoints, m2::PointD(5.0, 0.0)), 0, ());
|
||||
}
|
||||
|
||||
// One intermediate point test.
|
||||
UNIT_CLASS_TEST(CheckpointPredictorTest, PredictPositionTest2)
|
||||
{
|
||||
std::vector<m2::PointD> const intermediatePoints = {{2.0, 0.0}};
|
||||
|
||||
TEST_EQUAL(PredictPosition(intermediatePoints, m2::PointD(-0.5, 0.5)), 0, ());
|
||||
TEST_EQUAL(PredictPosition(intermediatePoints, m2::PointD(1.5, -0.5)), 0, ());
|
||||
TEST_EQUAL(PredictPosition(intermediatePoints, m2::PointD(3.5, 0.7)), 1, ());
|
||||
TEST_EQUAL(PredictPosition(intermediatePoints, m2::PointD(5.0, 0.0)), 1, ());
|
||||
}
|
||||
|
||||
// Three intermediate points test.
|
||||
UNIT_CLASS_TEST(CheckpointPredictorTest, PredictPositionTest3)
|
||||
{
|
||||
std::vector<m2::PointD> const intermediatePoints = {{1.0, 0.0}, {2.0, 0.0}, {3.0, 0.0}};
|
||||
|
||||
TEST_EQUAL(PredictPosition(intermediatePoints, m2::PointD(-0.5, 0.5)), 0, ());
|
||||
TEST_EQUAL(PredictPosition(intermediatePoints, m2::PointD(0.5, 0.5)), 0, ());
|
||||
TEST_EQUAL(PredictPosition(intermediatePoints, m2::PointD(1.5, -0.5)), 1, ());
|
||||
TEST_EQUAL(PredictPosition(intermediatePoints, m2::PointD(2.5, -0.5)), 2, ());
|
||||
TEST_EQUAL(PredictPosition(intermediatePoints, m2::PointD(3.5, 0.7)), 3, ());
|
||||
TEST_EQUAL(PredictPosition(intermediatePoints, m2::PointD(5.0, 0.0)), 3, ());
|
||||
}
|
||||
} // namespace checkpoint_predictor_test
|
||||
106
libs/routing/routing_tests/coding_test.cpp
Normal file
106
libs/routing/routing_tests/coding_test.cpp
Normal file
|
|
@ -0,0 +1,106 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/coding.hpp"
|
||||
|
||||
#include <cstdint>
|
||||
#include <limits>
|
||||
#include <type_traits>
|
||||
|
||||
using namespace routing;
|
||||
|
||||
namespace
|
||||
{
|
||||
template <typename T, typename ToDo>
|
||||
void ForEachNumber(ToDo && toDo)
|
||||
{
|
||||
for (T number = std::numeric_limits<T>::min();; ++number)
|
||||
{
|
||||
toDo(number);
|
||||
|
||||
if (number == std::numeric_limits<T>::max())
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
void TestZigZag(T prev, T current)
|
||||
{
|
||||
auto const delta = EncodeZigZagDelta(prev, current);
|
||||
auto const decodedCurrent = DecodeZigZagDelta(prev, delta);
|
||||
TEST_EQUAL(decodedCurrent, current, ("prev:", prev, "delta:", delta));
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
void TestZigZagUnsigned()
|
||||
{
|
||||
static_assert(std::is_unsigned<T>::value, "T should be an unsigned type");
|
||||
|
||||
constexpr auto max = std::numeric_limits<T>::max();
|
||||
constexpr T values[] = {0, 1, 7, max / 2, max - 1, max};
|
||||
for (T prev : values)
|
||||
for (T current : values)
|
||||
TestZigZag(prev, current);
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
void TestZigZagSigned()
|
||||
{
|
||||
static_assert(std::is_signed<T>::value, "T should be a signed type");
|
||||
|
||||
constexpr auto min = std::numeric_limits<T>::min();
|
||||
constexpr auto max = std::numeric_limits<T>::max();
|
||||
constexpr T values[] = {min, min + 1, min / 2, -7, -1, 0, 1, 7, max / 2, max - 1, max};
|
||||
for (T prev : values)
|
||||
for (T current : values)
|
||||
TestZigZag(prev, current);
|
||||
}
|
||||
} // namespace
|
||||
|
||||
namespace routing_test
|
||||
{
|
||||
UNIT_TEST(ModuleCastTest)
|
||||
{
|
||||
ForEachNumber<uint8_t>([](uint8_t number)
|
||||
{
|
||||
auto signedNumber = ModularCast(number);
|
||||
static_assert(std::is_same<decltype(signedNumber), int8_t>::value, "int8_t expected");
|
||||
TEST_EQUAL(static_cast<uint8_t>(signedNumber), number, ("signedNumber:", signedNumber));
|
||||
});
|
||||
}
|
||||
|
||||
UNIT_TEST(ZigZagUint8)
|
||||
{
|
||||
ForEachNumber<uint8_t>([](uint8_t prev)
|
||||
{ ForEachNumber<uint8_t>([&](uint8_t current) { TestZigZag(prev, current); }); });
|
||||
}
|
||||
|
||||
UNIT_TEST(ZigZagInt8)
|
||||
{
|
||||
ForEachNumber<int8_t>([](int8_t prev) { ForEachNumber<int8_t>([&](int8_t current) { TestZigZag(prev, current); }); });
|
||||
}
|
||||
|
||||
UNIT_TEST(ZigZagUint16)
|
||||
{
|
||||
TestZigZagUnsigned<uint16_t>();
|
||||
}
|
||||
UNIT_TEST(ZigZagInt16)
|
||||
{
|
||||
TestZigZagSigned<int16_t>();
|
||||
}
|
||||
UNIT_TEST(ZigZagUint32)
|
||||
{
|
||||
TestZigZagUnsigned<uint32_t>();
|
||||
}
|
||||
UNIT_TEST(ZigZagInt32)
|
||||
{
|
||||
TestZigZagSigned<int32_t>();
|
||||
}
|
||||
UNIT_TEST(ZigZagUint64)
|
||||
{
|
||||
TestZigZagUnsigned<uint64_t>();
|
||||
}
|
||||
UNIT_TEST(ZigZagInt64)
|
||||
{
|
||||
TestZigZagSigned<int64_t>();
|
||||
}
|
||||
} // namespace routing_test
|
||||
139
libs/routing/routing_tests/cross_border_graph_tests.cpp
Normal file
139
libs/routing/routing_tests/cross_border_graph_tests.cpp
Normal file
|
|
@ -0,0 +1,139 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/cross_border_graph.hpp"
|
||||
|
||||
#include "storage/routing_helpers.hpp"
|
||||
#include "storage/storage.hpp"
|
||||
|
||||
#include "routing_common/num_mwm_id.hpp"
|
||||
|
||||
#include "platform/platform.hpp"
|
||||
|
||||
#include "coding/file_reader.hpp"
|
||||
#include "coding/file_writer.hpp"
|
||||
|
||||
#include "geometry/distance_on_sphere.hpp"
|
||||
#include "geometry/latlon.hpp"
|
||||
|
||||
#include <algorithm>
|
||||
#include <cstdint>
|
||||
#include <memory>
|
||||
#include <string>
|
||||
#include <utility>
|
||||
|
||||
namespace routing
|
||||
{
|
||||
// Test for serializing/deserializing of the chain of 4 points passing through 4 mwms:
|
||||
// *-------------------------*-------------------------*-------------------------*
|
||||
// p1 p2 p3 p4
|
||||
|
||||
std::pair<ms::LatLon, NumMwmId> GetCoordInRegion(double lat, double lon, std::string const & region,
|
||||
std::shared_ptr<NumMwmIds> numMwmIds)
|
||||
{
|
||||
return {ms::LatLon(lat, lon), numMwmIds->GetId(platform::CountryFile(region))};
|
||||
}
|
||||
|
||||
void FillGraphWithTestInfo(CrossBorderGraph & gaph, std::shared_ptr<NumMwmIds> numMwmIds)
|
||||
{
|
||||
auto const [p1, id1] = GetCoordInRegion(50.88010, 4.41923, "Belgium_Flemish Brabant", numMwmIds);
|
||||
auto const [p2, id2] = GetCoordInRegion(50.99043, 5.48125, "Belgium_Limburg", numMwmIds);
|
||||
auto const [p3, id3] = GetCoordInRegion(50.88751, 5.92378, "Netherlands_Limburg", numMwmIds);
|
||||
auto const [p4, id4] =
|
||||
GetCoordInRegion(50.8734, 6.27417, "Germany_North Rhine-Westphalia_Regierungsbezirk Koln_Aachen", numMwmIds);
|
||||
|
||||
double constexpr avgSpeedMpS = 14.0;
|
||||
|
||||
CrossBorderSegment d12;
|
||||
d12.m_weight = ms::DistanceOnEarth(p1, p2) / avgSpeedMpS;
|
||||
d12.m_start = CrossBorderSegmentEnding(p1, id1);
|
||||
d12.m_end = CrossBorderSegmentEnding(p2, id2);
|
||||
gaph.m_segments.emplace(10, d12);
|
||||
|
||||
CrossBorderSegment d23;
|
||||
d23.m_weight = ms::DistanceOnEarth(p2, p3) / avgSpeedMpS;
|
||||
d23.m_start = CrossBorderSegmentEnding(p2, id2);
|
||||
d23.m_end = CrossBorderSegmentEnding(p3, id3);
|
||||
gaph.m_segments.emplace(20, d23);
|
||||
|
||||
CrossBorderSegment d34;
|
||||
d34.m_weight = ms::DistanceOnEarth(p3, p4) / avgSpeedMpS;
|
||||
d34.m_start = CrossBorderSegmentEnding(p3, id3);
|
||||
d34.m_end = CrossBorderSegmentEnding(p4, id4);
|
||||
gaph.m_segments.emplace(30, d34);
|
||||
|
||||
gaph.m_mwms.emplace(id1, std::vector<RegionSegmentId>{10});
|
||||
gaph.m_mwms.emplace(id2, std::vector<RegionSegmentId>{10, 20});
|
||||
gaph.m_mwms.emplace(id3, std::vector<RegionSegmentId>{20, 30});
|
||||
gaph.m_mwms.emplace(id4, std::vector<RegionSegmentId>{30});
|
||||
}
|
||||
|
||||
template <class T>
|
||||
T GetSorted(T const & cont)
|
||||
{
|
||||
auto contSorted = cont;
|
||||
std::sort(contSorted.begin(), contSorted.end());
|
||||
return contSorted;
|
||||
}
|
||||
|
||||
void TestEqualMwm(MwmIdToSegmentIds const & mwmIds1, MwmIdToSegmentIds const & mwmIds2)
|
||||
{
|
||||
TEST_EQUAL(mwmIds1.size(), mwmIds2.size(), ());
|
||||
|
||||
for (auto const & [mwmId, segIds] : mwmIds1)
|
||||
{
|
||||
auto itMwmId = mwmIds2.find(mwmId);
|
||||
TEST(itMwmId != mwmIds2.end(), ());
|
||||
TEST_EQUAL(GetSorted(segIds), GetSorted(itMwmId->second), ());
|
||||
}
|
||||
}
|
||||
|
||||
void TestEqualSegments(CrossBorderSegments const & s1, CrossBorderSegments const & s2)
|
||||
{
|
||||
TEST_EQUAL(s1.size(), s2.size(), ());
|
||||
|
||||
for (auto const & [segId1, data1] : s1)
|
||||
{
|
||||
auto itSegId = s2.find(segId1);
|
||||
TEST(itSegId != s2.end(), ());
|
||||
|
||||
auto const & data2 = itSegId->second;
|
||||
|
||||
static double constexpr epsCoord = 1e-5;
|
||||
|
||||
TEST(AlmostEqualAbs(data1.m_start.m_point.GetLatLon(), data2.m_start.m_point.GetLatLon(), epsCoord), ());
|
||||
TEST(AlmostEqualAbs(data1.m_end.m_point.GetLatLon(), data2.m_end.m_point.GetLatLon(), epsCoord), ());
|
||||
TEST_EQUAL(static_cast<uint32_t>(std::ceil(data1.m_weight)), static_cast<uint32_t>(std::ceil(data2.m_weight)), ());
|
||||
}
|
||||
}
|
||||
|
||||
UNIT_TEST(CrossBorderGraph_SerDes)
|
||||
{
|
||||
std::string const fileName = "CrossBorderGraph_SerDes.test";
|
||||
|
||||
storage::Storage storage;
|
||||
std::shared_ptr<NumMwmIds> numMwmIds = CreateNumMwmIds(storage);
|
||||
|
||||
CrossBorderGraph graph1;
|
||||
FillGraphWithTestInfo(graph1, numMwmIds);
|
||||
|
||||
{
|
||||
FilesContainerW cont(fileName, FileWriter::OP_WRITE_TRUNCATE);
|
||||
auto writer = cont.GetWriter(ROUTING_WORLD_FILE_TAG);
|
||||
CrossBorderGraphSerializer::Serialize(graph1, writer, numMwmIds);
|
||||
}
|
||||
|
||||
uint64_t sizeBytes;
|
||||
CHECK(GetPlatform().GetFileSizeByFullPath(fileName, sizeBytes), (fileName, sizeBytes));
|
||||
LOG(LINFO, ("File size:", sizeBytes, "bytes"));
|
||||
|
||||
FilesContainerR cont(fileName);
|
||||
auto src = std::make_unique<FilesContainerR::TReader>(cont.GetReader(ROUTING_WORLD_FILE_TAG));
|
||||
ReaderSource<FilesContainerR::TReader> reader(*src);
|
||||
|
||||
CrossBorderGraph graph2;
|
||||
CrossBorderGraphSerializer::Deserialize(graph2, reader, numMwmIds);
|
||||
|
||||
TestEqualMwm(graph1.m_mwms, graph2.m_mwms);
|
||||
TestEqualSegments(graph1.m_segments, graph2.m_segments);
|
||||
}
|
||||
} // namespace routing
|
||||
348
libs/routing/routing_tests/cross_mwm_connector_test.cpp
Normal file
348
libs/routing/routing_tests/cross_mwm_connector_test.cpp
Normal file
|
|
@ -0,0 +1,348 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/cross_mwm_connector_serialization.hpp"
|
||||
#include "routing/cross_mwm_ids.hpp"
|
||||
|
||||
#include "coding/writer.hpp"
|
||||
|
||||
#include "base/geo_object_id.hpp"
|
||||
|
||||
namespace cross_mwm_connector_test
|
||||
{
|
||||
using namespace routing;
|
||||
using namespace routing::connector;
|
||||
using namespace std;
|
||||
|
||||
namespace
|
||||
{
|
||||
NumMwmId constexpr kTestMwmId = 777;
|
||||
|
||||
template <typename CrossMwmId>
|
||||
struct CrossMwmBuilderTestFixture
|
||||
{
|
||||
CrossMwmConnector<CrossMwmId> connector;
|
||||
CrossMwmConnectorBuilder<CrossMwmId> builder;
|
||||
|
||||
explicit CrossMwmBuilderTestFixture(NumMwmId numMwmId = kTestMwmId) : connector(numMwmId), builder(connector) {}
|
||||
};
|
||||
|
||||
template <typename CrossMwmId>
|
||||
void TestConnectorConsistency(CrossMwmConnector<CrossMwmId> const & connector)
|
||||
{
|
||||
connector.ForEachEnter([&connector](uint32_t, Segment const & enter)
|
||||
{
|
||||
TEST(connector.IsTransition(enter, false /* isOutgoing */), ("enter:", enter));
|
||||
TEST(!connector.IsTransition(enter, true /* isOutgoing */), ("enter:", enter));
|
||||
});
|
||||
|
||||
connector.ForEachExit([&connector](uint32_t, Segment const & exit)
|
||||
{
|
||||
TEST(!connector.IsTransition(exit, false /* isOutgoing */), ("exit:", exit));
|
||||
TEST(connector.IsTransition(exit, true /* isOutgoing */), ("exit:", exit));
|
||||
});
|
||||
}
|
||||
|
||||
template <typename CrossMwmId>
|
||||
void TestOutgoingEdges(CrossMwmConnector<CrossMwmId> const & connector, Segment const & from,
|
||||
vector<SegmentEdge> const & expectedEdges)
|
||||
{
|
||||
typename CrossMwmConnector<CrossMwmId>::EdgeListT edges;
|
||||
connector.GetOutgoingEdgeList(from, edges);
|
||||
|
||||
TEST_EQUAL(edges.size(), expectedEdges.size(), ());
|
||||
for (size_t i = 0; i < edges.size(); ++i)
|
||||
TEST_EQUAL(edges[i], expectedEdges[i], ());
|
||||
}
|
||||
|
||||
template <typename CrossMwmId>
|
||||
void TestOneWayEnter(CrossMwmId const & crossMwmId)
|
||||
{
|
||||
uint32_t constexpr featureId = 1;
|
||||
uint32_t constexpr segmentIdx = 1;
|
||||
|
||||
CrossMwmBuilderTestFixture<CrossMwmId> test;
|
||||
test.builder.AddTransition(crossMwmId, featureId, segmentIdx, true /* oneWay */, true /* forwardIsEnter */);
|
||||
|
||||
TestConnectorConsistency(test.connector);
|
||||
TEST_EQUAL(test.connector.GetNumEnters(), 1, ());
|
||||
TEST_EQUAL(test.connector.GetNumExits(), 0, ());
|
||||
TEST(!test.connector.IsTransition(Segment(kTestMwmId, featureId, segmentIdx, true /* forward */),
|
||||
true /* isOutgoing */),
|
||||
());
|
||||
TEST(test.connector.IsTransition(Segment(kTestMwmId, featureId, segmentIdx, true /* forward */),
|
||||
false /* isOutgoing */),
|
||||
());
|
||||
TEST(!test.connector.IsTransition(Segment(kTestMwmId, featureId, segmentIdx, false /* forward */),
|
||||
true /* isOutgoing */),
|
||||
());
|
||||
TEST(!test.connector.IsTransition(Segment(kTestMwmId, featureId, segmentIdx, false /* forward */),
|
||||
false /* isOutgoing */),
|
||||
());
|
||||
}
|
||||
|
||||
template <typename CrossMwmId>
|
||||
void TestOneWayExit(CrossMwmId const & crossMwmId)
|
||||
{
|
||||
uint32_t constexpr featureId = 1;
|
||||
uint32_t constexpr segmentIdx = 1;
|
||||
|
||||
CrossMwmBuilderTestFixture<CrossMwmId> test;
|
||||
test.builder.AddTransition(crossMwmId, featureId, segmentIdx, true /* oneWay */, false /* forwardIsEnter */);
|
||||
|
||||
TestConnectorConsistency(test.connector);
|
||||
TEST_EQUAL(test.connector.GetNumEnters(), 0, ());
|
||||
TEST_EQUAL(test.connector.GetNumExits(), 1, ());
|
||||
TEST(test.connector.IsTransition(Segment(kTestMwmId, featureId, segmentIdx, true /* forward */),
|
||||
true /* isOutgoing */),
|
||||
());
|
||||
TEST(!test.connector.IsTransition(Segment(kTestMwmId, featureId, segmentIdx, true /* forward */),
|
||||
false /* isOutgoing */),
|
||||
());
|
||||
TEST(!test.connector.IsTransition(Segment(kTestMwmId, featureId, segmentIdx, false /* forward */),
|
||||
true /* isOutgoing */),
|
||||
());
|
||||
TEST(!test.connector.IsTransition(Segment(kTestMwmId, featureId, segmentIdx, false /* forward */),
|
||||
false /* isOutgoing */),
|
||||
());
|
||||
}
|
||||
|
||||
template <typename CrossMwmId>
|
||||
void TestTwoWayEnter(CrossMwmId const & crossMwmId)
|
||||
{
|
||||
uint32_t constexpr featureId = 1;
|
||||
uint32_t constexpr segmentIdx = 1;
|
||||
|
||||
CrossMwmBuilderTestFixture<CrossMwmId> test;
|
||||
test.builder.AddTransition(crossMwmId, featureId, segmentIdx, false /* oneWay */, true /* forwardIsEnter */);
|
||||
|
||||
TestConnectorConsistency(test.connector);
|
||||
TEST_EQUAL(test.connector.GetNumEnters(), 1, ());
|
||||
TEST_EQUAL(test.connector.GetNumExits(), 1, ());
|
||||
TEST(!test.connector.IsTransition(Segment(kTestMwmId, featureId, segmentIdx, true /* forward */),
|
||||
true /* isOutgoing */),
|
||||
());
|
||||
TEST(test.connector.IsTransition(Segment(kTestMwmId, featureId, segmentIdx, true /* forward */),
|
||||
false /* isOutgoing */),
|
||||
());
|
||||
TEST(test.connector.IsTransition(Segment(kTestMwmId, featureId, segmentIdx, false /* forward */),
|
||||
true /* isOutgoing */),
|
||||
());
|
||||
TEST(!test.connector.IsTransition(Segment(kTestMwmId, featureId, segmentIdx, false /* forward */),
|
||||
false /* isOutgoing */),
|
||||
());
|
||||
}
|
||||
|
||||
template <typename CrossMwmId>
|
||||
void TestTwoWayExit(CrossMwmId const & crossMwmId)
|
||||
{
|
||||
uint32_t constexpr featureId = 1;
|
||||
uint32_t constexpr segmentIdx = 1;
|
||||
|
||||
CrossMwmBuilderTestFixture<CrossMwmId> test;
|
||||
test.builder.AddTransition(crossMwmId, featureId, segmentIdx, false /* oneWay */, false /* forwardIsEnter */);
|
||||
|
||||
TestConnectorConsistency(test.connector);
|
||||
TEST_EQUAL(test.connector.GetNumEnters(), 1, ());
|
||||
TEST_EQUAL(test.connector.GetNumExits(), 1, ());
|
||||
TEST(test.connector.IsTransition(Segment(kTestMwmId, featureId, segmentIdx, true /* forward */),
|
||||
true /* isOutgoing */),
|
||||
());
|
||||
TEST(!test.connector.IsTransition(Segment(kTestMwmId, featureId, segmentIdx, true /* forward */),
|
||||
false /* isOutgoing */),
|
||||
());
|
||||
TEST(!test.connector.IsTransition(Segment(kTestMwmId, featureId, segmentIdx, false /* forward */),
|
||||
true /* isOutgoing */),
|
||||
());
|
||||
TEST(test.connector.IsTransition(Segment(kTestMwmId, featureId, segmentIdx, false /* forward */),
|
||||
false /* isOutgoing */),
|
||||
());
|
||||
}
|
||||
|
||||
template <typename CrossMwmId>
|
||||
void TestSerialization(CrossMwmConnectorBuilderEx<CrossMwmId> & builder)
|
||||
{
|
||||
double constexpr kEdgesWeight = 4444.0;
|
||||
|
||||
vector<uint8_t> buffer;
|
||||
builder.PrepareConnector(VehicleType::Car);
|
||||
builder.FillWeights([&](Segment const &, Segment const &) { return kEdgesWeight; });
|
||||
|
||||
MemWriter<vector<uint8_t>> writer(buffer);
|
||||
builder.Serialize(writer);
|
||||
|
||||
MemReader reader(buffer.data(), buffer.size());
|
||||
|
||||
CrossMwmBuilderTestFixture<CrossMwmId> test;
|
||||
|
||||
test.builder.DeserializeTransitions(VehicleType::Car, reader);
|
||||
|
||||
TestConnectorConsistency(test.connector);
|
||||
|
||||
TEST_EQUAL(test.connector.GetNumEnters(), 2, ());
|
||||
TEST_EQUAL(test.connector.GetNumExits(), 1, ());
|
||||
|
||||
TEST(!test.connector.IsTransition(Segment(kTestMwmId, 0, 0, true), true /* isOutgoing */), ());
|
||||
|
||||
TEST(!test.connector.IsTransition(Segment(kTestMwmId, 10, 1, true /* forward */), true /* isOutgoing */), ());
|
||||
TEST(test.connector.IsTransition(Segment(kTestMwmId, 10, 1, true /* forward */), false /* isOutgoing */), ());
|
||||
TEST(!test.connector.IsTransition(Segment(kTestMwmId, 10, 1, false /* forward */), true /* isOutgoing */), ());
|
||||
TEST(!test.connector.IsTransition(Segment(kTestMwmId, 10, 1, false /* forward */), false /* isOutgoing */), ());
|
||||
|
||||
TEST(!test.connector.IsTransition(Segment(kTestMwmId, 20, 2, true /* forward */), true /* isOutgoing */), ());
|
||||
TEST(test.connector.IsTransition(Segment(kTestMwmId, 20, 2, true /* forward */), false /* isOutgoing */), ());
|
||||
TEST(test.connector.IsTransition(Segment(kTestMwmId, 20, 2, false /* forward */), true /* isOutgoing */), ());
|
||||
TEST(!test.connector.IsTransition(Segment(kTestMwmId, 20, 2, false /* forward */), false /* isOutgoing */), ());
|
||||
|
||||
TEST(!test.connector.IsTransition(Segment(kTestMwmId, 30, 3, true /* forward */), true /* isOutgoing */), ());
|
||||
|
||||
TEST(!test.connector.WeightsWereLoaded(), ());
|
||||
TEST(!test.connector.HasWeights(), ());
|
||||
|
||||
test.builder.DeserializeWeights(reader);
|
||||
|
||||
TEST(test.connector.WeightsWereLoaded(), ());
|
||||
TEST(test.connector.HasWeights(), ());
|
||||
|
||||
TestOutgoingEdges(test.connector, Segment(kTestMwmId, 10, 1, true /* forward */),
|
||||
{{Segment(kTestMwmId, 20, 2, false /* forward */), RouteWeight::FromCrossMwmWeight(kEdgesWeight)}});
|
||||
|
||||
TestOutgoingEdges(test.connector, Segment(kTestMwmId, 20, 2, true /* forward */),
|
||||
{{Segment(kTestMwmId, 20, 2, false /* forward */), RouteWeight::FromCrossMwmWeight(kEdgesWeight)}});
|
||||
}
|
||||
|
||||
void GetCrossMwmId(uint32_t i, base::GeoObjectId & id)
|
||||
{
|
||||
id = base::GeoObjectId(base::MakeOsmWay(10 * i));
|
||||
}
|
||||
|
||||
void GetCrossMwmId(uint32_t i, TransitId & id)
|
||||
{
|
||||
id = TransitId(1 /* stop 1 id */, 10 * i /* stop 1 id */, 1 /* line id */);
|
||||
}
|
||||
|
||||
template <typename CrossMwmId>
|
||||
void TestWeightsSerialization()
|
||||
{
|
||||
size_t constexpr kNumTransitions = 3;
|
||||
uint32_t constexpr segmentIdx = 1;
|
||||
double const weights[] = {4.0, 20.0, connector::kNoRoute, 12.0, connector::kNoRoute, 40.0, 48.0, 24.0, 12.0};
|
||||
TEST_EQUAL(std::size(weights), kNumTransitions * kNumTransitions, ());
|
||||
|
||||
std::map<std::pair<Segment, Segment>, double> expectedWeights;
|
||||
|
||||
vector<uint8_t> buffer;
|
||||
{
|
||||
CrossMwmConnectorBuilderEx<CrossMwmId> builder;
|
||||
for (uint32_t featureId : {2, 0, 1}) // reshuffled
|
||||
{
|
||||
CrossMwmId id;
|
||||
GetCrossMwmId(featureId, id);
|
||||
builder.AddTransition(id, featureId, segmentIdx, kCarMask, 0 /* oneWayMask */, true /* forwardIsEnter */);
|
||||
}
|
||||
|
||||
builder.PrepareConnector(VehicleType::Car);
|
||||
|
||||
size_t weightIdx = 0;
|
||||
builder.FillWeights([&](Segment const & enter, Segment const & exit)
|
||||
{
|
||||
double const w = weights[weightIdx++];
|
||||
TEST(expectedWeights.insert({{enter, exit}, w}).second, ());
|
||||
return w;
|
||||
});
|
||||
|
||||
MemWriter<vector<uint8_t>> writer(buffer);
|
||||
builder.Serialize(writer);
|
||||
}
|
||||
|
||||
MemReader reader(buffer.data(), buffer.size());
|
||||
|
||||
NumMwmId const mwmId = kGeneratorMwmId;
|
||||
CrossMwmBuilderTestFixture<CrossMwmId> test(mwmId);
|
||||
|
||||
test.builder.DeserializeTransitions(VehicleType::Car, reader);
|
||||
|
||||
TestConnectorConsistency(test.connector);
|
||||
|
||||
TEST_EQUAL(test.connector.GetNumEnters(), kNumTransitions, ());
|
||||
TEST_EQUAL(test.connector.GetNumExits(), kNumTransitions, ());
|
||||
|
||||
TEST(!test.connector.WeightsWereLoaded(), ());
|
||||
TEST(!test.connector.HasWeights(), ());
|
||||
|
||||
test.builder.DeserializeWeights(reader);
|
||||
|
||||
TEST(test.connector.WeightsWereLoaded(), ());
|
||||
TEST(test.connector.HasWeights(), ());
|
||||
|
||||
for (uint32_t enterId = 0; enterId < kNumTransitions; ++enterId)
|
||||
{
|
||||
vector<SegmentEdge> expectedEdges;
|
||||
|
||||
Segment const enter(mwmId, enterId, segmentIdx, true /* forward */);
|
||||
for (uint32_t exitId = 0; exitId < kNumTransitions; ++exitId)
|
||||
{
|
||||
Segment const exit(mwmId, exitId, segmentIdx, false /* forward */);
|
||||
|
||||
auto const it = expectedWeights.find({enter, exit});
|
||||
TEST(it != expectedWeights.end(), ());
|
||||
if (it->second != connector::kNoRoute)
|
||||
expectedEdges.emplace_back(exit, RouteWeight::FromCrossMwmWeight(it->second));
|
||||
}
|
||||
|
||||
TestOutgoingEdges(test.connector, enter, expectedEdges);
|
||||
}
|
||||
}
|
||||
} // namespace
|
||||
|
||||
UNIT_TEST(CMWMC_OneWayEnter)
|
||||
{
|
||||
TestOneWayEnter(base::MakeOsmWay(1ULL));
|
||||
TestOneWayEnter(TransitId(1 /* stop 1 id */, 2 /* stop 2 id */, 1 /* line id */));
|
||||
}
|
||||
|
||||
UNIT_TEST(CMWMC_OneWayExit)
|
||||
{
|
||||
TestOneWayExit(base::MakeOsmWay(1ULL));
|
||||
TestOneWayExit(TransitId(1 /* stop 1 id */, 2 /* stop 2 id */, 1 /* line id */));
|
||||
}
|
||||
|
||||
UNIT_TEST(CMWMC_TwoWayEnter)
|
||||
{
|
||||
TestTwoWayEnter(base::MakeOsmWay(1ULL));
|
||||
TestTwoWayEnter(TransitId(1 /* stop 1 id */, 2 /* stop 2 id */, 1 /* line id */));
|
||||
}
|
||||
|
||||
UNIT_TEST(CMWMC_TwoWayExit)
|
||||
{
|
||||
TestTwoWayExit(base::MakeOsmWay(1ULL));
|
||||
TestTwoWayExit(TransitId(1 /* stop 1 id */, 2 /* stop 2 id */, 1 /* line id */));
|
||||
}
|
||||
|
||||
UNIT_TEST(CMWMC_Serialization)
|
||||
{
|
||||
{
|
||||
CrossMwmConnectorBuilderEx<base::GeoObjectId> builder;
|
||||
// osmId featureId, segmentIdx, roadMask, oneWayMask, forwardIsEnter
|
||||
builder.AddTransition(base::MakeOsmWay(100ULL), 10, 1, kCarMask, kCarMask, true);
|
||||
builder.AddTransition(base::MakeOsmWay(200ULL), 20, 2, kCarMask, 0, true);
|
||||
builder.AddTransition(base::MakeOsmWay(300ULL), 30, 3, kPedestrianMask, kCarMask, true);
|
||||
TestSerialization(builder);
|
||||
}
|
||||
|
||||
{
|
||||
CrossMwmConnectorBuilderEx<TransitId> builder;
|
||||
// osmId featureId, segmentIdx, roadMask, oneWayMask, forwardIsEnter
|
||||
builder.AddTransition(TransitId(1ULL /* stop 1 id */, 2ULL /* stop 2 id */, 1ULL /* line id */), 10, 1, kCarMask,
|
||||
kCarMask, true);
|
||||
builder.AddTransition(TransitId(1ULL, 3ULL, 1ULL), 20, 2, kCarMask, 0, true);
|
||||
builder.AddTransition(TransitId(1ULL, 3ULL, 2ULL), 30, 3, kPedestrianMask, kCarMask, true);
|
||||
TestSerialization(builder);
|
||||
}
|
||||
}
|
||||
|
||||
UNIT_TEST(CMWMC_WeightsSerialization)
|
||||
{
|
||||
TestWeightsSerialization<base::GeoObjectId>();
|
||||
TestWeightsSerialization<TransitId>();
|
||||
}
|
||||
} // namespace cross_mwm_connector_test
|
||||
353
libs/routing/routing_tests/cumulative_restriction_test.cpp
Normal file
353
libs/routing/routing_tests/cumulative_restriction_test.cpp
Normal file
|
|
@ -0,0 +1,353 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "generator/generator_tests_support/routing_helpers.hpp"
|
||||
|
||||
#include "routing/routing_tests/index_graph_tools.hpp"
|
||||
|
||||
#include "routing/fake_ending.hpp"
|
||||
#include "routing/geometry.hpp"
|
||||
#include "routing/restriction_loader.hpp"
|
||||
|
||||
#include "traffic/traffic_cache.hpp"
|
||||
|
||||
#include "routing_common/car_model.hpp"
|
||||
|
||||
#include "geometry/point2d.hpp"
|
||||
|
||||
#include <memory>
|
||||
#include <utility>
|
||||
#include <vector>
|
||||
|
||||
namespace cumulative_restriction_test
|
||||
{
|
||||
using namespace routing;
|
||||
using namespace routing_test;
|
||||
using namespace std;
|
||||
|
||||
// Finish
|
||||
// 3 *
|
||||
// ^
|
||||
// F5
|
||||
// |
|
||||
// 2 * *
|
||||
// ↖ ↗ ↖
|
||||
// F2 F3 F4
|
||||
// ↖ ↗ ↖
|
||||
// 1 * *
|
||||
// ↗ ↖
|
||||
// F0 F1
|
||||
// ↗ ↖
|
||||
// 0 * *
|
||||
// 0 1 2 3
|
||||
// Start
|
||||
// Note. This graph contains of 6 one segment directed features.
|
||||
unique_ptr<SingleVehicleWorldGraph> BuildXYGraph()
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
loader->AddRoad(0 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 0.0}, {1.0, 1.0}}));
|
||||
loader->AddRoad(1 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 0.0}, {1.0, 1.0}}));
|
||||
loader->AddRoad(2 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 1.0}, {0.0, 2.0}}));
|
||||
loader->AddRoad(3 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 1.0}, {2.0, 2.0}}));
|
||||
loader->AddRoad(4 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{3.0, 1.0}, {2.0, 2.0}}));
|
||||
loader->AddRoad(5 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 2.0}, {2.0, 3.0}}));
|
||||
|
||||
vector<Joint> const joints = {
|
||||
MakeJoint({{0 /* feature id */, 0 /* point id */}}), /* joint at point (0, 0) */
|
||||
MakeJoint({{1, 0}}), /* joint at point (2, 0) */
|
||||
MakeJoint({{0, 1}, {1, 1}, {2, 0}, {3, 0}}), /* joint at point (1, 1) */
|
||||
MakeJoint({{2, 1}}), /* joint at point (0, 2) */
|
||||
MakeJoint({{3, 1}, {4, 1}, {5, 0}}), /* joint at point (2, 2) */
|
||||
MakeJoint({{4, 0}}), /* joint at point (3, 1) */
|
||||
MakeJoint({{5, 1}}), /* joint at point (2, 3) */
|
||||
};
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
return BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
}
|
||||
|
||||
using Algorithm = AStarAlgorithm<Segment, SegmentEdge, RouteWeight>;
|
||||
|
||||
// Route through XY graph without any restrictions.
|
||||
UNIT_TEST(XYGraph)
|
||||
{
|
||||
unique_ptr<WorldGraph> graph = BuildXYGraph();
|
||||
auto const start = MakeFakeEnding(1 /* featureId */, 0 /* segmentIdx */, m2::PointD(2, 0), *graph);
|
||||
auto const finish = MakeFakeEnding(5, 0, m2::PointD(2, 3), *graph);
|
||||
auto starter = MakeStarter(start, finish, *graph);
|
||||
vector<m2::PointD> const expectedGeom = {{2 /* x */, 0 /* y */}, {1, 1}, {2, 2}, {2, 3}};
|
||||
TestRouteGeometry(*starter, Algorithm::Result::OK, expectedGeom);
|
||||
}
|
||||
|
||||
// Route through XY graph with one restriciton (type only) from F1 to F3.
|
||||
UNIT_CLASS_TEST(RestrictionTest, XYGraph_RestrictionF1F3Only)
|
||||
{
|
||||
Init(BuildXYGraph());
|
||||
RestrictionVec restrictionsOnly = {{1 /* feature from */, 3 /* feature to */}};
|
||||
RestrictionVec restrictionsNo;
|
||||
ConvertRestrictionsOnlyToNo(m_graph->GetIndexGraphForTests(kTestNumMwmId), restrictionsOnly, restrictionsNo);
|
||||
|
||||
vector<m2::PointD> const expectedGeom = {{2 /* x */, 0 /* y */}, {1, 1}, {2, 2}, {2, 3}};
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(1 /* featureId */, 0 /* segmentIdx */, m2::PointD(2, 0), *m_graph),
|
||||
MakeFakeEnding(5, 0, m2::PointD(2, 3), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
// Route through XY graph with one restriction (type only) from F3 to F5.
|
||||
UNIT_CLASS_TEST(RestrictionTest, XYGraph_RestrictionF3F5Only)
|
||||
{
|
||||
Init(BuildXYGraph());
|
||||
RestrictionVec restrictionsOnly = {{3 /* feature from */, 5 /* feature to */}};
|
||||
RestrictionVec restrictionsNo;
|
||||
ConvertRestrictionsOnlyToNo(m_graph->GetIndexGraphForTests(kTestNumMwmId), restrictionsOnly, restrictionsNo);
|
||||
|
||||
vector<m2::PointD> const expectedGeom = {{2 /* x */, 0 /* y */}, {1, 1}, {2, 2}, {2, 3}};
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(1 /* featureId */, 0 /* segmentIdx */, m2::PointD(2, 0), *m_graph),
|
||||
MakeFakeEnding(5, 0, m2::PointD(2, 3), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
// Cumulative case. Route through XY graph with two restricitons (type only) applying
|
||||
// in all possible orders.
|
||||
UNIT_CLASS_TEST(RestrictionTest, XYGraph_PermutationsF3F5OnlyF1F3Only)
|
||||
{
|
||||
Init(BuildXYGraph());
|
||||
RestrictionVec restrictionsOnly = {{1 /* feature from */, 3 /* feature to */},
|
||||
{3 /* feature from */, 5 /* feature to */}};
|
||||
RestrictionVec restrictionsNo;
|
||||
ConvertRestrictionsOnlyToNo(m_graph->GetIndexGraphForTests(kTestNumMwmId), restrictionsOnly, restrictionsNo);
|
||||
|
||||
vector<m2::PointD> const expectedGeom = {{2 /* x */, 0 /* y */}, {1, 1}, {2, 2}, {2, 3}};
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(1 /* featureId */, 0 /* segmentIdx */, m2::PointD(2, 0), *m_graph),
|
||||
MakeFakeEnding(5, 0, m2::PointD(2, 3), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
// Cumulative case. Route through XY graph with two restricitons (type only and type no) applying
|
||||
// in all possible orders.
|
||||
UNIT_CLASS_TEST(RestrictionTest, XYGraph_PermutationsF3F5OnlyAndF0F2No)
|
||||
{
|
||||
Init(BuildXYGraph());
|
||||
|
||||
RestrictionVec restrictionsNo = {{1 /* feature from */, 2 /* feature to */}};
|
||||
|
||||
RestrictionVec restrictionsOnly = {{3 /* feature from */, 5 /* feature to */}};
|
||||
ConvertRestrictionsOnlyToNo(m_graph->GetIndexGraphForTests(kTestNumMwmId), restrictionsOnly, restrictionsNo);
|
||||
|
||||
vector<m2::PointD> const expectedGeom = {{2 /* x */, 0 /* y */}, {1, 1}, {2, 2}, {2, 3}};
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(1 /* featureId */, 0 /* segmentIdx */, m2::PointD(2, 0), *m_graph),
|
||||
MakeFakeEnding(5, 0, m2::PointD(2, 3), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
// Cumulative case. Trying to build route through XY graph with two restricitons applying
|
||||
// according to the order. First from F3 to F5 (type only)
|
||||
// and then and from F1 to F3 (type no).
|
||||
UNIT_CLASS_TEST(RestrictionTest, XYGraph_RestrictionF3F5OnlyAndF1F3No)
|
||||
{
|
||||
Init(BuildXYGraph());
|
||||
RestrictionVec restrictionsNo = {{1 /* feature from */, 3 /* feature to */}};
|
||||
RestrictionVec restrictionsOnly = {{3 /* feature from */, 5 /* feature to */}};
|
||||
ConvertRestrictionsOnlyToNo(m_graph->GetIndexGraphForTests(kTestNumMwmId), restrictionsOnly, restrictionsNo);
|
||||
|
||||
TestRestrictions({} /* expectedGeom */, Algorithm::Result::NoPath,
|
||||
MakeFakeEnding(1 /* featureId */, 0 /* segmentIdx */, m2::PointD(2, 0), *m_graph),
|
||||
MakeFakeEnding(5, 0, m2::PointD(2, 3), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
// Finish
|
||||
// 3 * *
|
||||
// ↖ ↗
|
||||
// F5 F6
|
||||
// ↖ ↗
|
||||
// 2 * *
|
||||
// ↖ ↗ ↖
|
||||
// F2 F3 F4
|
||||
// ↖ ↗ ↖
|
||||
// 1 * *
|
||||
// ↗ ↖ ^
|
||||
// F0 F1 F8
|
||||
// ↗ ↖ |
|
||||
// 0 * *--F7--->*
|
||||
// ^
|
||||
// F9
|
||||
// |
|
||||
//-1 *
|
||||
// 0 1 2 3
|
||||
// Start
|
||||
// Note. This graph contains of 9 one segment directed features.
|
||||
unique_ptr<SingleVehicleWorldGraph> BuildXXGraph()
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
loader->AddRoad(0 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 0.0}, {1.0, 1.0}}));
|
||||
loader->AddRoad(1 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 0.0}, {1.0, 1.0}}));
|
||||
loader->AddRoad(2 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 1.0}, {0.0, 2.0}}));
|
||||
loader->AddRoad(3 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 1.0}, {2.0, 2.0}}));
|
||||
loader->AddRoad(4 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{3.0, 1.0}, {2.0, 2.0}}));
|
||||
loader->AddRoad(5 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 2.0}, {1.0, 3.0}}));
|
||||
loader->AddRoad(6 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 2.0}, {3.0, 3.0}}));
|
||||
loader->AddRoad(7 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 0.0}, {3.0, 0.0}}));
|
||||
loader->AddRoad(8 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{3.0, 0.0}, {3.0, 1.0}}));
|
||||
loader->AddRoad(9 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, -1.0}, {2.0, 0.0}}));
|
||||
|
||||
vector<Joint> const joints = {
|
||||
MakeJoint({{0 /* feature id */, 0 /* point id */}}), /* joint at point (0, 0) */
|
||||
MakeJoint({{1, 0}, {7, 0}, {9, 1}}), /* joint at point (2, 0) */
|
||||
MakeJoint({{0, 1}, {1, 1}, {2, 0}, {3, 0}}), /* joint at point (1, 1) */
|
||||
MakeJoint({{2, 1}}), /* joint at point (0, 2) */
|
||||
MakeJoint({{3, 1}, {4, 1}, {5, 0}, {6, 0}}), /* joint at point (2, 2) */
|
||||
MakeJoint({{4, 0}, {8, 1}}), /* joint at point (3, 1) */
|
||||
MakeJoint({{5, 1}}), /* joint at point (1, 3) */
|
||||
MakeJoint({{6, 1}}), /* joint at point (3, 3) */
|
||||
MakeJoint({{7, 1}, {8, 0}}), /* joint at point (3, 0) */
|
||||
MakeJoint({{9, 0}}), /* joint at point (2, -1) */
|
||||
};
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
return BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
}
|
||||
|
||||
// 2 * *
|
||||
// ↗ ↘
|
||||
// F4 F5
|
||||
// ↗ ↘
|
||||
// 1 * *
|
||||
// ↖ ↑
|
||||
// F2 F3
|
||||
// ↖ ↓ <-- Finish
|
||||
// 0 * *--F1--->*
|
||||
// ^
|
||||
// F0
|
||||
// |
|
||||
//-1 *
|
||||
// 0 1 2 3
|
||||
// Start
|
||||
// Note. This graph contains of 9 one segment directed features.
|
||||
unique_ptr<SingleVehicleWorldGraph> BuildCubeGraph()
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
loader->AddRoad(0 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, -1.0}, {2.0, 0.0}}));
|
||||
loader->AddRoad(1 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 0.0}, {3.0, 0.0}}));
|
||||
loader->AddRoad(2 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 0.0}, {1.0, 1.0}}));
|
||||
loader->AddRoad(3 /* featureId */, false /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{3.0, 1.0}, {3.0, 0.0}}));
|
||||
loader->AddRoad(4 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 1.0}, {2.0, 2.0}}));
|
||||
loader->AddRoad(5 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 2.0}, {3.0, 1.0}}));
|
||||
|
||||
vector<Joint> const joints = {
|
||||
MakeJoint({{0 /* feature id */, 0 /* point id */}}), /* joint at point (2, -1) */
|
||||
MakeJoint({{0, 1}, {1, 0}, {2, 0}}), /* joint at point (2, 0) */
|
||||
MakeJoint({{2, 1}, {4, 0}}), /* joint at point (1, 1) */
|
||||
MakeJoint({{4, 1}, {5, 0}}), /* joint at point (2, 2) */
|
||||
MakeJoint({{5, 1}, {3, 0}}), /* joint at point (3, 1) */
|
||||
MakeJoint({{1, 1}, {3, 1}}), /* joint at point (3, 0) */
|
||||
};
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
return BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
}
|
||||
|
||||
// Route through XY graph without any restrictions.
|
||||
UNIT_CLASS_TEST(RestrictionTest, XXGraph)
|
||||
{
|
||||
Init(BuildXXGraph());
|
||||
RestrictionVec restrictions = {};
|
||||
vector<m2::PointD> const expectedGeom = {{2 /* x */, -1 /* y */}, {2, 0}, {1, 1}, {2, 2}, {3, 3}};
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(9 /* featureId */, 0 /* segmentIdx */, m2::PointD(2, -1), *m_graph),
|
||||
MakeFakeEnding(6, 0, m2::PointD(3, 3), *m_graph), std::move(restrictions), *this);
|
||||
}
|
||||
|
||||
// Cumulative case. Route through XX graph with two restricitons (type only) applying
|
||||
// in all possible orders.
|
||||
UNIT_CLASS_TEST(RestrictionTest, XXGraph_PermutationsF1F3OnlyAndF3F6Only)
|
||||
{
|
||||
Init(BuildXXGraph());
|
||||
RestrictionVec restrictionsNo;
|
||||
RestrictionVec restrictionsOnly = {{1 /* feature from */, 3 /* feature to */},
|
||||
{3 /* feature from */, 6 /* feature to */}};
|
||||
ConvertRestrictionsOnlyToNo(m_graph->GetIndexGraphForTests(kTestNumMwmId), restrictionsOnly, restrictionsNo);
|
||||
|
||||
vector<m2::PointD> const expectedGeom = {{2 /* x */, -1 /* y */}, {2, 0}, {1, 1}, {2, 2}, {3, 3}};
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(9 /* featureId */, 0 /* segmentIdx */, m2::PointD(2, -1), *m_graph),
|
||||
MakeFakeEnding(6, 0, m2::PointD(3, 3), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
// Route through XX graph with one restriciton (type no) from F1 to F3.
|
||||
UNIT_CLASS_TEST(RestrictionTest, XXGraph_RestrictionF1F3No)
|
||||
{
|
||||
Init(BuildXXGraph());
|
||||
RestrictionVec restrictionsNo = {{1 /* feature from */, 3 /* feature to */}};
|
||||
vector<m2::PointD> const expectedGeom = {{2 /* x */, -1 /* y */}, {2, 0}, {3, 0}, {3, 1}, {2, 2}, {3, 3}};
|
||||
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(9 /* featureId */, 0 /* segmentIdx */, m2::PointD(2, -1), *m_graph),
|
||||
MakeFakeEnding(6, 0, m2::PointD(3, 3), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
// Cumulative case. Route through XX graph with four restricitons of different types applying
|
||||
// in all possible orders.
|
||||
UNIT_CLASS_TEST(RestrictionTest, XXGraph_PermutationsF1F3NoF7F8OnlyF8F4OnlyF4F6Only)
|
||||
{
|
||||
Init(BuildXXGraph());
|
||||
RestrictionVec restrictionsNo = {{1 /* feature from */, 3 /* feature to */}};
|
||||
|
||||
RestrictionVec restrictionsOnly = {{4 /* feature from */, 6 /* feature to */},
|
||||
{7 /* feature from */, 8 /* feature to */},
|
||||
{8 /* feature from */, 4 /* feature to */}};
|
||||
|
||||
ConvertRestrictionsOnlyToNo(m_graph->GetIndexGraphForTests(kTestNumMwmId), restrictionsOnly, restrictionsNo);
|
||||
vector<m2::PointD> const expectedGeom = {{2 /* x */, -1 /* y */}, {2, 0}, {3, 0}, {3, 1}, {2, 2}, {3, 3}};
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(9 /* featureId */, 0 /* segmentIdx */, m2::PointD(2, -1), *m_graph),
|
||||
MakeFakeEnding(6, 0, m2::PointD(3, 3), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RestrictionTest, XXGraph_CheckOnlyRestriction)
|
||||
{
|
||||
Init(BuildCubeGraph());
|
||||
|
||||
m2::PointD const start(2.0, -1.0);
|
||||
m2::PointD const finish(3.0, 0.2);
|
||||
auto const test = [&](vector<m2::PointD> const & expectedGeom, RestrictionVec && restrictionsNo)
|
||||
{
|
||||
TestRestrictions(
|
||||
expectedGeom, Algorithm::Result::OK, MakeFakeEnding(0 /* featureId */, 0 /* segmentIdx */, start, *m_graph),
|
||||
MakeFakeEnding(3 /* featureId */, 0 /* segmentIdx */, finish, *m_graph), std::move(restrictionsNo), *this);
|
||||
};
|
||||
|
||||
RestrictionVec restrictionsOnly = {
|
||||
{0 /* feature from */, 2 /* feature to */},
|
||||
};
|
||||
RestrictionVec restrictionsNo;
|
||||
ConvertRestrictionsOnlyToNo(m_graph->GetIndexGraphForTests(kTestNumMwmId), restrictionsOnly, restrictionsNo);
|
||||
|
||||
// Check that without restrictions we can find path better.
|
||||
test({start, {2, 0}, {1, 1}, {2, 2}, {3, 1}, finish}, std::move(restrictionsNo));
|
||||
test({start, {2, 0}, {3, 0}, finish}, RestrictionVec());
|
||||
}
|
||||
} // namespace cumulative_restriction_test
|
||||
79
libs/routing/routing_tests/edge_estimator_tests.cpp
Normal file
79
libs/routing/routing_tests/edge_estimator_tests.cpp
Normal file
|
|
@ -0,0 +1,79 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/edge_estimator.hpp"
|
||||
|
||||
#include "geometry/point_with_altitude.hpp"
|
||||
|
||||
#include <cmath>
|
||||
|
||||
namespace
|
||||
{
|
||||
using namespace routing;
|
||||
|
||||
double const kTan = 0.1;
|
||||
geometry::Altitude const kAlt = 100.0;
|
||||
auto const kPurposes = {EdgeEstimator::Purpose::Weight, EdgeEstimator::Purpose::ETA};
|
||||
constexpr double kAccuracyEps = 1e-5;
|
||||
|
||||
// Climb penalty on plain surface (tangent = 0) must be 1.0 for ETA and Weight estimations.
|
||||
UNIT_TEST(ClimbPenalty_ZeroTangent)
|
||||
{
|
||||
double const zeroTangent = 0.0;
|
||||
|
||||
for (auto const & purpose : kPurposes)
|
||||
{
|
||||
TEST_EQUAL(GetCarClimbPenalty(purpose, zeroTangent, kAlt), 1.0, ());
|
||||
TEST_EQUAL(GetBicycleClimbPenalty(purpose, zeroTangent, kAlt), 1.0, ());
|
||||
TEST_EQUAL(GetPedestrianClimbPenalty(purpose, zeroTangent, kAlt), 1.0, ());
|
||||
}
|
||||
}
|
||||
|
||||
// Descent penalty for pedestrians and bicycles must be less then the ascent penalty.
|
||||
UNIT_TEST(ClimbPenalty_DescentLessThenAscent)
|
||||
{
|
||||
for (auto const & purpose : kPurposes)
|
||||
{
|
||||
double const ascPenaltyPedestrian = GetPedestrianClimbPenalty(purpose, kTan, kAlt);
|
||||
double const descPenaltyPedestrian = GetPedestrianClimbPenalty(purpose, -kTan, kAlt);
|
||||
TEST_LESS(descPenaltyPedestrian, ascPenaltyPedestrian, ());
|
||||
|
||||
double const ascPenaltyBicycle = GetBicycleClimbPenalty(purpose, kTan, kAlt);
|
||||
double const descPenaltyBicycle = GetBicycleClimbPenalty(purpose, -kTan, kAlt);
|
||||
TEST_LESS(descPenaltyBicycle, ascPenaltyBicycle, ());
|
||||
}
|
||||
}
|
||||
|
||||
// Descent penalty for cars must be equal to the ascent penalty.
|
||||
UNIT_TEST(ClimbPenalty_DescentEqualsAscent)
|
||||
{
|
||||
for (auto const & purpose : kPurposes)
|
||||
{
|
||||
double const ascPenaltyCar = GetCarClimbPenalty(purpose, kTan, kAlt);
|
||||
double const descPenaltyCar = GetCarClimbPenalty(purpose, -kTan, kAlt);
|
||||
TEST_EQUAL(ascPenaltyCar, 1.0, ());
|
||||
TEST_EQUAL(descPenaltyCar, 1.0, ());
|
||||
}
|
||||
}
|
||||
|
||||
// Climb penalty high above the sea level (higher then 2.5 km) should be very significant.
|
||||
UNIT_TEST(ClimbPenalty_HighAboveSeaLevel)
|
||||
{
|
||||
for (auto const & purpose : kPurposes)
|
||||
{
|
||||
double const penalty2500 = GetPedestrianClimbPenalty(purpose, kTan, 2500);
|
||||
double const penalty4000 = GetPedestrianClimbPenalty(purpose, kTan, 4000);
|
||||
double const penalty5500 = GetPedestrianClimbPenalty(purpose, kTan, 5500);
|
||||
double const penalty7000 = GetPedestrianClimbPenalty(purpose, kTan, 7000);
|
||||
|
||||
TEST_GREATER_OR_EQUAL(penalty2500, 2.0, ());
|
||||
TEST_GREATER_OR_EQUAL(penalty4000, penalty2500 + 1.0, ());
|
||||
TEST_GREATER_OR_EQUAL(penalty5500, penalty4000 + 1.0, ());
|
||||
TEST_GREATER_OR_EQUAL(penalty7000, penalty5500 + 1.0, ());
|
||||
|
||||
double const penalty2500Bicyclce = GetBicycleClimbPenalty(purpose, kTan, 2500);
|
||||
|
||||
TEST_GREATER_OR_EQUAL(penalty2500Bicyclce, 6.0, ());
|
||||
TEST_ALMOST_EQUAL_ABS(GetCarClimbPenalty(purpose, kTan, 2500), 1.0, kAccuracyEps, ());
|
||||
}
|
||||
}
|
||||
} // namespace
|
||||
133
libs/routing/routing_tests/fake_graph_test.cpp
Normal file
133
libs/routing/routing_tests/fake_graph_test.cpp
Normal file
|
|
@ -0,0 +1,133 @@
|
|||
#include "routing/fake_graph.hpp"
|
||||
|
||||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/fake_feature_ids.hpp"
|
||||
#include "routing/latlon_with_altitude.hpp"
|
||||
#include "routing/segment.hpp"
|
||||
|
||||
#include "routing_common/num_mwm_id.hpp"
|
||||
|
||||
#include <cstdint>
|
||||
#include <set>
|
||||
|
||||
namespace fake_graph_test
|
||||
{
|
||||
using namespace routing;
|
||||
using namespace std;
|
||||
|
||||
Segment GetSegment(uint32_t segmentIdx, bool isReal = false)
|
||||
{
|
||||
static NumMwmId constexpr kFakeNumMwmId = std::numeric_limits<NumMwmId>::max();
|
||||
static uint32_t constexpr kFakeFeatureId = FakeFeatureIds::kIndexGraphStarterId;
|
||||
if (isReal)
|
||||
return Segment(0 /* mwmId */, 0 /* featureId */, segmentIdx, true /* isForward */);
|
||||
return Segment(kFakeNumMwmId, kFakeFeatureId, segmentIdx, true /* isForward */);
|
||||
}
|
||||
|
||||
FakeVertex GetFakeVertex(uint32_t index)
|
||||
{
|
||||
auto const indexCoord = static_cast<double>(index);
|
||||
LatLonWithAltitude const coord({indexCoord, indexCoord}, 0 /* altitude */);
|
||||
// FakeVertex(NumMwmId numMwmId, LatLonWithAltitude const & from,
|
||||
// LatLonWithAltitude const & to, Type type)
|
||||
return FakeVertex(0 /* mwmId */, coord, coord, FakeVertex::Type::PureFake);
|
||||
}
|
||||
|
||||
// Constructs simple fake graph where vertex (i + 1) is child of vertex (i) with |numFake| fake
|
||||
// vertices and |numReal| real vertices. Checks vertex-to-segment, segment-to-vertex, fake-to-real,
|
||||
// real-to-fake mappings for each vertex. Checks ingoing and outgoing sets.
|
||||
FakeGraph ConstructFakeGraph(uint32_t numerationStart, uint32_t numFake, uint32_t numReal)
|
||||
{
|
||||
FakeGraph fakeGraph;
|
||||
TEST_EQUAL(fakeGraph.GetSize(), 0, ("Constructed fake graph not empty"));
|
||||
if (numFake < 1)
|
||||
{
|
||||
CHECK_EQUAL(numReal, 0, ("Construction of non-empty fake graph without pure fake vertices not supported."));
|
||||
return fakeGraph;
|
||||
}
|
||||
|
||||
auto const startSegment = GetSegment(numerationStart);
|
||||
auto const startVertex = GetFakeVertex(numerationStart);
|
||||
fakeGraph.AddStandaloneVertex(startSegment, startVertex);
|
||||
|
||||
// Add pure fake.
|
||||
for (uint32_t prevNumber = numerationStart; prevNumber + 1 < numerationStart + numFake + numReal; ++prevNumber)
|
||||
{
|
||||
bool const newIsReal = prevNumber + 1 >= numerationStart + numFake;
|
||||
auto const prevSegment = GetSegment(prevNumber);
|
||||
auto const newSegment = GetSegment(prevNumber + 1);
|
||||
auto const newVertex = GetFakeVertex(prevNumber + 1);
|
||||
auto const realSegment = GetSegment(prevNumber + 1, true /* isReal */);
|
||||
|
||||
fakeGraph.AddVertex(prevSegment, newSegment, newVertex, true /* isOutgoing */, newIsReal /* isPartOfReal */,
|
||||
realSegment);
|
||||
|
||||
// Test segment to vertex mapping.
|
||||
TEST_EQUAL(fakeGraph.GetVertex(newSegment), newVertex, ("Wrong segment to vertex mapping."));
|
||||
// Test outgoing edge.
|
||||
TEST_EQUAL(fakeGraph.GetEdges(newSegment, false /* isOutgoing */), set<Segment>{prevSegment},
|
||||
("Wrong ingoing edges set."));
|
||||
// Test ingoing edge.
|
||||
TEST_EQUAL(fakeGraph.GetEdges(prevSegment, true /* isOutgoing */), set<Segment>{newSegment},
|
||||
("Wrong ingoing edges set."));
|
||||
// Test graph size
|
||||
TEST_EQUAL(fakeGraph.GetSize() + numerationStart, prevNumber + 2, ("Wrong fake graph size."));
|
||||
// Test fake to real and real to fake mapping.
|
||||
Segment realFound;
|
||||
if (newIsReal)
|
||||
{
|
||||
TEST_EQUAL(fakeGraph.FindReal(newSegment, realFound), true, ("Unexpected real segment found."));
|
||||
TEST_EQUAL(realSegment, realFound, ("Wrong fake to real mapping."));
|
||||
TEST_EQUAL(fakeGraph.GetFake(realSegment), set<Segment>{newSegment}, ("Unexpected fake segment found."));
|
||||
}
|
||||
else
|
||||
{
|
||||
TEST_EQUAL(fakeGraph.FindReal(newSegment, realFound), false, ("Unexpected real segment found."));
|
||||
TEST(fakeGraph.GetFake(realSegment).empty(), ("Unexpected fake segment found."));
|
||||
}
|
||||
}
|
||||
return fakeGraph;
|
||||
}
|
||||
|
||||
// Test constructs two fake graphs, performs checks during construction, merges graphs
|
||||
// Calls FakeGraph::Append and checks topology of the merged graph.
|
||||
UNIT_TEST(FakeGraphTest)
|
||||
{
|
||||
uint32_t const fake0 = 5;
|
||||
uint32_t const real0 = 3;
|
||||
uint32_t const fake1 = 4;
|
||||
uint32_t const real1 = 2;
|
||||
auto fakeGraph0 = ConstructFakeGraph(0, fake0, real0);
|
||||
TEST_EQUAL(fakeGraph0.GetSize(), fake0 + real0, ("Wrong fake graph size"));
|
||||
|
||||
auto const fakeGraph1 = ConstructFakeGraph(static_cast<uint32_t>(fakeGraph0.GetSize()), fake1, real1);
|
||||
TEST_EQUAL(fakeGraph1.GetSize(), fake1 + real1, ("Wrong fake graph size"));
|
||||
|
||||
fakeGraph0.Append(fakeGraph1);
|
||||
TEST_EQUAL(fakeGraph0.GetSize(), fake0 + real0 + fake1 + real1, ("Wrong size of merged graph"));
|
||||
|
||||
// Test merged graph.
|
||||
for (uint32_t i = 0; i + 1 < fakeGraph0.GetSize(); ++i)
|
||||
{
|
||||
auto const segmentFrom = GetSegment(i);
|
||||
auto const segmentTo = GetSegment(i + 1);
|
||||
|
||||
TEST_EQUAL(fakeGraph0.GetVertex(segmentFrom), GetFakeVertex(i), ("Wrong segment to vertex mapping."));
|
||||
TEST_EQUAL(fakeGraph0.GetVertex(segmentTo), GetFakeVertex(i + 1), ("Wrong segment to vertex mapping."));
|
||||
// No connection to next fake segment; next segment was in separate fake graph before Append.
|
||||
if (i + 1 == fake0 + real0)
|
||||
{
|
||||
TEST(fakeGraph0.GetEdges(segmentFrom, true /* isOutgoing */).empty(), ("Wrong ingoing edges set."));
|
||||
TEST(fakeGraph0.GetEdges(segmentTo, false /* isOutgoing */).empty(), ("Wrong ingoing edges set."));
|
||||
}
|
||||
else
|
||||
{
|
||||
TEST_EQUAL(fakeGraph0.GetEdges(segmentFrom, true /* isOutgoing */), set<Segment>{segmentTo},
|
||||
("Wrong ingoing edges set."));
|
||||
TEST_EQUAL(fakeGraph0.GetEdges(segmentTo, false /* isOutgoing */), set<Segment>{segmentFrom},
|
||||
("Wrong ingoing edges set."));
|
||||
}
|
||||
}
|
||||
}
|
||||
} // namespace fake_graph_test
|
||||
124
libs/routing/routing_tests/followed_polyline_test.cpp
Normal file
124
libs/routing/routing_tests/followed_polyline_test.cpp
Normal file
|
|
@ -0,0 +1,124 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/base/followed_polyline.hpp"
|
||||
|
||||
#include "geometry/polyline2d.hpp"
|
||||
|
||||
namespace routing_test
|
||||
{
|
||||
using namespace routing;
|
||||
|
||||
namespace
|
||||
{
|
||||
static m2::PolylineD const kTestDirectedPolyline1(std::vector<m2::PointD>{{0.0, 0.0}, {3.0, 0.0}, {5.0, 0.0}});
|
||||
static m2::PolylineD const kTestDirectedPolyline2(std::vector<m2::PointD>{{6.0, 0.0}, {7.0, 0.0}});
|
||||
} // namespace
|
||||
|
||||
UNIT_TEST(FollowedPolylineAppend)
|
||||
{
|
||||
FollowedPolyline followedPolyline1(kTestDirectedPolyline1.Begin(), kTestDirectedPolyline1.End());
|
||||
FollowedPolyline const followedPolyline2(kTestDirectedPolyline2.Begin(), kTestDirectedPolyline2.End());
|
||||
|
||||
TEST_EQUAL(followedPolyline1.GetPolyline(), kTestDirectedPolyline1, ());
|
||||
followedPolyline1.Append(followedPolyline2);
|
||||
TEST_EQUAL(followedPolyline1.GetPolyline().GetSize(), 5, ());
|
||||
|
||||
m2::PolylineD polyline1 = kTestDirectedPolyline1;
|
||||
polyline1.Append(kTestDirectedPolyline2);
|
||||
TEST_EQUAL(followedPolyline1.GetPolyline(), polyline1, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(FollowedPolylinePop)
|
||||
{
|
||||
FollowedPolyline followedPolyline(kTestDirectedPolyline1.Begin(), kTestDirectedPolyline1.End());
|
||||
|
||||
TEST_EQUAL(followedPolyline.GetPolyline(), kTestDirectedPolyline1, ());
|
||||
TEST_EQUAL(followedPolyline.GetPolyline().GetSize(), 3, ());
|
||||
followedPolyline.PopBack();
|
||||
TEST_EQUAL(followedPolyline.GetPolyline().GetSize(), 2, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(FollowedPolylineInitializationFogTest)
|
||||
{
|
||||
FollowedPolyline polyline(kTestDirectedPolyline1.Begin(), kTestDirectedPolyline1.End());
|
||||
TEST(polyline.IsValid(), ());
|
||||
TEST_EQUAL(polyline.GetCurrentIter().m_ind, 0, ());
|
||||
TEST_EQUAL(polyline.GetPolyline().GetSize(), 3, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(FollowedPolylineFollowingTestByProjection)
|
||||
{
|
||||
FollowedPolyline polyline(kTestDirectedPolyline1.Begin(), kTestDirectedPolyline1.End());
|
||||
TEST_EQUAL(polyline.GetCurrentIter().m_ind, 0, ());
|
||||
polyline.UpdateProjection(mercator::RectByCenterXYAndSizeInMeters({0, 0}, 2));
|
||||
TEST_EQUAL(polyline.GetCurrentIter().m_ind, 0, ());
|
||||
TEST_EQUAL(polyline.GetCurrentIter().m_pt, m2::PointD(0, 0), ());
|
||||
polyline.UpdateProjection(mercator::RectByCenterXYAndSizeInMeters({1, 0}, 2));
|
||||
TEST_EQUAL(polyline.GetCurrentIter().m_ind, 0, ());
|
||||
TEST_EQUAL(polyline.GetCurrentIter().m_pt, m2::PointD(1, 0), ());
|
||||
polyline.UpdateProjection(mercator::RectByCenterXYAndSizeInMeters({4, 0}, 2));
|
||||
TEST_EQUAL(polyline.GetCurrentIter().m_ind, 1, ());
|
||||
TEST_EQUAL(polyline.GetCurrentIter().m_pt, m2::PointD(4, 0), ());
|
||||
auto iter = polyline.UpdateProjection(mercator::RectByCenterXYAndSizeInMeters({5.0001, 0}, 1));
|
||||
TEST(!iter.IsValid(), ());
|
||||
TEST_EQUAL(polyline.GetCurrentIter().m_ind, 1, ());
|
||||
TEST_EQUAL(polyline.GetCurrentIter().m_pt, m2::PointD(4, 0), ());
|
||||
polyline.UpdateProjection(mercator::RectByCenterXYAndSizeInMeters({5.0001, 0}, 2000));
|
||||
TEST_EQUAL(polyline.GetCurrentIter().m_ind, 1, ());
|
||||
TEST_EQUAL(polyline.GetCurrentIter().m_pt, m2::PointD(5, 0), ());
|
||||
}
|
||||
|
||||
UNIT_TEST(FollowedPolylineDistanceCalculationTest)
|
||||
{
|
||||
// Test full length case.
|
||||
FollowedPolyline polyline(kTestDirectedPolyline1.Begin(), kTestDirectedPolyline1.End());
|
||||
double distance = polyline.GetDistanceM(polyline.Begin(), polyline.End());
|
||||
double masterDistance = mercator::DistanceOnEarth(kTestDirectedPolyline1.Front(), kTestDirectedPolyline1.Back());
|
||||
TEST_ALMOST_EQUAL_ULPS(distance, masterDistance, ());
|
||||
distance = polyline.GetTotalDistanceMeters();
|
||||
TEST_ALMOST_EQUAL_ULPS(distance, masterDistance, ());
|
||||
|
||||
// Test partial length case.
|
||||
polyline.UpdateProjection(mercator::RectByCenterXYAndSizeInMeters({3, 0}, 2));
|
||||
distance = polyline.GetDistanceM(polyline.GetCurrentIter(), polyline.End());
|
||||
masterDistance = mercator::DistanceOnEarth(kTestDirectedPolyline1.GetPoint(1), kTestDirectedPolyline1.Back());
|
||||
TEST_ALMOST_EQUAL_ULPS(distance, masterDistance, ());
|
||||
distance = polyline.GetDistanceToEndMeters();
|
||||
TEST_ALMOST_EQUAL_ULPS(distance, masterDistance, ());
|
||||
|
||||
// Test point in the middle case.
|
||||
polyline.UpdateProjection(mercator::RectByCenterXYAndSizeInMeters({4, 0}, 2));
|
||||
distance = polyline.GetDistanceM(polyline.GetCurrentIter(), polyline.End());
|
||||
masterDistance = mercator::DistanceOnEarth(m2::PointD(4, 0), kTestDirectedPolyline1.Back());
|
||||
TEST_ALMOST_EQUAL_ULPS(distance, masterDistance, ());
|
||||
distance = polyline.GetDistanceToEndMeters();
|
||||
TEST_ALMOST_EQUAL_ULPS(distance, masterDistance, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(FollowedPolylineDirectionTest)
|
||||
{
|
||||
m2::PolylineD testPolyline(std::vector<m2::PointD>{{0, 0}, {1.00003, 0}, {1.00003, 1}});
|
||||
FollowedPolyline polyline(testPolyline.Begin(), testPolyline.End());
|
||||
TEST_EQUAL(polyline.GetCurrentIter().m_ind, 0, ());
|
||||
m2::PointD directionPoint;
|
||||
polyline.GetCurrentDirectionPoint(directionPoint, 20);
|
||||
TEST_EQUAL(directionPoint, testPolyline.GetPoint(1), ());
|
||||
polyline.UpdateProjection(mercator::RectByCenterXYAndSizeInMeters({1.0, 0}, 2));
|
||||
polyline.GetCurrentDirectionPoint(directionPoint, 0.0001);
|
||||
TEST_EQUAL(directionPoint, testPolyline.GetPoint(1), ());
|
||||
polyline.GetCurrentDirectionPoint(directionPoint, 20);
|
||||
TEST_EQUAL(directionPoint, testPolyline.GetPoint(2), ());
|
||||
}
|
||||
|
||||
UNIT_TEST(FollowedPolylineGetDistanceFromBeginM)
|
||||
{
|
||||
m2::PolylineD testPolyline(std::vector<m2::PointD>{{0, 0}, {1, 0}, {2, 0}, {3, 0}, {5, 0}, {6, 0}});
|
||||
FollowedPolyline polyline(testPolyline.Begin(), testPolyline.End());
|
||||
m2::PointD point(4, 0);
|
||||
polyline.UpdateProjection(mercator::RectByCenterXYAndSizeInMeters(point, 2));
|
||||
|
||||
double const distance = polyline.GetDistanceFromStartMeters();
|
||||
double const masterDistance = mercator::DistanceOnEarth(kTestDirectedPolyline1.Front(), point);
|
||||
TEST_ALMOST_EQUAL_ULPS(distance, masterDistance, ());
|
||||
}
|
||||
} // namespace routing_test
|
||||
135
libs/routing/routing_tests/guides_tests.cpp
Normal file
135
libs/routing/routing_tests/guides_tests.cpp
Normal file
|
|
@ -0,0 +1,135 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/guides_connections.hpp"
|
||||
|
||||
#include "geometry/mercator.hpp"
|
||||
|
||||
namespace
|
||||
{
|
||||
using namespace routing;
|
||||
|
||||
// 10 guide, track 0 10 guide, track 1 11 guide, track 0
|
||||
// 4 points 3 points 3 points
|
||||
//
|
||||
// X 2 X 2
|
||||
// X X
|
||||
// X X
|
||||
// X X
|
||||
// 2 XXXXX 3 X X 1
|
||||
// X X X
|
||||
// X X X
|
||||
// X X X
|
||||
// X X 1 X
|
||||
// XXX 1 XX X 0
|
||||
// 0 XX
|
||||
// XX
|
||||
// XX 0
|
||||
|
||||
GuidesTracks GetTestGuides()
|
||||
{
|
||||
// Two guides. First with 2 tracks, second - with 1 track.
|
||||
GuidesTracks guides;
|
||||
guides[10] = {{{mercator::FromLatLon(48.13999, 11.56873), 5},
|
||||
{mercator::FromLatLon(48.14096, 11.57246), 5},
|
||||
{mercator::FromLatLon(48.14487, 11.57259), 6}},
|
||||
{{mercator::FromLatLon(48.14349, 11.56712), 8},
|
||||
{mercator::FromLatLon(48.14298, 11.56604), 6},
|
||||
{mercator::FromLatLon(48.14223, 11.56362), 6},
|
||||
{mercator::FromLatLon(48.14202, 11.56283), 6}}};
|
||||
guides[11] = {{{mercator::FromLatLon(48.14246, 11.57814), 9},
|
||||
{mercator::FromLatLon(48.14279, 11.57941), 10},
|
||||
{mercator::FromLatLon(48.14311, 11.58063), 10}}};
|
||||
return guides;
|
||||
}
|
||||
|
||||
UNIT_TEST(Guides_SafeInit)
|
||||
{
|
||||
GuidesConnections guides;
|
||||
TEST(!guides.IsActive(), ());
|
||||
TEST(!guides.IsAttached(), ());
|
||||
TEST(!guides.IsCheckpointAttached(0 /* checkpointIdx */), ());
|
||||
}
|
||||
|
||||
UNIT_TEST(Guides_InitWithGuides)
|
||||
{
|
||||
GuidesConnections guides(GetTestGuides());
|
||||
TEST(guides.IsActive(), ());
|
||||
TEST(!guides.IsAttached(), ());
|
||||
}
|
||||
|
||||
UNIT_TEST(Guides_TooFarCheckpointsAreNotAttached)
|
||||
{
|
||||
GuidesConnections guides(GetTestGuides());
|
||||
TEST(guides.IsActive(), ());
|
||||
TEST(!guides.IsAttached(), ());
|
||||
|
||||
// Checkpoints located further from guides than |kMaxDistToTrackPointM|.
|
||||
std::vector<m2::PointD> const & checkpoints{mercator::FromLatLon(48.13902, 11.57113),
|
||||
mercator::FromLatLon(48.14589, 11.56911)};
|
||||
|
||||
guides.ConnectToGuidesGraph(checkpoints);
|
||||
TEST(!guides.IsAttached(), ());
|
||||
|
||||
for (size_t checkpointIdx = 0; checkpointIdx < checkpoints.size(); ++checkpointIdx)
|
||||
{
|
||||
TEST(!guides.IsCheckpointAttached(checkpointIdx), ());
|
||||
TEST(guides.GetOsmConnections(checkpointIdx).empty(), ());
|
||||
}
|
||||
}
|
||||
|
||||
UNIT_TEST(Guides_FinishAndStartAttached)
|
||||
{
|
||||
GuidesConnections guides(GetTestGuides());
|
||||
|
||||
// Start checkpoint should be with fake ending to OSM and finish - with fake ending to the guide
|
||||
// segment.
|
||||
std::vector<m2::PointD> const & checkpoints{mercator::FromLatLon(48.13998, 11.56982),
|
||||
mercator::FromLatLon(48.14448, 11.57259)};
|
||||
|
||||
guides.ConnectToGuidesGraph(checkpoints);
|
||||
TEST(guides.IsAttached(), ());
|
||||
|
||||
for (size_t checkpointIdx = 0; checkpointIdx < checkpoints.size(); ++checkpointIdx)
|
||||
{
|
||||
TEST(guides.IsCheckpointAttached(checkpointIdx), ());
|
||||
auto const links = guides.GetOsmConnections(checkpointIdx);
|
||||
TEST(!links.empty(), ());
|
||||
|
||||
bool const isCheckpointNear = guides.FitsForDirectLinkToGuide(checkpointIdx, checkpoints.size());
|
||||
auto const ending = guides.GetFakeEnding(checkpointIdx);
|
||||
|
||||
// Initial projection to guides track.
|
||||
TEST_EQUAL(ending.m_projections.size(), 1, ());
|
||||
|
||||
// Start point is on the track, finish point is on some distance.
|
||||
bool const isStart = checkpointIdx == 0;
|
||||
if (isStart)
|
||||
TEST(!isCheckpointNear, ());
|
||||
else
|
||||
TEST(isCheckpointNear, ());
|
||||
}
|
||||
}
|
||||
|
||||
UNIT_TEST(Guides_NotAttachIntermediatePoint)
|
||||
{
|
||||
GuidesConnections guides(GetTestGuides());
|
||||
|
||||
// Intermediate checkpoints should not be attached to the guides if they are far enough even
|
||||
// if their neighbours are attached.
|
||||
std::vector<m2::PointD> const & checkpoints{mercator::FromLatLon(48.14349, 11.56712),
|
||||
mercator::FromLatLon(48.14493, 11.56820),
|
||||
mercator::FromLatLon(48.14311, 11.58063)};
|
||||
|
||||
guides.ConnectToGuidesGraph(checkpoints);
|
||||
TEST(guides.IsAttached(), ());
|
||||
for (size_t checkpointIdx = 0; checkpointIdx < checkpoints.size(); ++checkpointIdx)
|
||||
{
|
||||
bool const isAttached = guides.IsCheckpointAttached(checkpointIdx);
|
||||
bool const isIntermediate = checkpointIdx == 1;
|
||||
if (isIntermediate)
|
||||
TEST(!isAttached, ());
|
||||
else
|
||||
TEST(isAttached, ());
|
||||
}
|
||||
}
|
||||
} // namespace
|
||||
802
libs/routing/routing_tests/index_graph_test.cpp
Normal file
802
libs/routing/routing_tests/index_graph_test.cpp
Normal file
|
|
@ -0,0 +1,802 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/routing_tests/index_graph_tools.hpp"
|
||||
|
||||
#include "routing/base/astar_algorithm.hpp"
|
||||
#include "routing/base/astar_graph.hpp"
|
||||
|
||||
#include "routing/edge_estimator.hpp"
|
||||
#include "routing/fake_ending.hpp"
|
||||
#include "routing/index_graph.hpp"
|
||||
#include "routing/index_graph_serialization.hpp"
|
||||
#include "routing/index_graph_starter.hpp"
|
||||
#include "routing/index_router.hpp"
|
||||
#include "routing/routing_helpers.hpp"
|
||||
#include "routing/vehicle_mask.hpp"
|
||||
|
||||
#include "routing_common/car_model.hpp"
|
||||
|
||||
#include "geometry/mercator.hpp"
|
||||
#include "geometry/point2d.hpp"
|
||||
#include "geometry/point_with_altitude.hpp"
|
||||
|
||||
#include "coding/reader.hpp"
|
||||
#include "coding/writer.hpp"
|
||||
|
||||
#include "base/assert.hpp"
|
||||
#include "base/math.hpp"
|
||||
|
||||
#include <algorithm>
|
||||
#include <cstdint>
|
||||
#include <memory>
|
||||
#include <unordered_map>
|
||||
#include <vector>
|
||||
|
||||
namespace index_graph_test
|
||||
{
|
||||
using namespace routing;
|
||||
using namespace routing_test;
|
||||
using namespace std;
|
||||
|
||||
using measurement_utils::KmphToMps;
|
||||
|
||||
using TestEdge = TestIndexGraphTopology::Edge;
|
||||
|
||||
using AlgorithmForIndexGraphStarter = AStarAlgorithm<Segment, SegmentEdge, RouteWeight>;
|
||||
|
||||
double constexpr kUnknownWeight = -1.0;
|
||||
|
||||
void TestRoute(FakeEnding const & start, FakeEnding const & finish, size_t expectedLength,
|
||||
vector<Segment> const * expectedRoute, double expectedWeight, WorldGraph & graph)
|
||||
{
|
||||
auto starter = MakeStarter(start, finish, graph);
|
||||
vector<Segment> route;
|
||||
double timeSec;
|
||||
auto const resultCode = CalculateRoute(*starter, route, timeSec);
|
||||
TEST_EQUAL(resultCode, AlgorithmForIndexGraphStarter::Result::OK, ());
|
||||
|
||||
TEST_GREATER(route.size(), 2, ());
|
||||
|
||||
vector<Segment> noFakeRoute;
|
||||
for (auto const & s : route)
|
||||
{
|
||||
auto real = s;
|
||||
if (!starter->ConvertToReal(real))
|
||||
continue;
|
||||
noFakeRoute.push_back(real);
|
||||
}
|
||||
|
||||
TEST_EQUAL(noFakeRoute.size(), expectedLength, ("route =", noFakeRoute));
|
||||
|
||||
if (expectedWeight != kUnknownWeight)
|
||||
{
|
||||
double constexpr kEpsilon = 0.01;
|
||||
TEST(AlmostEqualRel(timeSec, expectedWeight, kEpsilon), ("Expected weight:", expectedWeight, "got:", timeSec));
|
||||
}
|
||||
|
||||
if (expectedRoute)
|
||||
TEST_EQUAL(noFakeRoute, *expectedRoute, ());
|
||||
}
|
||||
|
||||
void TestEdges(IndexGraph & graph, Segment const & segment, vector<Segment> const & expectedTargets, bool isOutgoing)
|
||||
{
|
||||
ASSERT(segment.IsForward() || !graph.GetRoadGeometry(segment.GetFeatureId()).IsOneWay(), ());
|
||||
|
||||
IndexGraph::SegmentEdgeListT edges;
|
||||
graph.GetEdgeList(segment, isOutgoing, true /* useRoutingOptions */, edges);
|
||||
|
||||
vector<Segment> targets;
|
||||
for (SegmentEdge const & edge : edges)
|
||||
targets.push_back(edge.GetTarget());
|
||||
|
||||
sort(targets.begin(), targets.end());
|
||||
|
||||
vector<Segment> sortedExpectedTargets(expectedTargets);
|
||||
sort(sortedExpectedTargets.begin(), sortedExpectedTargets.end());
|
||||
|
||||
TEST_EQUAL(targets, sortedExpectedTargets, ());
|
||||
}
|
||||
|
||||
void TestOutgoingEdges(IndexGraph & graph, Segment const & segment, vector<Segment> const & expectedTargets)
|
||||
{
|
||||
TestEdges(graph, segment, expectedTargets, true /* isOutgoing */);
|
||||
}
|
||||
|
||||
void TestIngoingEdges(IndexGraph & graph, Segment const & segment, vector<Segment> const & expectedTargets)
|
||||
{
|
||||
TestEdges(graph, segment, expectedTargets, false /* isOutgoing */);
|
||||
}
|
||||
|
||||
uint32_t AbsDelta(uint32_t v0, uint32_t v1)
|
||||
{
|
||||
return v0 > v1 ? v0 - v1 : v1 - v0;
|
||||
}
|
||||
|
||||
// R4 (one way down)
|
||||
//
|
||||
// R1 J2--------J3 -1
|
||||
// ^ v
|
||||
// ^ v
|
||||
// R0 *---J0----*---J1----* 0
|
||||
// ^ v
|
||||
// ^ v
|
||||
// R2 J4--------J5 1
|
||||
//
|
||||
// R3 (one way up) y
|
||||
//
|
||||
// x: 0 1 2 3 4
|
||||
//
|
||||
UNIT_TEST(EdgesTest)
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
loader->AddRoad(0 /* featureId */, false, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 0.0}, {1.0, 0.0}, {2.0, 0.0}, {3.0, 0.0}, {4.0, 0.0}}));
|
||||
loader->AddRoad(1 /* featureId */, false, 1.0 /* speed */, RoadGeometry::Points({{1.0, -1.0}, {3.0, -1.0}}));
|
||||
loader->AddRoad(2 /* featureId */, false, 1.0 /* speed */, RoadGeometry::Points({{1.0, -1.0}, {3.0, -1.0}}));
|
||||
loader->AddRoad(3 /* featureId */, true, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 1.0}, {1.0, 0.0}, {1.0, -1.0}}));
|
||||
loader->AddRoad(4 /* featureId */, true, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{3.0, -1.0}, {3.0, 0.0}, {3.0, 1.0}}));
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
IndexGraph graph(make_shared<Geometry>(std::move(loader)), CreateEstimatorForCar(trafficCache));
|
||||
|
||||
vector<Joint> joints;
|
||||
joints.emplace_back(MakeJoint({{0, 1}, {3, 1}})); // J0
|
||||
joints.emplace_back(MakeJoint({{0, 3}, {4, 1}})); // J1
|
||||
joints.emplace_back(MakeJoint({{1, 0}, {3, 2}})); // J2
|
||||
joints.emplace_back(MakeJoint({{1, 1}, {4, 0}})); // J3
|
||||
joints.emplace_back(MakeJoint({{2, 0}, {3, 0}})); // J4
|
||||
joints.emplace_back(MakeJoint({{2, 1}, {4, 2}})); // J5
|
||||
graph.Import(joints);
|
||||
|
||||
TestOutgoingEdges(graph, {kTestNumMwmId, 0 /* featureId */, 0 /* segmentIdx */, true /* forward */},
|
||||
{{kTestNumMwmId, 0, 0, false}, {kTestNumMwmId, 0, 1, true}, {kTestNumMwmId, 3, 1, true}});
|
||||
TestIngoingEdges(graph, {kTestNumMwmId, 0, 0, true}, {{kTestNumMwmId, 0, 0, false}});
|
||||
TestOutgoingEdges(graph, {kTestNumMwmId, 0, 0, false}, {{kTestNumMwmId, 0, 0, true}});
|
||||
TestIngoingEdges(graph, {kTestNumMwmId, 0, 0, false},
|
||||
{{kTestNumMwmId, 0, 0, true}, {kTestNumMwmId, 0, 1, false}, {kTestNumMwmId, 3, 0, true}});
|
||||
|
||||
TestOutgoingEdges(graph, {kTestNumMwmId, 0, 2, true},
|
||||
{{kTestNumMwmId, 0, 2, false}, {kTestNumMwmId, 0, 3, true}, {kTestNumMwmId, 4, 1, true}});
|
||||
TestIngoingEdges(graph, {kTestNumMwmId, 0, 2, true}, {{kTestNumMwmId, 0, 1, true}});
|
||||
TestOutgoingEdges(graph, {kTestNumMwmId, 0, 2, false}, {{kTestNumMwmId, 0, 1, false}});
|
||||
TestIngoingEdges(graph, {kTestNumMwmId, 0, 2, false},
|
||||
{{kTestNumMwmId, 0, 2, true}, {kTestNumMwmId, 0, 3, false}, {kTestNumMwmId, 4, 0, true}});
|
||||
|
||||
TestOutgoingEdges(graph, {kTestNumMwmId, 3, 0, true},
|
||||
{{kTestNumMwmId, 3, 1, true}, {kTestNumMwmId, 0, 0, false}, {kTestNumMwmId, 0, 1, true}});
|
||||
TestIngoingEdges(graph, {kTestNumMwmId, 3, 0, true}, {{kTestNumMwmId, 2, 0, false}});
|
||||
|
||||
TestOutgoingEdges(graph, {kTestNumMwmId, 4, 1, true}, {{kTestNumMwmId, 2, 0, false}});
|
||||
TestIngoingEdges(graph, {kTestNumMwmId, 4, 1, true},
|
||||
{{kTestNumMwmId, 4, 0, true}, {kTestNumMwmId, 0, 2, true}, {kTestNumMwmId, 0, 3, false}});
|
||||
}
|
||||
|
||||
// Roads R1:
|
||||
//
|
||||
// -2
|
||||
// -1
|
||||
// R0 -2 -1 0 1 2
|
||||
// 1
|
||||
// 2
|
||||
//
|
||||
UNIT_TEST(FindPathCross)
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
loader->AddRoad(0 /* featureId */, false, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{-2.0, 0.0}, {-1.0, 0.0}, {0.0, 0.0}, {1.0, 0.0}, {2.0, 0.0}}));
|
||||
loader->AddRoad(1 /* featureId */, false, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, -2.0}, {0.0, -1.0}, {0.0, 0.0}, {0.0, 1.0}, {0.0, 2.0}}));
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
unique_ptr<WorldGraph> worldGraph = BuildWorldGraph(std::move(loader), estimator, {MakeJoint({{0, 2}, {1, 2}})});
|
||||
|
||||
vector<FakeEnding> endPoints;
|
||||
for (uint32_t i = 0; i < 4; ++i)
|
||||
{
|
||||
endPoints.push_back(MakeFakeEnding(0 /* featureId */, i /* segmentIdx */, m2::PointD(-1.5 + i, 0.0), *worldGraph));
|
||||
endPoints.push_back(MakeFakeEnding(1, i, m2::PointD(0.0, -1.5 + i), *worldGraph));
|
||||
}
|
||||
|
||||
for (auto const & start : endPoints)
|
||||
{
|
||||
for (auto const & finish : endPoints)
|
||||
{
|
||||
uint32_t expectedLength = 0;
|
||||
if (start.m_projections[0].m_segment.GetFeatureId() == finish.m_projections[0].m_segment.GetFeatureId())
|
||||
{
|
||||
expectedLength = AbsDelta(start.m_projections[0].m_segment.GetSegmentIdx(),
|
||||
finish.m_projections[0].m_segment.GetSegmentIdx()) +
|
||||
1;
|
||||
}
|
||||
else
|
||||
{
|
||||
if (start.m_projections[0].m_segment.GetSegmentIdx() < 2)
|
||||
expectedLength += 2 - start.m_projections[0].m_segment.GetSegmentIdx();
|
||||
else
|
||||
expectedLength += start.m_projections[0].m_segment.GetSegmentIdx() - 1;
|
||||
|
||||
if (finish.m_projections[0].m_segment.GetSegmentIdx() < 2)
|
||||
expectedLength += 2 - finish.m_projections[0].m_segment.GetSegmentIdx();
|
||||
else
|
||||
expectedLength += finish.m_projections[0].m_segment.GetSegmentIdx() - 1;
|
||||
}
|
||||
TestRoute(start, finish, expectedLength, nullptr /* expectedRoute */, kUnknownWeight, *worldGraph);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Roads R4 R5 R6 R7
|
||||
//
|
||||
// R0 0 - * - * - *
|
||||
// | | | |
|
||||
// R1 * - 1 - * - *
|
||||
// | | | |
|
||||
// R2 * - * - 2 - *
|
||||
// | | | |
|
||||
// R3 * - * - * - 3
|
||||
//
|
||||
UNIT_TEST(FindPathManhattan)
|
||||
{
|
||||
uint32_t constexpr kCitySize = 4;
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
for (uint32_t i = 0; i < kCitySize; ++i)
|
||||
{
|
||||
RoadGeometry::Points street;
|
||||
RoadGeometry::Points avenue;
|
||||
for (uint32_t j = 0; j < kCitySize; ++j)
|
||||
{
|
||||
street.emplace_back(static_cast<double>(j), static_cast<double>(i));
|
||||
avenue.emplace_back(static_cast<double>(i), static_cast<double>(j));
|
||||
}
|
||||
loader->AddRoad(i, false, 1.0 /* speed */, street);
|
||||
loader->AddRoad(i + kCitySize, false, 1.0 /* speed */, avenue);
|
||||
}
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
|
||||
vector<Joint> joints;
|
||||
for (uint32_t i = 0; i < kCitySize; ++i)
|
||||
for (uint32_t j = 0; j < kCitySize; ++j)
|
||||
joints.emplace_back(MakeJoint({{i, j}, {j + kCitySize, i}}));
|
||||
|
||||
unique_ptr<WorldGraph> worldGraph = BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
|
||||
vector<FakeEnding> endPoints;
|
||||
for (uint32_t featureId = 0; featureId < kCitySize; ++featureId)
|
||||
{
|
||||
for (uint32_t segmentId = 0; segmentId < kCitySize - 1; ++segmentId)
|
||||
{
|
||||
endPoints.push_back(MakeFakeEnding(featureId, segmentId, m2::PointD(0.5 + segmentId, featureId), *worldGraph));
|
||||
endPoints.push_back(
|
||||
MakeFakeEnding(featureId + kCitySize, segmentId, m2::PointD(featureId, 0.5 + segmentId), *worldGraph));
|
||||
}
|
||||
}
|
||||
|
||||
for (auto const & start : endPoints)
|
||||
{
|
||||
for (auto const & finish : endPoints)
|
||||
{
|
||||
uint32_t expectedLength = 0;
|
||||
|
||||
auto const startFeatureOffset = start.m_projections[0].m_segment.GetFeatureId() < kCitySize
|
||||
? start.m_projections[0].m_segment.GetFeatureId()
|
||||
: start.m_projections[0].m_segment.GetFeatureId() - kCitySize;
|
||||
auto const finishFeatureOffset = finish.m_projections[0].m_segment.GetFeatureId() < kCitySize
|
||||
? finish.m_projections[0].m_segment.GetFeatureId()
|
||||
: finish.m_projections[0].m_segment.GetFeatureId() - kCitySize;
|
||||
|
||||
if ((start.m_projections[0].m_segment.GetFeatureId() < kCitySize) ==
|
||||
(finish.m_projections[0].m_segment.GetFeatureId() < kCitySize))
|
||||
{
|
||||
uint32_t segDelta = AbsDelta(start.m_projections[0].m_segment.GetSegmentIdx(),
|
||||
finish.m_projections[0].m_segment.GetSegmentIdx());
|
||||
if (segDelta == 0 &&
|
||||
start.m_projections[0].m_segment.GetFeatureId() != finish.m_projections[0].m_segment.GetFeatureId())
|
||||
segDelta = 1;
|
||||
expectedLength += segDelta;
|
||||
expectedLength += AbsDelta(startFeatureOffset, finishFeatureOffset) + 1;
|
||||
}
|
||||
else
|
||||
{
|
||||
if (start.m_projections[0].m_segment.GetSegmentIdx() < finishFeatureOffset)
|
||||
expectedLength += finishFeatureOffset - start.m_projections[0].m_segment.GetSegmentIdx();
|
||||
else
|
||||
expectedLength += start.m_projections[0].m_segment.GetSegmentIdx() - finishFeatureOffset + 1;
|
||||
|
||||
if (finish.m_projections[0].m_segment.GetSegmentIdx() < startFeatureOffset)
|
||||
expectedLength += startFeatureOffset - finish.m_projections[0].m_segment.GetSegmentIdx();
|
||||
else
|
||||
expectedLength += finish.m_projections[0].m_segment.GetSegmentIdx() - startFeatureOffset + 1;
|
||||
}
|
||||
|
||||
TestRoute(start, finish, expectedLength, nullptr /* expectedRoute */, kUnknownWeight, *worldGraph);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Roads y:
|
||||
//
|
||||
// fast road R0 * - * - * -1
|
||||
// ╱ ╲
|
||||
// slow road R1 * - - * - - * - - * - - * 0
|
||||
// J0 J1
|
||||
//
|
||||
// x: 0 1 2 3 4 5 6
|
||||
//
|
||||
UNIT_TEST(RoadSpeed)
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
|
||||
loader->AddRoad(0 /* featureId */, false, 10.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 0.0}, {2.0, -1.0}, {3.0, -1.0}, {4.0, -1.0}, {5.0, 0.0}}));
|
||||
|
||||
loader->AddRoad(1 /* featureId */, false, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 0.0}, {1.0, 0.0}, {3.0, 0.0}, {5.0, 0.0}, {6.0, 0.0}}));
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
|
||||
vector<Joint> joints;
|
||||
joints.emplace_back(MakeJoint({{0, 0}, {1, 1}})); // J0
|
||||
joints.emplace_back(MakeJoint({{0, 4}, {1, 3}})); // J1
|
||||
|
||||
unique_ptr<WorldGraph> worldGraph = BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
|
||||
auto const start = MakeFakeEnding(1 /* featureId */, 0 /* segmentIdx */, m2::PointD(0.5, 0), *worldGraph);
|
||||
auto const finish = MakeFakeEnding(1, 3, m2::PointD(5.5, 0), *worldGraph);
|
||||
|
||||
vector<Segment> const expectedRoute({{kTestNumMwmId, 1, 0, true},
|
||||
{kTestNumMwmId, 0, 0, true},
|
||||
{kTestNumMwmId, 0, 1, true},
|
||||
{kTestNumMwmId, 0, 2, true},
|
||||
{kTestNumMwmId, 0, 3, true},
|
||||
{kTestNumMwmId, 1, 3, true}});
|
||||
double const expectedWeight = mercator::DistanceOnEarth({0.5, 0.0}, {1.0, 0.0}) / KmphToMps(1.0) +
|
||||
mercator::DistanceOnEarth({1.0, 0.0}, {2.0, -1.0}) / KmphToMps(10.0) +
|
||||
mercator::DistanceOnEarth({2.0, -1.0}, {4.0, -1.0}) / KmphToMps(10.0) +
|
||||
mercator::DistanceOnEarth({4.0, -1.0}, {5.0, 0.0}) / KmphToMps(10.0) +
|
||||
mercator::DistanceOnEarth({5.0, 0.0}, {5.5, 0.0}) / KmphToMps(1.0);
|
||||
TestRoute(start, finish, expectedRoute.size(), &expectedRoute, expectedWeight, *worldGraph);
|
||||
}
|
||||
|
||||
// Roads y:
|
||||
//
|
||||
// R0 * - - - - - - - - * 0
|
||||
// ^ ^
|
||||
// start finish
|
||||
//
|
||||
// x: 0 1 2 3
|
||||
//
|
||||
UNIT_TEST(OneSegmentWay)
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
|
||||
loader->AddRoad(0 /* featureId */, false, 1.0 /* speed */, RoadGeometry::Points({{0.0, 0.0}, {3.0, 0.0}}));
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
unique_ptr<WorldGraph> worldGraph = BuildWorldGraph(std::move(loader), estimator, vector<Joint>());
|
||||
vector<Segment> const expectedRoute({{kTestNumMwmId, 0 /* featureId */, 0 /* seg id */, true /* forward */}});
|
||||
|
||||
// Starter must match any combination of start and finish directions.
|
||||
vector<bool> const tf = {{true, false}};
|
||||
for (auto const startIsForward : tf)
|
||||
{
|
||||
for (auto const finishIsForward : tf)
|
||||
{
|
||||
auto const start =
|
||||
MakeFakeEnding({Segment(kTestNumMwmId, 0, 0, startIsForward)}, m2::PointD(1.0, 0.0), *worldGraph);
|
||||
auto const finish =
|
||||
MakeFakeEnding({Segment(kTestNumMwmId, 0, 0, finishIsForward)}, m2::PointD(2.0, 0.0), *worldGraph);
|
||||
|
||||
auto const expectedWeight = mercator::DistanceOnEarth({1.0, 0.0}, {2.0, 0.0}) / KmphToMps(1.0);
|
||||
TestRoute(start, finish, expectedRoute.size(), &expectedRoute, expectedWeight, *worldGraph);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
//
|
||||
// Roads y:
|
||||
//
|
||||
// R0 * - - - - - - - ->* 0
|
||||
// ^ ^
|
||||
// finish start
|
||||
//
|
||||
// x: 0 1 2 3
|
||||
//
|
||||
UNIT_TEST(OneSegmentWayBackward)
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
|
||||
loader->AddRoad(0 /* featureId */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 0.0}, {3.0, 0.0}}));
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
unique_ptr<WorldGraph> worldGraph = BuildWorldGraph(std::move(loader), estimator, vector<Joint>());
|
||||
|
||||
auto const start = MakeFakeEnding(0 /* featureId */, 0 /* segmentIdx */, m2::PointD(2, 0), *worldGraph);
|
||||
auto const finish = MakeFakeEnding(0, 0, m2::PointD(1, 0), *worldGraph);
|
||||
|
||||
auto starter = MakeStarter(start, finish, *worldGraph);
|
||||
vector<Segment> route;
|
||||
double timeSec;
|
||||
auto const resultCode = CalculateRoute(*starter, route, timeSec);
|
||||
TEST_EQUAL(resultCode, AlgorithmForIndexGraphStarter::Result::NoPath, ());
|
||||
}
|
||||
|
||||
// Roads y:
|
||||
//
|
||||
// R0 * - - - - - * - - - - - * R1 0
|
||||
// ^ ^
|
||||
// start finish
|
||||
//
|
||||
// x: 0 1 2 3 4
|
||||
//
|
||||
UNIT_TEST(FakeSegmentCoordinates)
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
|
||||
loader->AddRoad(0 /* featureId */, false, 1.0 /* speed */, RoadGeometry::Points({{0.0, 0.0}, {2.0, 0.0}}));
|
||||
loader->AddRoad(1 /* featureId */, false, 1.0 /* speed */, RoadGeometry::Points({{2.0, 0.0}, {4.0, 0.0}}));
|
||||
|
||||
vector<Joint> joints;
|
||||
joints.emplace_back(MakeJoint({{0 /* featureId */, 1 /* pointId */}, {1, 0}}));
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
unique_ptr<WorldGraph> worldGraph = BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
vector<m2::PointD> const expectedGeom = {{1.0 /* x */, 0.0 /* y */}, {2.0, 0.0}, {3.0, 0.0}};
|
||||
|
||||
// Test fake segments have valid coordinates for any combination of start and finish directions
|
||||
vector<bool> const tf = {{true, false}};
|
||||
for (auto const startIsForward : tf)
|
||||
{
|
||||
for (auto const finishIsForward : tf)
|
||||
{
|
||||
auto const start = MakeFakeEnding({Segment(kTestNumMwmId, 0, 0, startIsForward)}, m2::PointD(1, 0), *worldGraph);
|
||||
auto const finish =
|
||||
MakeFakeEnding({Segment(kTestNumMwmId, 1, 0, finishIsForward)}, m2::PointD(3, 0), *worldGraph);
|
||||
|
||||
auto starter = MakeStarter(start, finish, *worldGraph);
|
||||
TestRouteGeometry(*starter, AlgorithmForIndexGraphStarter::Result::OK, expectedGeom);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// start finish
|
||||
// * *
|
||||
// | | R1
|
||||
// | | *
|
||||
// * - - - - - - - - - - - - - - - - - - - - - - - *
|
||||
// R0
|
||||
//
|
||||
// x: 0 1 2 3 4 5 6 7 8
|
||||
//
|
||||
UNIT_TEST(FakeEndingAStarInvariant)
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
|
||||
loader->AddRoad(0 /* featureId */, false, 1.0 /* speed */, RoadGeometry::Points({{0.0, 0.0}, {8.0, 0.0}}));
|
||||
loader->AddRoad(1 /* featureId */, false, 1.0 /* speed */, RoadGeometry::Points({{8.0, 0.0}, {8.0, 1.0 / 1000.0}}));
|
||||
|
||||
vector<Joint> joints;
|
||||
joints.emplace_back(MakeJoint({{0 /* featureId */, 1 /* pointId */}, {1, 0}}));
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
unique_ptr<WorldGraph> worldGraph = BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
vector<Segment> const expectedRoute({{kTestNumMwmId, 0 /* featureId */, 0 /* seg id */, true /* forward */}});
|
||||
|
||||
auto const start = MakeFakeEnding(0 /* featureId */, 0 /* segmentIdx */, m2::PointD(1.0, 1.0), *worldGraph);
|
||||
auto const finish = MakeFakeEnding(0, 0, m2::PointD(2.0, 1.0), *worldGraph);
|
||||
|
||||
auto const expectedWeight = estimator->CalcOffroad({1.0, 1.0}, {1.0, 0.0}, EdgeEstimator::Purpose::Weight) +
|
||||
mercator::DistanceOnEarth({1.0, 0.0}, {2.0, 0.0}) / KmphToMps(1.0) +
|
||||
estimator->CalcOffroad({2.0, 0.0}, {2.0, 1.0}, EdgeEstimator::Purpose::Weight);
|
||||
TestRoute(start, finish, expectedRoute.size(), &expectedRoute, expectedWeight, *worldGraph);
|
||||
}
|
||||
|
||||
//
|
||||
// Road R0 (ped) R1 (car) R2 (car)
|
||||
// 0----------1 * 0----------1 * 0----------1
|
||||
// Joints J0 J1
|
||||
//
|
||||
UNIT_TEST(SerializeSimpleGraph)
|
||||
{
|
||||
vector<uint8_t> buffer;
|
||||
{
|
||||
IndexGraph graph;
|
||||
vector<Joint> joints = {
|
||||
MakeJoint({{0, 1}, {1, 0}}),
|
||||
MakeJoint({{1, 1}, {2, 0}}),
|
||||
};
|
||||
graph.Import(joints);
|
||||
unordered_map<uint32_t, VehicleMask> masks;
|
||||
masks[0] = kPedestrianMask;
|
||||
masks[1] = kCarMask;
|
||||
masks[2] = kCarMask;
|
||||
|
||||
MemWriter<vector<uint8_t>> writer(buffer);
|
||||
IndexGraphSerializer::Serialize(graph, masks, writer);
|
||||
}
|
||||
|
||||
{
|
||||
IndexGraph graph;
|
||||
MemReader reader(buffer.data(), buffer.size());
|
||||
ReaderSource<MemReader> source(reader);
|
||||
IndexGraphSerializer::Deserialize(graph, source, kAllVehiclesMask);
|
||||
|
||||
TEST_EQUAL(graph.GetNumRoads(), 3, ());
|
||||
TEST_EQUAL(graph.GetNumJoints(), 2, ());
|
||||
TEST_EQUAL(graph.GetNumPoints(), 4, ());
|
||||
|
||||
TEST_EQUAL(graph.GetJointId({0, 0}), Joint::kInvalidId, ());
|
||||
TEST_EQUAL(graph.GetJointId({0, 1}), 1, ());
|
||||
TEST_EQUAL(graph.GetJointId({1, 0}), 1, ());
|
||||
TEST_EQUAL(graph.GetJointId({1, 1}), 0, ());
|
||||
TEST_EQUAL(graph.GetJointId({2, 0}), 0, ());
|
||||
TEST_EQUAL(graph.GetJointId({2, 1}), Joint::kInvalidId, ());
|
||||
}
|
||||
|
||||
{
|
||||
IndexGraph graph;
|
||||
MemReader reader(buffer.data(), buffer.size());
|
||||
ReaderSource<MemReader> source(reader);
|
||||
IndexGraphSerializer::Deserialize(graph, source, kCarMask);
|
||||
|
||||
TEST_EQUAL(graph.GetNumRoads(), 2, ());
|
||||
TEST_EQUAL(graph.GetNumJoints(), 1, ());
|
||||
TEST_EQUAL(graph.GetNumPoints(), 2, ());
|
||||
|
||||
TEST_EQUAL(graph.GetJointId({0, 0}), Joint::kInvalidId, ());
|
||||
TEST_EQUAL(graph.GetJointId({0, 1}), Joint::kInvalidId, ());
|
||||
TEST_EQUAL(graph.GetJointId({1, 0}), Joint::kInvalidId, ());
|
||||
TEST_EQUAL(graph.GetJointId({1, 1}), 0, ());
|
||||
TEST_EQUAL(graph.GetJointId({2, 0}), 0, ());
|
||||
TEST_EQUAL(graph.GetJointId({2, 1}), Joint::kInvalidId, ());
|
||||
}
|
||||
}
|
||||
|
||||
// Finish
|
||||
// 0.0004 *
|
||||
// ^
|
||||
// |
|
||||
// F2
|
||||
// |
|
||||
// |
|
||||
// 0.0003 6*---------*5
|
||||
// | |
|
||||
// | |
|
||||
// | |
|
||||
// | |
|
||||
// | |
|
||||
// 0.0002 7* *4
|
||||
// | |
|
||||
// | |
|
||||
// 0.00015 8* F0 *3
|
||||
// \ /
|
||||
// \ / 1 0
|
||||
// 0.0001 9*---F0-*----*
|
||||
// 2 ^
|
||||
// |
|
||||
// F1
|
||||
// |
|
||||
// |
|
||||
// 0 * Start
|
||||
// 0 0.0001 0.0002
|
||||
// F0 is a two-way feature with a loop and F1 and F2 are an one-way one-segment features.
|
||||
unique_ptr<SingleVehicleWorldGraph> BuildLoopGraph()
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
loader->AddRoad(0 /* feature id */, false /* one way */, 100.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0002, 0.0001},
|
||||
{0.00015, 0.0001},
|
||||
{0.0001, 0.0001},
|
||||
{0.00015, 0.00015},
|
||||
{0.00015, 0.0002},
|
||||
{0.00015, 0.0003},
|
||||
{0.00005, 0.0003},
|
||||
{0.00005, 0.0002},
|
||||
{0.00005, 0.00015},
|
||||
{0.0001, 0.0001}}));
|
||||
loader->AddRoad(1 /* feature id */, true /* one way */, 100.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0002, 0.0}, {0.0002, 0.0001}}));
|
||||
loader->AddRoad(2 /* feature id */, true /* one way */, 100.0 /* speed */,
|
||||
RoadGeometry::Points({{0.00005, 0.0003}, {0.00005, 0.0004}}));
|
||||
|
||||
vector<Joint> const joints = {
|
||||
MakeJoint({{0 /* feature id */, 2 /* point id */}, {0, 9}}), /* joint at point (0.0002, 0) */
|
||||
MakeJoint({{1, 1}, {0, 0}}), /* joint at point (0.0002, 0.0001) */
|
||||
MakeJoint({{0, 6}, {2, 0}}), /* joint at point (0.00005, 0.0003) */
|
||||
MakeJoint({{2, 1}}), /* joint at point (0.00005, 0.0004) */
|
||||
};
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
return BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
}
|
||||
|
||||
// This test checks that the route from Start to Finish doesn't make an extra loop in F0.
|
||||
// If it was so the route time had been much more.
|
||||
UNIT_CLASS_TEST(RestrictionTest, LoopGraph)
|
||||
{
|
||||
Init(BuildLoopGraph());
|
||||
auto start = MakeFakeEnding(1 /* featureId */, 0 /* segmentIdx */, m2::PointD(0.0002, 0), *m_graph);
|
||||
auto finish = MakeFakeEnding(2, 0, m2::PointD(0.00005, 0.0004), *m_graph);
|
||||
|
||||
vector<Segment> const expectedRoute = {{kTestNumMwmId, 1, 0, true}, {kTestNumMwmId, 0, 0, true},
|
||||
{kTestNumMwmId, 0, 1, true}, {kTestNumMwmId, 0, 8, false},
|
||||
{kTestNumMwmId, 0, 7, false}, {kTestNumMwmId, 0, 6, false},
|
||||
{kTestNumMwmId, 2, 0, true}};
|
||||
|
||||
auto const expectedWeight = mercator::DistanceOnEarth({0.0002, 0.0}, {0.0002, 0.0001}) / KmphToMps(100.0) +
|
||||
mercator::DistanceOnEarth({0.0002, 0.0001}, {0.00015, 0.0001}) / KmphToMps(100.0) +
|
||||
mercator::DistanceOnEarth({0.00015, 0.0001}, {0.0001, 0.0001}) / KmphToMps(100.0) +
|
||||
mercator::DistanceOnEarth({0.0001, 0.0001}, {0.00005, 0.00015}) / KmphToMps(100.0) +
|
||||
mercator::DistanceOnEarth({0.00005, 0.00015}, {0.00005, 0.0002}) / KmphToMps(100.0) +
|
||||
mercator::DistanceOnEarth({0.00005, 0.0002}, {0.00005, 0.0003}) / KmphToMps(100.0) +
|
||||
mercator::DistanceOnEarth({0.00005, 0.0003}, {0.00005, 0.0004}) / KmphToMps(100.0);
|
||||
TestRoute(start, finish, expectedRoute.size(), &expectedRoute, expectedWeight, *m_graph);
|
||||
}
|
||||
|
||||
UNIT_TEST(IndexGraph_OnlyTopology_1)
|
||||
{
|
||||
// Add edges to the graph in the following format: (from, to, weight).
|
||||
|
||||
uint32_t const numVertices = 5;
|
||||
TestIndexGraphTopology graph(numVertices);
|
||||
graph.AddDirectedEdge(0, 1, 1.0);
|
||||
graph.AddDirectedEdge(0, 2, 2.0);
|
||||
graph.AddDirectedEdge(1, 3, 1.0);
|
||||
graph.AddDirectedEdge(2, 3, 2.0);
|
||||
|
||||
double const expectedWeight = 2.0;
|
||||
vector<TestEdge> const expectedEdges = {{0, 1}, {1, 3}};
|
||||
|
||||
TestTopologyGraph(graph, 0, 3, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
TestTopologyGraph(graph, 0, 4, false /* pathFound */, 0.0, {});
|
||||
}
|
||||
|
||||
UNIT_TEST(IndexGraph_OnlyTopology_2)
|
||||
{
|
||||
uint32_t const numVertices = 1;
|
||||
TestIndexGraphTopology graph(numVertices);
|
||||
graph.AddDirectedEdge(0, 0, 100.0);
|
||||
|
||||
double const expectedWeight = 0.0;
|
||||
vector<TestEdge> const expectedEdges = {};
|
||||
|
||||
TestTopologyGraph(graph, 0, 0, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
}
|
||||
|
||||
UNIT_TEST(IndexGraph_OnlyTopology_3)
|
||||
{
|
||||
uint32_t const numVertices = 2;
|
||||
TestIndexGraphTopology graph(numVertices);
|
||||
|
||||
graph.AddDirectedEdge(0, 1, 1.0);
|
||||
graph.AddDirectedEdge(1, 0, 1.0);
|
||||
double const expectedWeight = 1.0;
|
||||
vector<TestEdge> const expectedEdges = {{0, 1}};
|
||||
|
||||
TestTopologyGraph(graph, 0, 1, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
}
|
||||
|
||||
// ^ edge1 (-0.002, 0) - (-0.002, 0.002)
|
||||
// |
|
||||
// | ^ direction vector (0, 0.001)
|
||||
// | |
|
||||
// *-------*-------> edge2 (-0.002, 0) - (0.002, 0)
|
||||
// point (0, 0)
|
||||
//
|
||||
// Test that a codirectional edge is always better than others.
|
||||
UNIT_TEST(BestEdgeComparator_OneCodirectionalEdge)
|
||||
{
|
||||
Edge const edge1 = Edge::MakeFake(geometry::MakePointWithAltitudeForTesting({-0.002, 0.0}),
|
||||
geometry::MakePointWithAltitudeForTesting({-0.002, 0.002}));
|
||||
Edge const edge2 = Edge::MakeFake(geometry::MakePointWithAltitudeForTesting({-0.002, 0.0}),
|
||||
geometry::MakePointWithAltitudeForTesting({0.002, 0.0}));
|
||||
IndexRouter::BestEdgeComparator bestEdgeComparator(m2::PointD(0.0, 0.0), m2::PointD(0.0, 0.001));
|
||||
|
||||
TEST_EQUAL(bestEdgeComparator.Compare(edge1, edge2), -1, ());
|
||||
}
|
||||
|
||||
//
|
||||
// ^ edge1 (-0.002, 0) - (-0.002, 0.004)
|
||||
// |
|
||||
// |
|
||||
// |
|
||||
// ^ ^ edge2 (0, 0) - (0, 0.002)
|
||||
// | |
|
||||
// | ^ direction vector (0, 0.001)
|
||||
// | |
|
||||
// *-------*
|
||||
// point (0, 0)
|
||||
//
|
||||
// Test that if there are two codirectional edges the closest one to |point| is better.
|
||||
UNIT_TEST(BestEdgeComparator_TwoCodirectionalEdges)
|
||||
{
|
||||
Edge const edge1 = Edge::MakeFake(geometry::MakePointWithAltitudeForTesting({-0.002, 0.0}),
|
||||
geometry::MakePointWithAltitudeForTesting({-0.002, 0.004}));
|
||||
Edge const edge2 = Edge::MakeFake(geometry::MakePointWithAltitudeForTesting({0.0, 0.0}),
|
||||
geometry::MakePointWithAltitudeForTesting({0.0, 0.002}));
|
||||
IndexRouter::BestEdgeComparator bestEdgeComparator(m2::PointD(0.0, 0.0), m2::PointD(0.0, 0.001));
|
||||
|
||||
TEST_EQUAL(bestEdgeComparator.Compare(edge1, edge2), 1, ());
|
||||
}
|
||||
|
||||
// *---------------> edge1 (-0.002, 0.002) - (0.002, 0.002)
|
||||
//
|
||||
// ^ direction vector (0, 0.001)
|
||||
// |
|
||||
// *-------*-------> edge2 (-0.002, 0) - (0.002, 0)
|
||||
// point (0, 0)
|
||||
//
|
||||
// Test that if two edges are not codirectional the closet one to |point| is better.
|
||||
UNIT_TEST(BestEdgeComparator_TwoNotCodirectionalEdges)
|
||||
{
|
||||
Edge const edge1 = Edge::MakeFake(geometry::MakePointWithAltitudeForTesting({-0.002, 0.002}),
|
||||
geometry::MakePointWithAltitudeForTesting({0.002, 0.002}));
|
||||
Edge const edge2 = Edge::MakeFake(geometry::MakePointWithAltitudeForTesting({-0.002, 0.0}),
|
||||
geometry::MakePointWithAltitudeForTesting({0.002, 0.0}));
|
||||
IndexRouter::BestEdgeComparator bestEdgeComparator(m2::PointD(0.0, 0.0), m2::PointD(0.0, 0.001));
|
||||
|
||||
TEST_EQUAL(bestEdgeComparator.Compare(edge1, edge2), 1, ());
|
||||
}
|
||||
|
||||
// point(0, 0.001)
|
||||
// *--> direction vector (0.001, 0)
|
||||
//
|
||||
// edge1 (-0.002, 0) - (0.002, 0) <-------------> edge2 (0.002, 0) - (-0.002, 0)
|
||||
// (0, 0)
|
||||
//
|
||||
// Test that if two edges are made by one bidirectional feature the one which have almost the same direction is better.
|
||||
UNIT_TEST(BestEdgeComparator_TwoEdgesOfOneFeature)
|
||||
{
|
||||
// Please see a note in class Edge definition about start and end point of Edge.
|
||||
Edge const edge1 = Edge::MakeFake(geometry::MakePointWithAltitudeForTesting({-0.002, 0.0}),
|
||||
geometry::MakePointWithAltitudeForTesting({0.002, 0.0}));
|
||||
Edge const edge2 = edge1.GetReverseEdge();
|
||||
|
||||
IndexRouter::BestEdgeComparator bestEdgeComparator(m2::PointD(0.0, 0.001), m2::PointD(0.001, 0.0));
|
||||
|
||||
TEST_EQUAL(bestEdgeComparator.Compare(edge1, edge2), -1, ());
|
||||
TEST_EQUAL(bestEdgeComparator.Compare(edge2, edge1), 1, ());
|
||||
}
|
||||
|
||||
// Roads
|
||||
//
|
||||
// R0 * - - - - -** R1
|
||||
// ^ ^
|
||||
// start finish
|
||||
//
|
||||
// x: 0 1 2 3 4 5
|
||||
//
|
||||
UNIT_TEST(FinishNearZeroEdge)
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
|
||||
loader->AddRoad(0 /* featureId */, false, 1.0 /* speed */, RoadGeometry::Points({{2.0, 0.0}, {4.0, 0.0}}));
|
||||
loader->AddRoad(1 /* featureId */, false, 1.0 /* speed */, RoadGeometry::Points({{4.0, 0.0}, {4.0, 0.0}}));
|
||||
|
||||
vector<Joint> joints;
|
||||
joints.emplace_back(MakeJoint({{0 /* featureId */, 1 /* pointId */}, {1, 0}}));
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
unique_ptr<WorldGraph> worldGraph = BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
auto const start =
|
||||
MakeFakeEnding({Segment(kTestNumMwmId, 0, 0, true /* forward */)}, m2::PointD(1.0, 0.0), *worldGraph);
|
||||
auto const finish =
|
||||
MakeFakeEnding({Segment(kTestNumMwmId, 1, 0, false /* forward */)}, m2::PointD(5.0, 0.0), *worldGraph);
|
||||
auto starter = MakeStarter(start, finish, *worldGraph);
|
||||
|
||||
vector<m2::PointD> const expectedGeom = {{1.0 /* x */, 0.0 /* y */}, {2.0, 0.0}, {4.0, 0.0}, {5.0, 0.0}};
|
||||
TestRouteGeometry(*starter, AlgorithmForIndexGraphStarter::Result::OK, expectedGeom);
|
||||
}
|
||||
} // namespace index_graph_test
|
||||
649
libs/routing/routing_tests/index_graph_tools.cpp
Normal file
649
libs/routing/routing_tests/index_graph_tools.cpp
Normal file
|
|
@ -0,0 +1,649 @@
|
|||
#include "routing/routing_tests/index_graph_tools.hpp"
|
||||
|
||||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/base/routing_result.hpp"
|
||||
#include "routing/geometry.hpp"
|
||||
#include "routing/routing_helpers.hpp"
|
||||
|
||||
#include "transit/transit_version.hpp"
|
||||
|
||||
#include "base/assert.hpp"
|
||||
#include "base/math.hpp"
|
||||
|
||||
#include <unordered_map>
|
||||
|
||||
#include "3party/opening_hours/opening_hours.hpp"
|
||||
|
||||
namespace routing_test
|
||||
{
|
||||
using namespace std;
|
||||
|
||||
double constexpr kEpsilon = 1e-6;
|
||||
|
||||
template <typename Graph>
|
||||
Graph & GetGraph(unordered_map<NumMwmId, unique_ptr<Graph>> const & graphs, NumMwmId mwmId)
|
||||
{
|
||||
auto it = graphs.find(mwmId);
|
||||
CHECK(it != graphs.end(), ("Not found graph for mwm", mwmId));
|
||||
return *it->second;
|
||||
}
|
||||
|
||||
template <typename Graph>
|
||||
void AddGraph(unordered_map<NumMwmId, unique_ptr<Graph>> & graphs, NumMwmId mwmId, unique_ptr<Graph> graph)
|
||||
{
|
||||
auto it = graphs.find(mwmId);
|
||||
CHECK(it == graphs.end(), ("Already contains graph for mwm", mwmId));
|
||||
graphs[mwmId] = std::move(graph);
|
||||
}
|
||||
|
||||
// RestrictionTest ---------------------------------------------------------------------------------
|
||||
void RestrictionTest::SetStarter(FakeEnding const & start, FakeEnding const & finish)
|
||||
{
|
||||
CHECK(m_graph != nullptr, ("Init() was not called."));
|
||||
m_starter = MakeStarter(start, finish, *m_graph);
|
||||
}
|
||||
|
||||
void RestrictionTest::SetRestrictions(RestrictionVec && restrictions)
|
||||
{
|
||||
m_graph->GetIndexGraphForTests(kTestNumMwmId).SetRestrictions(std::move(restrictions));
|
||||
}
|
||||
|
||||
void RestrictionTest::SetUTurnRestrictions(vector<RestrictionUTurn> && restrictions)
|
||||
{
|
||||
m_graph->GetIndexGraphForTests(kTestNumMwmId).SetUTurnRestrictions(std::move(restrictions));
|
||||
}
|
||||
|
||||
// NoUTurnRestrictionTest --------------------------------------------------------------------------
|
||||
void NoUTurnRestrictionTest::Init(unique_ptr<SingleVehicleWorldGraph> graph)
|
||||
{
|
||||
m_graph = make_unique<WorldGraphForAStar>(std::move(graph));
|
||||
}
|
||||
|
||||
void NoUTurnRestrictionTest::SetRestrictions(RestrictionVec && restrictions)
|
||||
{
|
||||
auto & indexGraph = m_graph->GetWorldGraph().GetIndexGraph(kTestNumMwmId);
|
||||
indexGraph.SetRestrictions(std::move(restrictions));
|
||||
}
|
||||
|
||||
void NoUTurnRestrictionTest::SetNoUTurnRestrictions(vector<RestrictionUTurn> && restrictions)
|
||||
{
|
||||
auto & indexGraph = m_graph->GetWorldGraph().GetIndexGraph(kTestNumMwmId);
|
||||
indexGraph.SetUTurnRestrictions(std::move(restrictions));
|
||||
}
|
||||
|
||||
void NoUTurnRestrictionTest::TestRouteGeom(Segment const & start, Segment const & finish,
|
||||
AlgorithmForWorldGraph::Result expectedRouteResult,
|
||||
vector<m2::PointD> const & expectedRouteGeom)
|
||||
{
|
||||
AlgorithmForWorldGraph algorithm;
|
||||
AlgorithmForWorldGraph::ParamsForTests<> params(*m_graph, start, finish);
|
||||
|
||||
RoutingResult<Segment, RouteWeight> routingResult;
|
||||
auto const resultCode = algorithm.FindPathBidirectional(params, routingResult);
|
||||
|
||||
TEST_EQUAL(resultCode, expectedRouteResult, ());
|
||||
for (size_t i = 0; i < routingResult.m_path.size(); ++i)
|
||||
{
|
||||
static auto constexpr kEps = 1e-3;
|
||||
auto const point = m_graph->GetWorldGraph().GetPoint(routingResult.m_path[i], true /* forward */);
|
||||
if (!AlmostEqualAbs(mercator::FromLatLon(point), expectedRouteGeom[i], kEps))
|
||||
TEST(false, ("Coords missmated at index:", i, "expected:", expectedRouteGeom[i], "received:", point));
|
||||
}
|
||||
}
|
||||
|
||||
// ZeroGeometryLoader ------------------------------------------------------------------------------
|
||||
void ZeroGeometryLoader::Load(uint32_t /* featureId */, routing::RoadGeometry & road)
|
||||
{
|
||||
// Any valid road will do.
|
||||
auto const points = routing::RoadGeometry::Points({{0.0, 0.0}, {0.0, 1.0}});
|
||||
road = RoadGeometry(true /* oneWay */, 1.0 /* weightSpeedKMpH */, 1.0 /* etaSpeedKMpH */, points);
|
||||
}
|
||||
|
||||
// TestIndexGraphLoader ----------------------------------------------------------------------------
|
||||
IndexGraph & TestIndexGraphLoader::GetIndexGraph(NumMwmId mwmId)
|
||||
{
|
||||
return GetGraph(m_graphs, mwmId);
|
||||
}
|
||||
|
||||
Geometry & TestIndexGraphLoader::GetGeometry(NumMwmId mwmId)
|
||||
{
|
||||
return GetIndexGraph(mwmId).GetGeometry();
|
||||
}
|
||||
|
||||
void TestIndexGraphLoader::Clear()
|
||||
{
|
||||
m_graphs.clear();
|
||||
}
|
||||
|
||||
void TestIndexGraphLoader::AddGraph(NumMwmId mwmId, unique_ptr<IndexGraph> graph)
|
||||
{
|
||||
routing_test::AddGraph(m_graphs, mwmId, std::move(graph));
|
||||
}
|
||||
|
||||
// TestTransitGraphLoader ----------------------------------------------------------------------------
|
||||
TransitGraph & TestTransitGraphLoader::GetTransitGraph(NumMwmId mwmId, IndexGraph &)
|
||||
{
|
||||
return GetGraph(m_graphs, mwmId);
|
||||
}
|
||||
|
||||
void TestTransitGraphLoader::Clear()
|
||||
{
|
||||
m_graphs.clear();
|
||||
}
|
||||
|
||||
void TestTransitGraphLoader::AddGraph(NumMwmId mwmId, unique_ptr<TransitGraph> graph)
|
||||
{
|
||||
routing_test::AddGraph(m_graphs, mwmId, std::move(graph));
|
||||
}
|
||||
|
||||
// WeightedEdgeEstimator --------------------------------------------------------------
|
||||
double WeightedEdgeEstimator::CalcSegmentWeight(Segment const & segment, RoadGeometry const & /* road */,
|
||||
EdgeEstimator::Purpose /* purpose */) const
|
||||
{
|
||||
auto const it = m_segmentWeights.find(segment);
|
||||
CHECK(it != m_segmentWeights.cend(), ());
|
||||
return it->second;
|
||||
}
|
||||
|
||||
double WeightedEdgeEstimator::GetUTurnPenalty(Purpose purpose) const
|
||||
{
|
||||
return 0.0;
|
||||
}
|
||||
double WeightedEdgeEstimator::GetTurnPenalty(Purpose purpose, double angle, RoadGeometry const & from_road,
|
||||
RoadGeometry const & to_road, bool is_left_hand_traffic) const
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
double WeightedEdgeEstimator::GetFerryLandingPenalty(Purpose purpose) const
|
||||
{
|
||||
return 0.0;
|
||||
}
|
||||
|
||||
// TestIndexGraphTopology --------------------------------------------------------------------------
|
||||
TestIndexGraphTopology::TestIndexGraphTopology(uint32_t numVertices) : m_numVertices(numVertices) {}
|
||||
|
||||
void TestIndexGraphTopology::AddDirectedEdge(Vertex from, Vertex to, double weight)
|
||||
{
|
||||
AddDirectedEdge(m_edgeRequests, from, to, weight);
|
||||
}
|
||||
|
||||
void TestIndexGraphTopology::SetEdgeAccess(Vertex from, Vertex to, RoadAccess::Type type)
|
||||
{
|
||||
for (auto & r : m_edgeRequests)
|
||||
{
|
||||
if (r.m_from == from && r.m_to == to)
|
||||
{
|
||||
r.m_accessType = type;
|
||||
return;
|
||||
}
|
||||
}
|
||||
CHECK(false, ("Cannot set access for edge that is not in the graph", from, to));
|
||||
}
|
||||
|
||||
void TestIndexGraphTopology::SetEdgeAccessConditional(Vertex from, Vertex to, RoadAccess::Type type,
|
||||
string const & condition)
|
||||
{
|
||||
for (auto & r : m_edgeRequests)
|
||||
{
|
||||
if (r.m_from == from && r.m_to == to)
|
||||
{
|
||||
osmoh::OpeningHours openingHours(condition);
|
||||
CHECK(openingHours.IsValid(), (condition));
|
||||
r.m_accessConditionalType.Insert(type, std::move(openingHours));
|
||||
return;
|
||||
}
|
||||
}
|
||||
CHECK(false, ("Cannot set access for edge that is not in the graph", from, to));
|
||||
}
|
||||
|
||||
void TestIndexGraphTopology::SetVertexAccess(Vertex v, RoadAccess::Type type)
|
||||
{
|
||||
bool found = false;
|
||||
for (auto & r : m_edgeRequests)
|
||||
{
|
||||
if (r.m_from == v)
|
||||
{
|
||||
r.m_fromAccessType = type;
|
||||
found = true;
|
||||
}
|
||||
else if (r.m_to == v)
|
||||
{
|
||||
r.m_toAccessType = type;
|
||||
found = true;
|
||||
}
|
||||
|
||||
if (found)
|
||||
break;
|
||||
}
|
||||
CHECK(found, ("Cannot set access for vertex that is not in the graph", v));
|
||||
}
|
||||
|
||||
void TestIndexGraphTopology::SetVertexAccessConditional(Vertex v, RoadAccess::Type type, string const & condition)
|
||||
{
|
||||
osmoh::OpeningHours openingHours(condition);
|
||||
CHECK(openingHours.IsValid(), (condition));
|
||||
|
||||
bool found = false;
|
||||
for (auto & r : m_edgeRequests)
|
||||
{
|
||||
if (r.m_from == v)
|
||||
{
|
||||
r.m_fromAccessConditionalType.Insert(type, std::move(openingHours));
|
||||
found = true;
|
||||
}
|
||||
else if (r.m_to == v)
|
||||
{
|
||||
r.m_toAccessConditionalType.Insert(type, std::move(openingHours));
|
||||
found = true;
|
||||
}
|
||||
|
||||
if (found)
|
||||
break;
|
||||
}
|
||||
CHECK(found, ("Cannot set access for vertex that is not in the graph", v));
|
||||
}
|
||||
|
||||
bool TestIndexGraphTopology::FindPath(Vertex start, Vertex finish, double & pathWeight, vector<Edge> & pathEdges) const
|
||||
{
|
||||
CHECK_LESS(start, m_numVertices, ());
|
||||
CHECK_LESS(finish, m_numVertices, ());
|
||||
|
||||
if (start == finish)
|
||||
{
|
||||
pathWeight = 0.0;
|
||||
pathEdges.clear();
|
||||
return true;
|
||||
}
|
||||
|
||||
auto edgeRequests = m_edgeRequests;
|
||||
// Edges of the index graph are segments, so we need a loop at finish
|
||||
// for the end of our path and another loop at start for the bidirectional search.
|
||||
auto const startFeatureId = static_cast<uint32_t>(edgeRequests.size());
|
||||
AddDirectedEdge(edgeRequests, start, start, 0.0);
|
||||
// |startSegment| corresponds to edge from |start| to |start| which has featureId |startFeatureId|
|
||||
// and the only segment with segmentIdx |0|. It is a loop so direction does not matter.
|
||||
auto const startSegment = Segment(kTestNumMwmId, startFeatureId, 0 /* segmentIdx */, true /* forward */);
|
||||
|
||||
auto const finishFeatureId = static_cast<uint32_t>(edgeRequests.size());
|
||||
AddDirectedEdge(edgeRequests, finish, finish, 0.0);
|
||||
// |finishSegment| corresponds to edge from |finish| to |finish| which has featureId |finishFeatureId|
|
||||
// and the only segment with segmentIdx |0|. It is a loop so direction does not matter.
|
||||
auto const finishSegment = Segment(kTestNumMwmId, finishFeatureId, 0 /* segmentIdx */, true /* forward */);
|
||||
|
||||
Builder builder(m_numVertices);
|
||||
builder.SetCurrentTimeGetter(m_currentTimeGetter);
|
||||
builder.BuildGraphFromRequests(edgeRequests);
|
||||
auto worldGraph = builder.PrepareIndexGraph();
|
||||
CHECK(worldGraph != nullptr, ());
|
||||
|
||||
AlgorithmForWorldGraph algorithm;
|
||||
|
||||
WorldGraphForAStar graphForAStar(std::move(worldGraph));
|
||||
|
||||
AlgorithmForWorldGraph::ParamsForTests<> params(graphForAStar, startSegment, finishSegment);
|
||||
RoutingResult<Segment, RouteWeight> routingResult;
|
||||
auto const resultCode = algorithm.FindPathBidirectional(params, routingResult);
|
||||
|
||||
// Check unidirectional AStar returns same result.
|
||||
{
|
||||
RoutingResult<Segment, RouteWeight> unidirectionalRoutingResult;
|
||||
auto const unidirectionalResultCode = algorithm.FindPath(params, unidirectionalRoutingResult);
|
||||
CHECK_EQUAL(resultCode, unidirectionalResultCode, ());
|
||||
CHECK(routingResult.m_distance.IsAlmostEqualForTests(unidirectionalRoutingResult.m_distance, kEpsilon),
|
||||
("Distances differ:", routingResult.m_distance, unidirectionalRoutingResult.m_distance));
|
||||
}
|
||||
|
||||
if (resultCode == AlgorithmForWorldGraph::Result::NoPath)
|
||||
return false;
|
||||
|
||||
CHECK_EQUAL(resultCode, AlgorithmForWorldGraph::Result::OK, ());
|
||||
CHECK_GREATER_OR_EQUAL(routingResult.m_path.size(), 2, ());
|
||||
CHECK_EQUAL(routingResult.m_path.front(), startSegment, ());
|
||||
CHECK_EQUAL(routingResult.m_path.back(), finishSegment, ());
|
||||
|
||||
pathEdges.reserve(routingResult.m_path.size());
|
||||
pathWeight = 0.0;
|
||||
for (auto const & s : routingResult.m_path)
|
||||
{
|
||||
auto const it = builder.m_segmentToEdge.find(s);
|
||||
CHECK(it != builder.m_segmentToEdge.cend(), ());
|
||||
auto const & edge = it->second;
|
||||
pathEdges.push_back(edge);
|
||||
pathWeight += builder.m_segmentWeights[s];
|
||||
}
|
||||
|
||||
// The loops from start to start and from finish to finish.
|
||||
CHECK_GREATER_OR_EQUAL(pathEdges.size(), 2, ());
|
||||
CHECK_EQUAL(pathEdges.front().first, pathEdges.front().second, ());
|
||||
CHECK_EQUAL(pathEdges.back().first, pathEdges.back().second, ());
|
||||
pathEdges.erase(pathEdges.begin());
|
||||
pathEdges.pop_back();
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void TestIndexGraphTopology::AddDirectedEdge(vector<EdgeRequest> & edgeRequests, Vertex from, Vertex to,
|
||||
double weight) const
|
||||
{
|
||||
uint32_t const id = static_cast<uint32_t>(edgeRequests.size());
|
||||
edgeRequests.emplace_back(id, from, to, weight);
|
||||
}
|
||||
|
||||
// TestIndexGraphTopology::Builder -----------------------------------------------------------------
|
||||
unique_ptr<SingleVehicleWorldGraph> TestIndexGraphTopology::Builder::PrepareIndexGraph()
|
||||
{
|
||||
auto loader = make_unique<ZeroGeometryLoader>();
|
||||
auto estimator = make_shared<WeightedEdgeEstimator>(m_segmentWeights);
|
||||
|
||||
BuildJoints();
|
||||
|
||||
auto worldGraph = BuildWorldGraph(std::move(loader), estimator, m_joints);
|
||||
auto & indexGraph = worldGraph->GetIndexGraphForTests(kTestNumMwmId);
|
||||
if (m_currentTimeGetter)
|
||||
indexGraph.SetCurrentTimeGetter(m_currentTimeGetter);
|
||||
indexGraph.SetRoadAccess(std::move(m_roadAccess));
|
||||
return worldGraph;
|
||||
}
|
||||
|
||||
void TestIndexGraphTopology::Builder::BuildJoints()
|
||||
{
|
||||
m_joints.resize(m_numVertices);
|
||||
for (uint32_t i = 0; i < m_joints.size(); ++i)
|
||||
{
|
||||
auto & joint = m_joints[i];
|
||||
|
||||
for (auto const & segment : m_outgoingSegments[i])
|
||||
joint.AddPoint(RoadPoint(segment.GetFeatureId(), segment.GetPointId(false /* front */)));
|
||||
|
||||
for (auto const & segment : m_ingoingSegments[i])
|
||||
joint.AddPoint(RoadPoint(segment.GetFeatureId(), segment.GetPointId(true /* front */)));
|
||||
}
|
||||
}
|
||||
|
||||
void TestIndexGraphTopology::Builder::BuildGraphFromRequests(vector<EdgeRequest> const & requests)
|
||||
{
|
||||
RoadAccess::WayToAccess wayToAccess;
|
||||
RoadAccess::WayToAccessConditional wayToAccessConditional;
|
||||
RoadAccess::PointToAccess pointToAccess;
|
||||
RoadAccess::PointToAccessConditional pointToAccessConditional;
|
||||
for (auto const & request : requests)
|
||||
{
|
||||
BuildSegmentFromEdge(request);
|
||||
if (request.m_accessType != RoadAccess::Type::Yes)
|
||||
wayToAccess[request.m_id] = request.m_accessType;
|
||||
|
||||
if (!request.m_accessConditionalType.IsEmpty())
|
||||
wayToAccessConditional[request.m_id] = request.m_accessConditionalType;
|
||||
|
||||
// All features have 1 segment. |from| has point index 0, |to| has point index 1.
|
||||
if (request.m_fromAccessType != RoadAccess::Type::Yes)
|
||||
pointToAccess[RoadPoint(request.m_id, 0 /* pointId */)] = request.m_fromAccessType;
|
||||
|
||||
if (!request.m_fromAccessConditionalType.IsEmpty())
|
||||
pointToAccessConditional[RoadPoint(request.m_id, 0 /* pointId */)] = request.m_fromAccessConditionalType;
|
||||
|
||||
if (request.m_toAccessType != RoadAccess::Type::Yes)
|
||||
pointToAccess[RoadPoint(request.m_id, 1 /* pointId */)] = request.m_toAccessType;
|
||||
|
||||
if (!request.m_toAccessConditionalType.IsEmpty())
|
||||
pointToAccessConditional[RoadPoint(request.m_id, 1 /* pointId */)] = request.m_toAccessConditionalType;
|
||||
}
|
||||
|
||||
m_roadAccess.SetAccess(std::move(wayToAccess), std::move(pointToAccess));
|
||||
m_roadAccess.SetAccessConditional(std::move(wayToAccessConditional), std::move(pointToAccessConditional));
|
||||
if (m_currentTimeGetter)
|
||||
m_roadAccess.SetCurrentTimeGetter(m_currentTimeGetter);
|
||||
}
|
||||
|
||||
void TestIndexGraphTopology::Builder::BuildSegmentFromEdge(EdgeRequest const & request)
|
||||
{
|
||||
auto const edge = make_pair(request.m_from, request.m_to);
|
||||
auto p = m_edgeWeights.emplace(edge, request.m_weight);
|
||||
CHECK(p.second, ("Multi-edges are not allowed"));
|
||||
|
||||
uint32_t const featureId = request.m_id;
|
||||
Segment const segment(kTestNumMwmId, featureId, 0 /* segmentIdx */, true /* forward */);
|
||||
|
||||
m_segmentWeights[segment] = request.m_weight;
|
||||
m_segmentToEdge[segment] = edge;
|
||||
m_outgoingSegments[request.m_from].push_back(segment);
|
||||
m_ingoingSegments[request.m_to].push_back(segment);
|
||||
}
|
||||
|
||||
// Functions ---------------------------------------------------------------------------------------
|
||||
unique_ptr<SingleVehicleWorldGraph> BuildWorldGraph(unique_ptr<TestGeometryLoader> geometryLoader,
|
||||
shared_ptr<EdgeEstimator> estimator, vector<Joint> const & joints)
|
||||
{
|
||||
auto graph = make_unique<IndexGraph>(make_shared<Geometry>(std::move(geometryLoader)), estimator);
|
||||
graph->Import(joints);
|
||||
auto indexLoader = make_unique<TestIndexGraphLoader>();
|
||||
indexLoader->AddGraph(kTestNumMwmId, std::move(graph));
|
||||
return make_unique<SingleVehicleWorldGraph>(nullptr /* crossMwmGraph */, std::move(indexLoader), estimator,
|
||||
MwmHierarchyHandler());
|
||||
}
|
||||
|
||||
unique_ptr<IndexGraph> BuildIndexGraph(unique_ptr<TestGeometryLoader> geometryLoader,
|
||||
shared_ptr<EdgeEstimator> estimator, vector<Joint> const & joints)
|
||||
{
|
||||
auto graph = make_unique<IndexGraph>(make_shared<Geometry>(std::move(geometryLoader)), estimator);
|
||||
graph->Import(joints);
|
||||
return graph;
|
||||
}
|
||||
|
||||
unique_ptr<SingleVehicleWorldGraph> BuildWorldGraph(unique_ptr<ZeroGeometryLoader> geometryLoader,
|
||||
shared_ptr<EdgeEstimator> estimator, vector<Joint> const & joints)
|
||||
{
|
||||
auto graph = make_unique<IndexGraph>(make_shared<Geometry>(std::move(geometryLoader)), estimator);
|
||||
|
||||
graph->Import(joints);
|
||||
auto indexLoader = make_unique<TestIndexGraphLoader>();
|
||||
indexLoader->AddGraph(kTestNumMwmId, std::move(graph));
|
||||
return make_unique<SingleVehicleWorldGraph>(nullptr /* crossMwmGraph */, std::move(indexLoader), estimator,
|
||||
MwmHierarchyHandler());
|
||||
}
|
||||
|
||||
unique_ptr<TransitWorldGraph> BuildWorldGraph(unique_ptr<TestGeometryLoader> geometryLoader,
|
||||
shared_ptr<EdgeEstimator> estimator, vector<Joint> const & joints,
|
||||
routing::transit::GraphData const & transitData)
|
||||
{
|
||||
auto indexGraph = make_unique<IndexGraph>(make_shared<Geometry>(std::move(geometryLoader)), estimator);
|
||||
indexGraph->Import(joints);
|
||||
|
||||
auto transitGraph = make_unique<TransitGraph>(::transit::TransitVersion::OnlySubway, kTestNumMwmId, estimator);
|
||||
TransitGraph::Endings gateEndings;
|
||||
MakeGateEndings(transitData.GetGates(), kTestNumMwmId, *indexGraph, gateEndings);
|
||||
transitGraph->Fill(transitData, gateEndings);
|
||||
|
||||
auto indexLoader = make_unique<TestIndexGraphLoader>();
|
||||
indexLoader->AddGraph(kTestNumMwmId, std::move(indexGraph));
|
||||
|
||||
auto transitLoader = make_unique<TestTransitGraphLoader>();
|
||||
transitLoader->AddGraph(kTestNumMwmId, std::move(transitGraph));
|
||||
|
||||
return make_unique<TransitWorldGraph>(nullptr /* crossMwmGraph */, std::move(indexLoader), std::move(transitLoader),
|
||||
estimator);
|
||||
}
|
||||
|
||||
AlgorithmForWorldGraph::Result CalculateRoute(IndexGraphStarter & starter, vector<Segment> & roadPoints,
|
||||
double & timeSec)
|
||||
{
|
||||
AlgorithmForWorldGraph algorithm;
|
||||
RoutingResult<Segment, RouteWeight> routingResult;
|
||||
|
||||
AlgorithmForWorldGraph::ParamsForTests<AStarLengthChecker> params(
|
||||
starter, starter.GetStartSegment(), starter.GetFinishSegment(), AStarLengthChecker(starter));
|
||||
|
||||
auto const resultCode = algorithm.FindPathBidirectional(params, routingResult);
|
||||
|
||||
timeSec = routingResult.m_distance.GetWeight();
|
||||
roadPoints = routingResult.m_path;
|
||||
return resultCode;
|
||||
}
|
||||
|
||||
void TestRouteGeometry(IndexGraphStarter & starter, AlgorithmForWorldGraph::Result expectedRouteResult,
|
||||
vector<m2::PointD> const & expectedRouteGeom)
|
||||
{
|
||||
vector<Segment> routeSegs;
|
||||
double timeSec = 0.0;
|
||||
auto const resultCode = CalculateRoute(starter, routeSegs, timeSec);
|
||||
|
||||
TEST_EQUAL(resultCode, expectedRouteResult, ());
|
||||
|
||||
if (AlgorithmForWorldGraph::Result::NoPath == expectedRouteResult && expectedRouteGeom.empty())
|
||||
{
|
||||
// The route goes through a restriction. So there's no choice for building route
|
||||
// except for going through restriction. So no path.
|
||||
return;
|
||||
}
|
||||
|
||||
if (resultCode != AlgorithmForWorldGraph::Result::OK)
|
||||
return;
|
||||
|
||||
CHECK(!routeSegs.empty(), ());
|
||||
vector<m2::PointD> geom;
|
||||
|
||||
auto const pushPoint = [&geom](ms::LatLon const & ll)
|
||||
{
|
||||
auto const point = mercator::FromLatLon(ll);
|
||||
if (geom.empty() || geom.back() != point)
|
||||
geom.push_back(point);
|
||||
};
|
||||
|
||||
for (auto const & routeSeg : routeSegs)
|
||||
{
|
||||
auto const & ll = starter.GetPoint(routeSeg, false /* front */);
|
||||
// Note. In case of A* router all internal points of route are duplicated.
|
||||
// So it's necessary to exclude the duplicates.
|
||||
pushPoint(ll);
|
||||
}
|
||||
|
||||
pushPoint(starter.GetPoint(routeSegs.back(), false /* front */));
|
||||
TEST_EQUAL(geom.size(), expectedRouteGeom.size(), ("geom:", geom, "expectedRouteGeom:", expectedRouteGeom));
|
||||
for (size_t i = 0; i < geom.size(); ++i)
|
||||
{
|
||||
static double constexpr kEps = 1e-8;
|
||||
if (!AlmostEqualAbs(geom[i], expectedRouteGeom[i], kEps))
|
||||
{
|
||||
for (size_t j = 0; j < geom.size(); ++j)
|
||||
LOG(LINFO, (j, "=>", geom[j], "vs", expectedRouteGeom[j]));
|
||||
|
||||
TEST(false, ("Point with number:", i, "doesn't equal to expected."));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void TestRestrictions(vector<m2::PointD> const & expectedRouteGeom, AlgorithmForWorldGraph::Result expectedRouteResult,
|
||||
FakeEnding const & start, FakeEnding const & finish, RestrictionVec && restrictions,
|
||||
RestrictionTest & restrictionTest)
|
||||
{
|
||||
restrictionTest.SetRestrictions(std::move(restrictions));
|
||||
restrictionTest.SetStarter(start, finish);
|
||||
|
||||
TestRouteGeometry(*restrictionTest.m_starter, expectedRouteResult, expectedRouteGeom);
|
||||
}
|
||||
|
||||
void TestRestrictions(vector<m2::PointD> const & expectedRouteGeom, AlgorithmForWorldGraph::Result expectedRouteResult,
|
||||
FakeEnding const & start, FakeEnding const & finish, RestrictionVec && restrictions,
|
||||
vector<RestrictionUTurn> && restrictionsNoUTurn, RestrictionTest & restrictionTest)
|
||||
{
|
||||
restrictionTest.SetRestrictions(std::move(restrictions));
|
||||
restrictionTest.SetUTurnRestrictions(std::move(restrictionsNoUTurn));
|
||||
|
||||
restrictionTest.SetStarter(start, finish);
|
||||
TestRouteGeometry(*restrictionTest.m_starter, expectedRouteResult, expectedRouteGeom);
|
||||
}
|
||||
|
||||
void TestRestrictions(double expectedLength, FakeEnding const & start, FakeEnding const & finish,
|
||||
RestrictionVec && restrictions, RestrictionTest & restrictionTest)
|
||||
{
|
||||
restrictionTest.SetRestrictions(std::move(restrictions));
|
||||
restrictionTest.SetStarter(start, finish);
|
||||
|
||||
auto & starter = *restrictionTest.m_starter;
|
||||
|
||||
double timeSec = 0.0;
|
||||
vector<Segment> segments;
|
||||
auto const resultCode = CalculateRoute(starter, segments, timeSec);
|
||||
TEST_EQUAL(resultCode, AlgorithmForWorldGraph::Result::OK, ());
|
||||
|
||||
double length = 0.0;
|
||||
for (auto const & segment : segments)
|
||||
{
|
||||
auto const back = mercator::FromLatLon(starter.GetPoint(segment, false /* front */));
|
||||
auto const front = mercator::FromLatLon(starter.GetPoint(segment, true /* front */));
|
||||
|
||||
length += back.Length(front);
|
||||
}
|
||||
|
||||
static auto constexpr kEps = 1e-3;
|
||||
TEST(AlmostEqualAbs(expectedLength, length, kEps), ("Length expected:", expectedLength, "has:", length));
|
||||
}
|
||||
|
||||
void TestTopologyGraph(TestIndexGraphTopology const & graph, TestIndexGraphTopology::Vertex from,
|
||||
TestIndexGraphTopology::Vertex to, bool expectedPathFound, double const expectedWeight,
|
||||
vector<TestIndexGraphTopology::Edge> const & expectedEdges)
|
||||
{
|
||||
double pathWeight = 0.0;
|
||||
vector<TestIndexGraphTopology::Edge> pathEdges;
|
||||
bool const pathFound = graph.FindPath(from, to, pathWeight, pathEdges);
|
||||
TEST_EQUAL(pathFound, expectedPathFound, ());
|
||||
if (!pathFound)
|
||||
return;
|
||||
|
||||
TEST(AlmostEqualAbs(pathWeight, expectedWeight, kEpsilon), (pathWeight, expectedWeight, pathEdges));
|
||||
TEST_EQUAL(pathEdges, expectedEdges, ());
|
||||
}
|
||||
|
||||
FakeEnding MakeFakeEnding(uint32_t featureId, uint32_t segmentIdx, m2::PointD const & point, WorldGraph & graph)
|
||||
{
|
||||
return MakeFakeEnding({Segment(kTestNumMwmId, featureId, segmentIdx, true /* forward */)}, point, graph);
|
||||
}
|
||||
unique_ptr<IndexGraphStarter> MakeStarter(FakeEnding const & start, FakeEnding const & finish, WorldGraph & graph)
|
||||
{
|
||||
return make_unique<IndexGraphStarter>(start, finish, 0 /* fakeNumerationStart */, false /* strictForward */, graph);
|
||||
}
|
||||
|
||||
time_t GetUnixtimeByDate(uint16_t year, Month month, uint8_t monthDay, uint8_t hours, uint8_t minutes)
|
||||
{
|
||||
std::tm t{};
|
||||
t.tm_year = year - 1900;
|
||||
t.tm_mon = static_cast<int>(month) - 1;
|
||||
t.tm_mday = monthDay;
|
||||
t.tm_hour = hours;
|
||||
t.tm_min = minutes;
|
||||
|
||||
time_t moment = mktime(&t);
|
||||
return moment;
|
||||
}
|
||||
|
||||
time_t GetUnixtimeByDate(uint16_t year, Month month, Weekday weekday, uint8_t hours, uint8_t minutes)
|
||||
{
|
||||
int monthDay = 1;
|
||||
auto createUnixtime = [&]()
|
||||
{
|
||||
std::tm t{};
|
||||
t.tm_year = year - 1900;
|
||||
t.tm_mon = static_cast<int>(month) - 1;
|
||||
t.tm_mday = monthDay;
|
||||
t.tm_wday = static_cast<int>(weekday) - 1;
|
||||
t.tm_hour = hours;
|
||||
t.tm_min = minutes;
|
||||
|
||||
return mktime(&t);
|
||||
};
|
||||
|
||||
int wday = -1;
|
||||
for (;;)
|
||||
{
|
||||
auto unixtime = createUnixtime();
|
||||
auto timeOut = localtime(&unixtime);
|
||||
wday = timeOut->tm_wday;
|
||||
if (wday == static_cast<int>(weekday) - 1)
|
||||
break;
|
||||
++monthDay;
|
||||
}
|
||||
|
||||
return createUnixtime();
|
||||
}
|
||||
} // namespace routing_test
|
||||
321
libs/routing/routing_tests/index_graph_tools.hpp
Normal file
321
libs/routing/routing_tests/index_graph_tools.hpp
Normal file
|
|
@ -0,0 +1,321 @@
|
|||
#pragma once
|
||||
|
||||
#include "generator/generator_tests_support/routing_helpers.hpp"
|
||||
|
||||
#include "routing/base/astar_algorithm.hpp"
|
||||
#include "routing/edge_estimator.hpp"
|
||||
#include "routing/fake_ending.hpp"
|
||||
#include "routing/index_graph.hpp"
|
||||
#include "routing/index_graph_loader.hpp"
|
||||
#include "routing/index_graph_starter.hpp"
|
||||
#include "routing/restrictions_serialization.hpp"
|
||||
#include "routing/road_access.hpp"
|
||||
#include "routing/road_point.hpp"
|
||||
#include "routing/route.hpp"
|
||||
#include "routing/segment.hpp"
|
||||
#include "routing/single_vehicle_world_graph.hpp"
|
||||
#include "routing/speed_camera_ser_des.hpp"
|
||||
#include "routing/transit_graph_loader.hpp"
|
||||
#include "routing/transit_world_graph.hpp"
|
||||
|
||||
#include "traffic/traffic_info.hpp"
|
||||
|
||||
#include "transit/transit_types.hpp"
|
||||
|
||||
#include "routing_common/num_mwm_id.hpp"
|
||||
|
||||
#include "indexer/classificator_loader.hpp"
|
||||
|
||||
#include "geometry/point2d.hpp"
|
||||
|
||||
#include <algorithm>
|
||||
#include <cstdint>
|
||||
#include <ctime>
|
||||
#include <map>
|
||||
#include <memory>
|
||||
#include <unordered_map>
|
||||
#include <utility>
|
||||
#include <vector>
|
||||
|
||||
namespace routing_test
|
||||
{
|
||||
using namespace routing;
|
||||
|
||||
// The value doesn't matter, it doesn't associated with any real mwm id.
|
||||
// It just a noticeable value to detect the source of such id while debugging unit tests.
|
||||
NumMwmId constexpr kTestNumMwmId = 777;
|
||||
|
||||
using AlgorithmForWorldGraph = AStarAlgorithm<Segment, SegmentEdge, RouteWeight>;
|
||||
|
||||
class WorldGraphForAStar : public AStarGraph<Segment, SegmentEdge, RouteWeight>
|
||||
{
|
||||
public:
|
||||
explicit WorldGraphForAStar(std::unique_ptr<SingleVehicleWorldGraph> graph) : m_graph(std::move(graph)) {}
|
||||
~WorldGraphForAStar() override = default;
|
||||
|
||||
// AStarGraph overrides:
|
||||
// @{
|
||||
Weight HeuristicCostEstimate(Vertex const & from, Vertex const & to) override
|
||||
{
|
||||
return m_graph->HeuristicCostEstimate(m_graph->GetPoint(from, true /* front */),
|
||||
m_graph->GetPoint(to, true /* front */));
|
||||
}
|
||||
|
||||
void GetOutgoingEdgesList(astar::VertexData<Vertex, RouteWeight> const & vertexData, EdgeListT & edges) override
|
||||
{
|
||||
edges.clear();
|
||||
m_graph->GetEdgeList(vertexData, true /* isOutgoing */, true /* useRoutingOptions */,
|
||||
true /* useAccessConditional */, edges);
|
||||
}
|
||||
|
||||
void GetIngoingEdgesList(astar::VertexData<Vertex, RouteWeight> const & vertexData, EdgeListT & edges) override
|
||||
{
|
||||
edges.clear();
|
||||
m_graph->GetEdgeList(vertexData, false /* isOutgoing */, true /* useRoutingOptions */,
|
||||
true /* useAccessConditional */, edges);
|
||||
}
|
||||
|
||||
RouteWeight GetAStarWeightEpsilon() override { return RouteWeight(0.0); }
|
||||
// @}
|
||||
|
||||
WorldGraph & GetWorldGraph() { return *m_graph; }
|
||||
|
||||
private:
|
||||
std::unique_ptr<SingleVehicleWorldGraph> m_graph;
|
||||
};
|
||||
|
||||
struct RestrictionTest
|
||||
{
|
||||
RestrictionTest() { classificator::Load(); }
|
||||
void Init(std::unique_ptr<SingleVehicleWorldGraph> graph) { m_graph = std::move(graph); }
|
||||
void SetStarter(FakeEnding const & start, FakeEnding const & finish);
|
||||
void SetRestrictions(RestrictionVec && restrictions);
|
||||
void SetUTurnRestrictions(std::vector<RestrictionUTurn> && restrictions);
|
||||
|
||||
std::unique_ptr<SingleVehicleWorldGraph> m_graph;
|
||||
std::unique_ptr<IndexGraphStarter> m_starter;
|
||||
};
|
||||
|
||||
struct NoUTurnRestrictionTest
|
||||
{
|
||||
NoUTurnRestrictionTest() { classificator::Load(); }
|
||||
void Init(std::unique_ptr<SingleVehicleWorldGraph> graph);
|
||||
|
||||
void SetRestrictions(RestrictionVec && restrictions);
|
||||
void SetNoUTurnRestrictions(std::vector<RestrictionUTurn> && restrictions);
|
||||
|
||||
void TestRouteGeom(Segment const & start, Segment const & finish, AlgorithmForWorldGraph::Result expectedRouteResult,
|
||||
std::vector<m2::PointD> const & expectedRouteGeom);
|
||||
|
||||
std::unique_ptr<WorldGraphForAStar> m_graph;
|
||||
};
|
||||
|
||||
class ZeroGeometryLoader final : public routing::GeometryLoader
|
||||
{
|
||||
public:
|
||||
// GeometryLoader overrides:
|
||||
~ZeroGeometryLoader() override = default;
|
||||
|
||||
void Load(uint32_t featureId, routing::RoadGeometry & road) override;
|
||||
};
|
||||
|
||||
class TestIndexGraphLoader final : public IndexGraphLoader
|
||||
{
|
||||
public:
|
||||
// IndexGraphLoader overrides:
|
||||
~TestIndexGraphLoader() override = default;
|
||||
|
||||
IndexGraph & GetIndexGraph(NumMwmId mwmId) override;
|
||||
Geometry & GetGeometry(NumMwmId mwmId) override;
|
||||
|
||||
std::vector<RouteSegment::SpeedCamera> GetSpeedCameraInfo(Segment const & segment) override { return {}; }
|
||||
|
||||
void Clear() override;
|
||||
|
||||
void AddGraph(NumMwmId mwmId, std::unique_ptr<IndexGraph> graph);
|
||||
|
||||
private:
|
||||
std::unordered_map<NumMwmId, std::unique_ptr<IndexGraph>> m_graphs;
|
||||
};
|
||||
|
||||
class TestTransitGraphLoader : public TransitGraphLoader
|
||||
{
|
||||
public:
|
||||
// TransitGraphLoader overrides:
|
||||
~TestTransitGraphLoader() override = default;
|
||||
|
||||
TransitGraph & GetTransitGraph(NumMwmId mwmId, IndexGraph & indexGraph) override;
|
||||
void Clear() override;
|
||||
|
||||
void AddGraph(NumMwmId mwmId, std::unique_ptr<TransitGraph> graph);
|
||||
|
||||
private:
|
||||
std::unordered_map<NumMwmId, std::unique_ptr<TransitGraph>> m_graphs;
|
||||
};
|
||||
|
||||
// An estimator that uses the information from the supported |segmentWeights| map
|
||||
// and completely ignores road geometry. The underlying graph is assumed
|
||||
// to be directed, i.e. it is not guaranteed that each segment has its reverse
|
||||
// in the map.
|
||||
class WeightedEdgeEstimator final : public EdgeEstimator
|
||||
{
|
||||
public:
|
||||
// maxSpeedKMpH doesn't matter, but should be greater then any road speed in all tests.
|
||||
// offroadSpeedKMpH doesn't matter, but should be > 0 and <= maxSpeedKMpH.
|
||||
explicit WeightedEdgeEstimator(std::map<Segment, double> const & segmentWeights)
|
||||
: EdgeEstimator(VehicleType::Count, 1e10 /* maxSpeedKMpH */, 1.0 /* offroadSpeedKMpH */)
|
||||
, m_segmentWeights(segmentWeights)
|
||||
{}
|
||||
|
||||
// EdgeEstimator overrides:
|
||||
~WeightedEdgeEstimator() override = default;
|
||||
|
||||
double CalcSegmentWeight(Segment const & segment, RoadGeometry const & /* road */,
|
||||
EdgeEstimator::Purpose purpose) const override;
|
||||
|
||||
double GetUTurnPenalty(Purpose purpose) const override;
|
||||
double GetTurnPenalty(Purpose purpose, double angle, RoadGeometry const & from_road, RoadGeometry const & to_road,
|
||||
bool is_left_hand_traffic = false) const override;
|
||||
double GetFerryLandingPenalty(Purpose purpose) const override;
|
||||
|
||||
private:
|
||||
std::map<Segment, double> m_segmentWeights;
|
||||
};
|
||||
|
||||
// A simple class to test graph algorithms for the index graph
|
||||
// that do not depend on road geometry (but may depend on the
|
||||
// lengths of roads).
|
||||
class TestIndexGraphTopology final
|
||||
{
|
||||
public:
|
||||
using Vertex = uint32_t;
|
||||
using Edge = std::pair<Vertex, Vertex>;
|
||||
|
||||
// Creates an empty graph on |numVertices| vertices.
|
||||
TestIndexGraphTopology(uint32_t numVertices);
|
||||
|
||||
// Adds a weighted directed edge to the graph. Multi-edges are not supported.
|
||||
// *NOTE* The edges are added lazily, i.e. edge requests are only stored here
|
||||
// and the graph itself is built only after a call to FindPath.
|
||||
void AddDirectedEdge(Vertex from, Vertex to, double weight);
|
||||
|
||||
// Sets access for previously added edge.
|
||||
void SetEdgeAccess(Vertex from, Vertex to, RoadAccess::Type type);
|
||||
/// \param |condition| in osm opening hours format.
|
||||
void SetEdgeAccessConditional(Vertex from, Vertex to, RoadAccess::Type type, std::string const & condition);
|
||||
|
||||
// Sets access type for previously added point.
|
||||
void SetVertexAccess(Vertex v, RoadAccess::Type type);
|
||||
/// \param |condition| in osm opening hours format.
|
||||
void SetVertexAccessConditional(Vertex v, RoadAccess::Type type, std::string const & condition);
|
||||
|
||||
// Finds a path between the start and finish vertices. Returns true iff a path exists.
|
||||
bool FindPath(Vertex start, Vertex finish, double & pathWeight, std::vector<Edge> & pathEdges) const;
|
||||
|
||||
template <typename T>
|
||||
void SetCurrentTimeGetter(T && getter)
|
||||
{
|
||||
m_currentTimeGetter = std::forward<T>(getter);
|
||||
}
|
||||
|
||||
private:
|
||||
struct EdgeRequest
|
||||
{
|
||||
uint32_t m_id = 0;
|
||||
Vertex m_from = 0;
|
||||
Vertex m_to = 0;
|
||||
double m_weight = 0.0;
|
||||
// Access type for edge.
|
||||
RoadAccess::Type m_accessType = RoadAccess::Type::Yes;
|
||||
RoadAccess::Conditional m_accessConditionalType;
|
||||
// Access type for vertex from.
|
||||
RoadAccess::Type m_fromAccessType = RoadAccess::Type::Yes;
|
||||
RoadAccess::Conditional m_fromAccessConditionalType;
|
||||
// Access type for vertex to.
|
||||
RoadAccess::Type m_toAccessType = RoadAccess::Type::Yes;
|
||||
RoadAccess::Conditional m_toAccessConditionalType;
|
||||
|
||||
EdgeRequest(uint32_t id, Vertex from, Vertex to, double weight) : m_id(id), m_from(from), m_to(to), m_weight(weight)
|
||||
{}
|
||||
};
|
||||
|
||||
// Builder builds a graph from edge requests.
|
||||
struct Builder
|
||||
{
|
||||
explicit Builder(uint32_t numVertices) : m_numVertices(numVertices) {}
|
||||
std::unique_ptr<SingleVehicleWorldGraph> PrepareIndexGraph();
|
||||
void BuildJoints();
|
||||
void BuildGraphFromRequests(std::vector<EdgeRequest> const & requests);
|
||||
void BuildSegmentFromEdge(EdgeRequest const & request);
|
||||
void SetCurrentTimeGetter(std::function<time_t()> const & getter) { m_currentTimeGetter = getter; }
|
||||
|
||||
uint32_t const m_numVertices;
|
||||
std::map<Edge, double> m_edgeWeights;
|
||||
std::map<Segment, double> m_segmentWeights;
|
||||
std::map<Segment, Edge> m_segmentToEdge;
|
||||
std::map<Vertex, std::vector<Segment>> m_outgoingSegments;
|
||||
std::map<Vertex, std::vector<Segment>> m_ingoingSegments;
|
||||
std::vector<Joint> m_joints;
|
||||
RoadAccess m_roadAccess;
|
||||
std::function<time_t()> m_currentTimeGetter;
|
||||
};
|
||||
|
||||
void AddDirectedEdge(std::vector<EdgeRequest> & edgeRequests, Vertex from, Vertex to, double weight) const;
|
||||
|
||||
std::function<time_t()> m_currentTimeGetter;
|
||||
uint32_t const m_numVertices;
|
||||
std::vector<EdgeRequest> m_edgeRequests;
|
||||
};
|
||||
|
||||
std::unique_ptr<SingleVehicleWorldGraph> BuildWorldGraph(std::unique_ptr<TestGeometryLoader> loader,
|
||||
std::shared_ptr<EdgeEstimator> estimator,
|
||||
std::vector<Joint> const & joints);
|
||||
std::unique_ptr<SingleVehicleWorldGraph> BuildWorldGraph(std::unique_ptr<ZeroGeometryLoader> loader,
|
||||
std::shared_ptr<EdgeEstimator> estimator,
|
||||
std::vector<Joint> const & joints);
|
||||
|
||||
AStarAlgorithm<Segment, SegmentEdge, RouteWeight>::Result CalculateRoute(IndexGraphStarter & starter,
|
||||
std::vector<Segment> & roadPoints,
|
||||
double & timeSec);
|
||||
|
||||
void TestRouteGeometry(IndexGraphStarter & starter,
|
||||
AStarAlgorithm<Segment, SegmentEdge, RouteWeight>::Result expectedRouteResult,
|
||||
std::vector<m2::PointD> const & expectedRouteGeom);
|
||||
|
||||
/// \brief Applies |restrictions| to graph in |restrictionTest| and
|
||||
/// tests the resulting route.
|
||||
/// \note restrictionTest should have a valid |restrictionTest.m_graph|.
|
||||
void TestRestrictions(std::vector<m2::PointD> const & expectedRouteGeom,
|
||||
AStarAlgorithm<Segment, SegmentEdge, RouteWeight>::Result expectedRouteResult,
|
||||
FakeEnding const & start, FakeEnding const & finish, RestrictionVec && restrictions,
|
||||
RestrictionTest & restrictionTest);
|
||||
|
||||
void TestRestrictions(std::vector<m2::PointD> const & expectedRouteGeom,
|
||||
AStarAlgorithm<Segment, SegmentEdge, RouteWeight>::Result expectedRouteResult,
|
||||
FakeEnding const & start, FakeEnding const & finish, RestrictionVec && restrictions,
|
||||
std::vector<RestrictionUTurn> && restrictionsNoUTurn, RestrictionTest & restrictionTest);
|
||||
|
||||
void TestRestrictions(double timeExpected, FakeEnding const & start, FakeEnding const & finish,
|
||||
RestrictionVec && restrictions, RestrictionTest & restrictionTest);
|
||||
|
||||
// Tries to find a unique path from |from| to |to| in |graph|.
|
||||
// If |expectedPathFound| is true, |expectedWeight| and |expectedEdges| must
|
||||
// specify the weight and edges of the unique shortest path.
|
||||
// If |expectedPathFound| is false, |expectedWeight| and |expectedEdges| may
|
||||
// take arbitrary values.
|
||||
void TestTopologyGraph(TestIndexGraphTopology const & graph, TestIndexGraphTopology::Vertex from,
|
||||
TestIndexGraphTopology::Vertex to, bool expectedPathFound, double expectedWeight,
|
||||
std::vector<TestIndexGraphTopology::Edge> const & expectedEdges);
|
||||
|
||||
// Creates FakeEnding projected to |Segment(kTestNumMwmId, featureId, segmentIdx, true /* forward
|
||||
// */)|.
|
||||
FakeEnding MakeFakeEnding(uint32_t featureId, uint32_t segmentIdx, m2::PointD const & point, WorldGraph & graph);
|
||||
|
||||
std::unique_ptr<IndexGraphStarter> MakeStarter(FakeEnding const & start, FakeEnding const & finish, WorldGraph & graph);
|
||||
|
||||
using Month = osmoh::MonthDay::Month;
|
||||
using Weekday = osmoh::Weekday;
|
||||
|
||||
time_t GetUnixtimeByDate(uint16_t year, Month month, uint8_t monthDay, uint8_t hours, uint8_t minutes);
|
||||
time_t GetUnixtimeByDate(uint16_t year, Month month, Weekday weekday, uint8_t hours, uint8_t minutes);
|
||||
} // namespace routing_test
|
||||
160
libs/routing/routing_tests/lanes/lanes_parser_tests.cpp
Normal file
160
libs/routing/routing_tests/lanes/lanes_parser_tests.cpp
Normal file
|
|
@ -0,0 +1,160 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/lanes/lanes_parser.hpp"
|
||||
|
||||
namespace routing::turns::lanes::test
|
||||
{
|
||||
UNIT_TEST(TestParseLaneWays)
|
||||
{
|
||||
std::vector<std::pair<std::string, LaneWays>> const testData = {
|
||||
{";", {LaneWay::None}},
|
||||
{"none", {LaneWay::None}},
|
||||
{"left", {LaneWay::Left}},
|
||||
{"right", {LaneWay::Right}},
|
||||
{"sharp_left", {LaneWay::SharpLeft}},
|
||||
{"slight_left", {LaneWay::SlightLeft}},
|
||||
{"merge_to_right", {LaneWay::MergeToRight}},
|
||||
{"merge_to_left", {LaneWay::MergeToLeft}},
|
||||
{"slight_right", {LaneWay::SlightRight}},
|
||||
{"sharp_right", {LaneWay::SharpRight}},
|
||||
{"reverse", {LaneWay::ReverseLeft, LaneWay::ReverseRight}},
|
||||
{"next_right", {LaneWay::Right}},
|
||||
{"slide_left", {LaneWay::Through}},
|
||||
{"slide_right", {LaneWay::Through}},
|
||||
};
|
||||
|
||||
for (auto const & [in, out] : testData)
|
||||
{
|
||||
LanesInfo const result = ParseLanes(in);
|
||||
LaneWays const expected = {out};
|
||||
TEST_EQUAL(result.front().laneWays, expected, ());
|
||||
}
|
||||
}
|
||||
|
||||
UNIT_TEST(TestParseSingleLane)
|
||||
{
|
||||
{
|
||||
LanesInfo const result = ParseLanes("through;right");
|
||||
LaneWays constexpr expected = {LaneWay::Through, LaneWay::Right};
|
||||
TEST_EQUAL(result.front().laneWays, expected, ());
|
||||
}
|
||||
|
||||
{
|
||||
LanesInfo const result = ParseLanes("through;Right");
|
||||
LaneWays constexpr expected = {LaneWay::Through, LaneWay::Right};
|
||||
TEST_EQUAL(result.front().laneWays, expected, ());
|
||||
}
|
||||
|
||||
{
|
||||
LanesInfo const result = ParseLanes("through ;Right");
|
||||
LaneWays constexpr expected = {LaneWay::Through, LaneWay::Right};
|
||||
TEST_EQUAL(result.front().laneWays, expected, ());
|
||||
}
|
||||
|
||||
{
|
||||
LanesInfo const result = ParseLanes("left;through");
|
||||
LaneWays constexpr expected = {LaneWay::Left, LaneWay::Through};
|
||||
TEST_EQUAL(result.front().laneWays, expected, ());
|
||||
}
|
||||
|
||||
{
|
||||
LanesInfo const result = ParseLanes("left");
|
||||
LaneWays constexpr expected = {LaneWay::Left};
|
||||
TEST_EQUAL(result.front().laneWays, expected, ());
|
||||
}
|
||||
|
||||
{
|
||||
LanesInfo const result = ParseLanes("left;");
|
||||
LaneWays constexpr expected = {LaneWay::Left, LaneWay::None};
|
||||
TEST_EQUAL(result.front().laneWays, expected, ());
|
||||
}
|
||||
|
||||
{
|
||||
LanesInfo const result = ParseLanes(";");
|
||||
LaneWays constexpr expected = {LaneWay::None};
|
||||
TEST_EQUAL(result.front().laneWays, expected, ());
|
||||
}
|
||||
|
||||
TEST_EQUAL(ParseLanes("SD32kk*887;;").empty(), true, ());
|
||||
TEST_EQUAL(ParseLanes("Что-то на кириллице").empty(), true, ());
|
||||
TEST_EQUAL(ParseLanes("משהו בעברית").empty(), true, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(TestParseLanes)
|
||||
{
|
||||
{
|
||||
LanesInfo const result = ParseLanes("through|through|through|through;right");
|
||||
LanesInfo const expected = {
|
||||
{{LaneWay::Through}}, {{LaneWay::Through}}, {{LaneWay::Through}}, {{LaneWay::Through, LaneWay::Right}}};
|
||||
TEST_EQUAL(result, expected, ());
|
||||
}
|
||||
|
||||
{
|
||||
LanesInfo const result = ParseLanes("left|left;through|through|through");
|
||||
LanesInfo const expected = {
|
||||
{{LaneWay::Left}}, {{LaneWay::Left, LaneWay::Through}}, {{LaneWay::Through}}, {{LaneWay::Through}}};
|
||||
TEST_EQUAL(result, expected, ());
|
||||
}
|
||||
|
||||
{
|
||||
LanesInfo const result = ParseLanes("left|through|through");
|
||||
LanesInfo const expected = {{{LaneWay::Left}}, {{LaneWay::Through}}, {{LaneWay::Through}}};
|
||||
TEST_EQUAL(result, expected, ());
|
||||
}
|
||||
|
||||
{
|
||||
LanesInfo const result = ParseLanes("left|le ft| through|through | right");
|
||||
LanesInfo const expected = {
|
||||
{{LaneWay::Left}}, {{LaneWay::Left}}, {{LaneWay::Through}}, {{LaneWay::Through}}, {{LaneWay::Right}}};
|
||||
TEST_EQUAL(result, expected, ());
|
||||
}
|
||||
|
||||
{
|
||||
LanesInfo const result = ParseLanes("left|Left|through|througH|right");
|
||||
LanesInfo const expected = {
|
||||
{{LaneWay::Left}}, {{LaneWay::Left}}, {{LaneWay::Through}}, {{LaneWay::Through}}, {{LaneWay::Right}}};
|
||||
TEST_EQUAL(result, expected, ());
|
||||
}
|
||||
|
||||
{
|
||||
LanesInfo const result = ParseLanes("left|Left|through|througH|through;right;sharp_rIght");
|
||||
LanesInfo const expected = {{{LaneWay::Left}},
|
||||
{{LaneWay::Left}},
|
||||
{{LaneWay::Through}},
|
||||
{{LaneWay::Through}},
|
||||
{{LaneWay::Through, LaneWay::Right, LaneWay::SharpRight}}};
|
||||
TEST_EQUAL(result, expected, ());
|
||||
}
|
||||
|
||||
{
|
||||
LanesInfo const result = ParseLanes("left |Left|through|througH|right");
|
||||
LanesInfo const expected = {
|
||||
{{LaneWay::Left}}, {{LaneWay::Left}}, {{LaneWay::Through}}, {{LaneWay::Through}}, {{LaneWay::Right}}};
|
||||
TEST_EQUAL(result, expected, ());
|
||||
}
|
||||
|
||||
{
|
||||
LanesInfo const result = ParseLanes("|||||slight_right");
|
||||
LanesInfo const expected = {{{LaneWay::None}}, {{LaneWay::None}}, {{LaneWay::None}},
|
||||
{{LaneWay::None}}, {{LaneWay::None}}, {{LaneWay::SlightRight}}};
|
||||
TEST_EQUAL(result, expected, ());
|
||||
}
|
||||
|
||||
{
|
||||
LanesInfo const result = ParseLanes("|");
|
||||
LanesInfo const expected = {{{LaneWay::None}}, {{LaneWay::None}}};
|
||||
TEST_EQUAL(result, expected, ());
|
||||
}
|
||||
|
||||
{
|
||||
LanesInfo const result = ParseLanes(";|;;;");
|
||||
LanesInfo const expected = {{{LaneWay::None}}, {{LaneWay::None}}};
|
||||
TEST_EQUAL(result, expected, ());
|
||||
}
|
||||
|
||||
{
|
||||
LanesInfo const result = ParseLanes("left|Leftt|through|througH|right");
|
||||
TEST_EQUAL(result.empty(), true, ());
|
||||
}
|
||||
}
|
||||
} // namespace routing::turns::lanes::test
|
||||
221
libs/routing/routing_tests/lanes/lanes_recommendation_tests.cpp
Normal file
221
libs/routing/routing_tests/lanes/lanes_recommendation_tests.cpp
Normal file
|
|
@ -0,0 +1,221 @@
|
|||
#include "routing/turns.hpp"
|
||||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/lanes/lanes_recommendation.hpp"
|
||||
#include "routing/routing_tests/tools.hpp"
|
||||
|
||||
namespace routing::turns::lanes::test
|
||||
{
|
||||
UNIT_TEST(TestSetRecommendedLaneWays_Smoke)
|
||||
{
|
||||
using impl::SetRecommendedLaneWays;
|
||||
|
||||
struct CarDirectionToLaneWayMapping
|
||||
{
|
||||
CarDirection carDirection;
|
||||
LaneWay laneWay;
|
||||
bool shouldBeRecommended;
|
||||
};
|
||||
std::vector<CarDirectionToLaneWayMapping> const testData = {
|
||||
{CarDirection::GoStraight, LaneWay::Through, true},
|
||||
{CarDirection::TurnRight, LaneWay::Right, true},
|
||||
{CarDirection::TurnSharpRight, LaneWay::SharpRight, true},
|
||||
{CarDirection::TurnSlightRight, LaneWay::SlightRight, true},
|
||||
{CarDirection::TurnLeft, LaneWay::Left, true},
|
||||
{CarDirection::TurnSharpLeft, LaneWay::SharpLeft, true},
|
||||
{CarDirection::TurnSlightLeft, LaneWay::SlightLeft, true},
|
||||
{CarDirection::UTurnLeft, LaneWay::ReverseLeft, true},
|
||||
{CarDirection::UTurnRight, LaneWay::ReverseRight, true},
|
||||
{CarDirection::ExitHighwayToLeft, LaneWay::SlightLeft, true},
|
||||
{CarDirection::ExitHighwayToRight, LaneWay::SlightRight, true},
|
||||
// We do not recommend any lane way for these directions
|
||||
{CarDirection::None, LaneWay::None, false},
|
||||
{CarDirection::EnterRoundAbout, LaneWay::None, false},
|
||||
{CarDirection::LeaveRoundAbout, LaneWay::None, false},
|
||||
{CarDirection::StayOnRoundAbout, LaneWay::None, false},
|
||||
{CarDirection::StartAtEndOfStreet, LaneWay::None, false},
|
||||
{CarDirection::ReachedYourDestination, LaneWay::None, false},
|
||||
};
|
||||
TEST_EQUAL(testData.size(), static_cast<size_t>(CarDirection::Count), ("Not all CarDirection values are covered."));
|
||||
for (auto const & [carDirection, laneWay, shouldBeRecommended] : testData)
|
||||
{
|
||||
LanesInfo lanesInfo = {{{laneWay}}};
|
||||
bool const isRecommended = SetRecommendedLaneWays(carDirection, lanesInfo);
|
||||
TEST_EQUAL(isRecommended, shouldBeRecommended,
|
||||
("CarDirection:", DebugPrint(carDirection), "LaneWay:", DebugPrint(laneWay)));
|
||||
TEST_EQUAL(lanesInfo[0].recommendedWay, shouldBeRecommended ? laneWay : LaneWay::None, ());
|
||||
}
|
||||
}
|
||||
|
||||
UNIT_TEST(TestSetRecommendedLaneWays)
|
||||
{
|
||||
{
|
||||
LanesInfo lanesInfo = {
|
||||
{{LaneWay::ReverseLeft, LaneWay::Left, LaneWay::Through}},
|
||||
{{LaneWay::Through}},
|
||||
{{LaneWay::Through}},
|
||||
{{LaneWay::Through, LaneWay::Right}},
|
||||
{{LaneWay::Right}},
|
||||
};
|
||||
TEST(impl::SetRecommendedLaneWays(CarDirection::GoStraight, lanesInfo), ());
|
||||
TEST_EQUAL(lanesInfo[0].recommendedWay, LaneWay::Through, ());
|
||||
TEST_EQUAL(lanesInfo[1].recommendedWay, LaneWay::Through, ());
|
||||
TEST_EQUAL(lanesInfo[2].recommendedWay, LaneWay::Through, ());
|
||||
TEST_EQUAL(lanesInfo[3].recommendedWay, LaneWay::Through, ());
|
||||
TEST_EQUAL(lanesInfo[4].recommendedWay, LaneWay::None, ());
|
||||
}
|
||||
{
|
||||
LanesInfo lanesInfo = {
|
||||
{{LaneWay::ReverseLeft, LaneWay::Left}},
|
||||
{{LaneWay::Right}},
|
||||
};
|
||||
TEST(!impl::SetRecommendedLaneWays(CarDirection::GoStraight, lanesInfo), ());
|
||||
TEST_EQUAL(lanesInfo[0].recommendedWay, LaneWay::None, ());
|
||||
TEST_EQUAL(lanesInfo[1].recommendedWay, LaneWay::None, ());
|
||||
}
|
||||
{
|
||||
LanesInfo lanesInfo = {
|
||||
{{LaneWay::ReverseLeft, LaneWay::ReverseRight}},
|
||||
};
|
||||
TEST(impl::SetRecommendedLaneWays(CarDirection::UTurnLeft, lanesInfo), ());
|
||||
TEST_EQUAL(lanesInfo[0].recommendedWay, LaneWay::ReverseLeft, ());
|
||||
TEST_EQUAL(lanesInfo[0].laneWays.Contains(LaneWay::ReverseRight), false, ());
|
||||
}
|
||||
}
|
||||
|
||||
UNIT_TEST(SetRecommendedLaneWaysApproximately_Smoke)
|
||||
{
|
||||
{
|
||||
struct CarDirectionToLaneWaysApproximateMapping
|
||||
{
|
||||
CarDirection carDirection;
|
||||
std::vector<LaneWay> laneWay;
|
||||
};
|
||||
std::vector<CarDirectionToLaneWaysApproximateMapping> const testData = {
|
||||
{CarDirection::UTurnLeft, {LaneWay::SharpLeft}},
|
||||
{CarDirection::TurnSharpLeft, {LaneWay::Left}},
|
||||
{CarDirection::TurnLeft, {LaneWay::SlightLeft, LaneWay::SharpLeft}},
|
||||
{CarDirection::TurnSlightLeft, {LaneWay::Left}},
|
||||
{CarDirection::ExitHighwayToLeft, {LaneWay::Left}},
|
||||
{CarDirection::GoStraight, {LaneWay::SlightRight, LaneWay::SlightLeft}},
|
||||
{CarDirection::ExitHighwayToRight, {LaneWay::Right}},
|
||||
{CarDirection::TurnSlightRight, {LaneWay::Right}},
|
||||
{CarDirection::TurnRight, {LaneWay::SlightRight, LaneWay::SharpRight}},
|
||||
{CarDirection::TurnSharpRight, {LaneWay::Right}},
|
||||
{CarDirection::UTurnRight, {LaneWay::SharpRight}},
|
||||
};
|
||||
for (auto const & [carDirection, laneWays] : testData)
|
||||
{
|
||||
for (auto const & laneWay : laneWays)
|
||||
{
|
||||
LanesInfo lanesInfo = {{{laneWay}}};
|
||||
bool const isRecommended = impl::SetRecommendedLaneWaysApproximately(carDirection, lanesInfo);
|
||||
TEST(isRecommended, ("CarDirection:", DebugPrint(carDirection), "LaneWay:", DebugPrint(laneWay)));
|
||||
TEST_EQUAL(lanesInfo[0].recommendedWay, laneWay, ());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
{
|
||||
// Those directions do not have any recommended lane ways.
|
||||
std::vector const carDirections = {CarDirection::None,
|
||||
CarDirection::EnterRoundAbout,
|
||||
CarDirection::LeaveRoundAbout,
|
||||
CarDirection::StayOnRoundAbout,
|
||||
CarDirection::StartAtEndOfStreet,
|
||||
CarDirection::ReachedYourDestination};
|
||||
for (auto const & carDirection : carDirections)
|
||||
{
|
||||
LanesInfo lanesInfo = {{{LaneWay::Through}}};
|
||||
TEST(!impl::SetRecommendedLaneWaysApproximately(carDirection, lanesInfo), ());
|
||||
TEST_EQUAL(lanesInfo[0].recommendedWay, LaneWay::None, ());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
UNIT_TEST(SetRecommendedLaneWaysApproximately)
|
||||
{
|
||||
{
|
||||
LanesInfo lanesInfo = {
|
||||
{{LaneWay::ReverseLeft, LaneWay::Left, LaneWay::SlightLeft}},
|
||||
{{LaneWay::SlightRight, LaneWay::Right}},
|
||||
{{LaneWay::Right}},
|
||||
};
|
||||
TEST(impl::SetRecommendedLaneWaysApproximately(CarDirection::GoStraight, lanesInfo), ());
|
||||
TEST_EQUAL(lanesInfo[0].recommendedWay, LaneWay::SlightLeft, ());
|
||||
TEST_EQUAL(lanesInfo[1].recommendedWay, LaneWay::SlightRight, ());
|
||||
TEST_EQUAL(lanesInfo[2].recommendedWay, LaneWay::None, ());
|
||||
}
|
||||
{
|
||||
LanesInfo lanesInfo = {
|
||||
{{LaneWay::ReverseLeft, LaneWay::Left}},
|
||||
{{LaneWay::Right}},
|
||||
};
|
||||
TEST(!impl::SetRecommendedLaneWaysApproximately(CarDirection::GoStraight, lanesInfo), ());
|
||||
TEST_EQUAL(lanesInfo[0].recommendedWay, LaneWay::None, ());
|
||||
TEST_EQUAL(lanesInfo[1].recommendedWay, LaneWay::None, ());
|
||||
}
|
||||
{
|
||||
LanesInfo lanesInfo = {
|
||||
{{LaneWay::SharpLeft, LaneWay::SlightLeft}},
|
||||
};
|
||||
TEST(impl::SetRecommendedLaneWaysApproximately(CarDirection::TurnLeft, lanesInfo), ());
|
||||
TEST_EQUAL(lanesInfo[0].recommendedWay, LaneWay::SlightLeft, ());
|
||||
}
|
||||
}
|
||||
|
||||
UNIT_TEST(SetUnrestrictedLaneAsRecommended)
|
||||
{
|
||||
LanesInfo const testData = {{{LaneWay::ReverseLeft}}, {{LaneWay::None}}, {{LaneWay::None}}, {{LaneWay::Right}}};
|
||||
{
|
||||
LanesInfo lanesInfo = testData;
|
||||
TEST(impl::SetUnrestrictedLaneAsRecommended(CarDirection::TurnLeft, lanesInfo), ());
|
||||
TEST_EQUAL(lanesInfo[0].recommendedWay, LaneWay::None, ());
|
||||
TEST_EQUAL(lanesInfo[1].recommendedWay, LaneWay::Left, ());
|
||||
TEST_EQUAL(lanesInfo[2].recommendedWay, LaneWay::None, ());
|
||||
TEST_EQUAL(lanesInfo[3].recommendedWay, LaneWay::None, ());
|
||||
}
|
||||
{
|
||||
LanesInfo lanesInfo = testData;
|
||||
TEST(impl::SetUnrestrictedLaneAsRecommended(CarDirection::TurnRight, lanesInfo), ());
|
||||
TEST_EQUAL(lanesInfo[0].recommendedWay, LaneWay::None, ());
|
||||
TEST_EQUAL(lanesInfo[1].recommendedWay, LaneWay::None, ());
|
||||
TEST_EQUAL(lanesInfo[2].recommendedWay, LaneWay::Right, ());
|
||||
TEST_EQUAL(lanesInfo[3].recommendedWay, LaneWay::None, ());
|
||||
}
|
||||
{
|
||||
LanesInfo lanesInfo = {};
|
||||
TEST(!impl::SetUnrestrictedLaneAsRecommended(CarDirection::TurnRight, lanesInfo), ());
|
||||
}
|
||||
{
|
||||
LanesInfo lanesInfo = {{{LaneWay::Right}}};
|
||||
TEST(!impl::SetUnrestrictedLaneAsRecommended(CarDirection::TurnRight, lanesInfo), ());
|
||||
TEST_EQUAL(lanesInfo[0].recommendedWay, LaneWay::None, ());
|
||||
}
|
||||
}
|
||||
|
||||
UNIT_TEST(SelectRecommendedLanes)
|
||||
{
|
||||
std::vector<TurnItem> turns = {{1, CarDirection::GoStraight},
|
||||
{2, CarDirection::TurnLeft},
|
||||
{3, CarDirection::TurnRight},
|
||||
{4, CarDirection::ReachedYourDestination}};
|
||||
turns[0].m_lanes.push_back({{LaneWay::Left, LaneWay::Through}});
|
||||
turns[0].m_lanes.push_back({{LaneWay::Right}});
|
||||
turns[1].m_lanes.push_back({{LaneWay::SlightLeft}});
|
||||
turns[1].m_lanes.push_back({{LaneWay::Through}});
|
||||
turns[1].m_lanes.push_back({{LaneWay::None}});
|
||||
turns[2].m_lanes.push_back({{LaneWay::Left, LaneWay::SharpLeft}});
|
||||
turns[2].m_lanes.push_back({{LaneWay::None}});
|
||||
std::vector<RouteSegment> routeSegments;
|
||||
RouteSegmentsFrom({}, {}, turns, {}, routeSegments);
|
||||
SelectRecommendedLanes(routeSegments);
|
||||
TEST_EQUAL(routeSegments[0].GetTurn().m_lanes[0].recommendedWay, LaneWay::Through, ());
|
||||
TEST_EQUAL(routeSegments[0].GetTurn().m_lanes[1].recommendedWay, LaneWay::None, ());
|
||||
TEST_EQUAL(routeSegments[1].GetTurn().m_lanes[0].recommendedWay, LaneWay::SlightLeft, ());
|
||||
TEST_EQUAL(routeSegments[1].GetTurn().m_lanes[1].recommendedWay, LaneWay::None, ());
|
||||
TEST_EQUAL(routeSegments[1].GetTurn().m_lanes[2].recommendedWay, LaneWay::None, ());
|
||||
TEST_EQUAL(routeSegments[2].GetTurn().m_lanes[0].recommendedWay, LaneWay::None, ());
|
||||
TEST_EQUAL(routeSegments[2].GetTurn().m_lanes[1].recommendedWay, LaneWay::Right, ());
|
||||
}
|
||||
} // namespace routing::turns::lanes::test
|
||||
231
libs/routing/routing_tests/maxspeeds_tests.cpp
Normal file
231
libs/routing/routing_tests/maxspeeds_tests.cpp
Normal file
|
|
@ -0,0 +1,231 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/maxspeeds.hpp"
|
||||
#include "routing/maxspeeds_serialization.hpp"
|
||||
|
||||
#include "routing_common/maxspeed_conversion.hpp"
|
||||
|
||||
#include "platform/measurement_utils.hpp"
|
||||
|
||||
#include "coding/reader.hpp"
|
||||
#include "coding/writer.hpp"
|
||||
|
||||
#include "base/file_name_utils.hpp"
|
||||
|
||||
#include <cstdint>
|
||||
#include <limits>
|
||||
#include <vector>
|
||||
|
||||
namespace maxspeeds_test
|
||||
{
|
||||
using namespace measurement_utils;
|
||||
using namespace routing;
|
||||
using namespace std;
|
||||
|
||||
void TestMaxspeedsSerialization(vector<FeatureMaxspeed> const & speeds)
|
||||
{
|
||||
vector<char> buffer;
|
||||
MemWriter<vector<char>> w(buffer);
|
||||
|
||||
std::vector<MaxspeedsSerializer::FeatureSpeedMacro> inputSpeeds;
|
||||
inputSpeeds.reserve(speeds.size());
|
||||
MaxspeedConverter const & converter = GetMaxspeedConverter();
|
||||
for (auto const & s : speeds)
|
||||
{
|
||||
inputSpeeds.push_back({s.GetFeatureId(), converter.SpeedToMacro(s.GetForwardSpeedInUnits()),
|
||||
converter.SpeedToMacro(s.GetBackwardSpeedInUnits())});
|
||||
}
|
||||
|
||||
int constexpr SPEEDS_COUNT = MaxspeedsSerializer::DEFAULT_SPEEDS_COUNT;
|
||||
SpeedInUnits defSpeeds[SPEEDS_COUNT];
|
||||
MaxspeedsSerializer::HW2SpeedMap defaultMap[SPEEDS_COUNT];
|
||||
|
||||
if (!speeds.empty())
|
||||
{
|
||||
defSpeeds[0] = speeds.front().GetForwardSpeedInUnits();
|
||||
defSpeeds[1] = speeds.back().GetForwardSpeedInUnits();
|
||||
defaultMap[0][HighwayType::HighwayPrimary] = converter.SpeedToMacro(defSpeeds[0]);
|
||||
defaultMap[1][HighwayType::HighwaySecondary] = converter.SpeedToMacro(defSpeeds[1]);
|
||||
}
|
||||
|
||||
MaxspeedsSerializer::Serialize(inputSpeeds, defaultMap, w);
|
||||
|
||||
size_t const sz = buffer.size();
|
||||
|
||||
MemReader r(buffer.data(), sz);
|
||||
ReaderSource<MemReader> src(r);
|
||||
Maxspeeds maxspeeds;
|
||||
MaxspeedsSerializer::Deserialize(src, maxspeeds);
|
||||
|
||||
for (auto const & s : speeds)
|
||||
TEST_EQUAL(maxspeeds.GetMaxspeed(s.GetFeatureId()), s.GetMaxspeed(), (s));
|
||||
|
||||
TEST_EQUAL(maxspeeds.GetDefaultSpeed(false, HighwayType::HighwayPrimary), defSpeeds[0].GetSpeed(), ());
|
||||
TEST_EQUAL(maxspeeds.GetDefaultSpeed(true, HighwayType::HighwaySecondary), defSpeeds[1].GetSpeed(), ());
|
||||
}
|
||||
|
||||
UNIT_TEST(MaxspeedConverter_Smoke)
|
||||
{
|
||||
auto const & conv = GetMaxspeedConverter();
|
||||
|
||||
// All maxspeed limits conversion test.
|
||||
for (size_t i = 0; i < numeric_limits<uint8_t>::max(); ++i)
|
||||
{
|
||||
auto const macro = static_cast<SpeedMacro>(i);
|
||||
auto const speed = conv.MacroToSpeed(macro);
|
||||
auto const backToMacro = conv.SpeedToMacro(speed);
|
||||
if (speed.IsValid())
|
||||
TEST_EQUAL(backToMacro, macro, (i));
|
||||
else
|
||||
TEST_EQUAL(backToMacro, SpeedMacro::Undefined, (i));
|
||||
}
|
||||
|
||||
// Test on conversion some maxspeed value to macro.
|
||||
TEST_EQUAL(conv.SpeedToMacro(SpeedInUnits(kInvalidSpeed, Units::Metric)), SpeedMacro::Undefined, ());
|
||||
TEST_EQUAL(conv.SpeedToMacro(SpeedInUnits(kNoneMaxSpeed, Units::Metric)), SpeedMacro::None, ());
|
||||
TEST_EQUAL(conv.SpeedToMacro(SpeedInUnits(kWalkMaxSpeed, Units::Metric)), SpeedMacro::Walk, ());
|
||||
TEST_EQUAL(conv.SpeedToMacro(SpeedInUnits(60, Units::Metric)), SpeedMacro::Speed60KmPH, ());
|
||||
TEST_EQUAL(conv.SpeedToMacro(SpeedInUnits(90, Units::Metric)), SpeedMacro::Speed90KmPH, ());
|
||||
TEST_EQUAL(conv.SpeedToMacro(SpeedInUnits(30, Units::Imperial)), SpeedMacro::Speed30MPH, ());
|
||||
TEST_EQUAL(conv.SpeedToMacro(SpeedInUnits(33, Units::Metric)), SpeedMacro::Undefined, ());
|
||||
|
||||
// Test on conversion some maxspeed to macro to value.
|
||||
TEST_EQUAL(conv.MacroToSpeed(SpeedMacro::Undefined), SpeedInUnits(kInvalidSpeed, Units::Metric), ());
|
||||
TEST_EQUAL(conv.MacroToSpeed(SpeedMacro::None), SpeedInUnits(kNoneMaxSpeed, Units::Metric), ());
|
||||
TEST_EQUAL(conv.MacroToSpeed(SpeedMacro::Walk), SpeedInUnits(kWalkMaxSpeed, Units::Metric), ());
|
||||
TEST_EQUAL(conv.MacroToSpeed(SpeedMacro::Speed60KmPH), SpeedInUnits(60, Units::Metric), ());
|
||||
TEST_EQUAL(conv.MacroToSpeed(SpeedMacro::Speed90KmPH), SpeedInUnits(90, Units::Metric), ());
|
||||
TEST_EQUAL(conv.MacroToSpeed(SpeedMacro::Speed30MPH), SpeedInUnits(30, Units::Imperial), ());
|
||||
}
|
||||
|
||||
UNIT_TEST(MaxspeedConverter_ClosestValidMacro)
|
||||
{
|
||||
auto const & conv = GetMaxspeedConverter();
|
||||
|
||||
SpeedInUnits expected{1, Units::Metric};
|
||||
TEST_EQUAL(conv.ClosestValidMacro({0, Units::Metric}), expected, ());
|
||||
TEST_EQUAL(conv.ClosestValidMacro(expected), expected, ());
|
||||
|
||||
expected = {380, Units::Metric};
|
||||
TEST_EQUAL(conv.ClosestValidMacro(expected), expected, ());
|
||||
TEST_EQUAL(conv.ClosestValidMacro({400, Units::Metric}), expected, ());
|
||||
|
||||
expected = {3, Units::Imperial};
|
||||
TEST_EQUAL(conv.ClosestValidMacro({0, Units::Imperial}), expected, ());
|
||||
TEST_EQUAL(conv.ClosestValidMacro({1, Units::Imperial}), expected, ());
|
||||
TEST_EQUAL(conv.ClosestValidMacro(expected), expected, ());
|
||||
|
||||
expected = {125, Units::Imperial};
|
||||
TEST_EQUAL(conv.ClosestValidMacro(expected), expected, ());
|
||||
TEST_EQUAL(conv.ClosestValidMacro({150, Units::Imperial}), expected, ());
|
||||
|
||||
expected = {50, Units::Metric};
|
||||
TEST_EQUAL(conv.ClosestValidMacro({48, Units::Metric}), expected, ());
|
||||
TEST_EQUAL(conv.ClosestValidMacro({52, Units::Metric}), expected, ());
|
||||
|
||||
expected = {40, Units::Imperial};
|
||||
TEST_EQUAL(conv.ClosestValidMacro({42, Units::Imperial}), expected, ());
|
||||
TEST_EQUAL(conv.ClosestValidMacro({38, Units::Imperial}), expected, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(MaxspeedsSerializer_Smoke)
|
||||
{
|
||||
TestMaxspeedsSerialization({});
|
||||
}
|
||||
|
||||
UNIT_TEST(MaxspeedsSerializer_OneForwardMetric)
|
||||
{
|
||||
TestMaxspeedsSerialization({FeatureMaxspeed(0 /* feature id */, Units::Metric, 20 /* speed */)});
|
||||
}
|
||||
|
||||
UNIT_TEST(MaxspeedsSerializer_OneNone)
|
||||
{
|
||||
TestMaxspeedsSerialization({FeatureMaxspeed(0 /* feature id */, Units::Metric, kNoneMaxSpeed)});
|
||||
}
|
||||
|
||||
UNIT_TEST(MaxspeedsSerializer_OneWalk)
|
||||
{
|
||||
TestMaxspeedsSerialization({FeatureMaxspeed(0 /* feature id */, Units::Metric, kWalkMaxSpeed)});
|
||||
}
|
||||
|
||||
UNIT_TEST(MaxspeedsSerializer_OneBidirectionalMetric_1)
|
||||
{
|
||||
TestMaxspeedsSerialization({FeatureMaxspeed(0 /* feature id */, Units::Metric, 20 /* speed */, 40 /* speed */)});
|
||||
}
|
||||
|
||||
UNIT_TEST(MaxspeedsSerializer_OneBidirectionalMetric_2)
|
||||
{
|
||||
TestMaxspeedsSerialization({FeatureMaxspeed(0 /* feature id */, Units::Metric, 10 /* speed */, kWalkMaxSpeed)});
|
||||
}
|
||||
|
||||
UNIT_TEST(MaxspeedsSerializer_OneBidirectionalImperial)
|
||||
{
|
||||
TestMaxspeedsSerialization({FeatureMaxspeed(0 /* feature id */, Units::Imperial, 30 /* speed */, 50 /* speed */)});
|
||||
}
|
||||
|
||||
UNIT_TEST(MaxspeedsSerializer_BigMetric)
|
||||
{
|
||||
std::vector<FeatureMaxspeed> const maxspeeds = {
|
||||
{0 /* feature id */, Units::Metric, 20 /* speed */},
|
||||
{1 /* feature id */, Units::Metric, 60 /* speed */},
|
||||
{4 /* feature id */, Units::Metric, 90 /* speed */},
|
||||
{5 /* feature id */, Units::Metric, 5 /* speed */},
|
||||
{7 /* feature id */, Units::Metric, 70 /* speed */, 90 /* speed */},
|
||||
{8 /* feature id */, Units::Metric, 100 /* speed */},
|
||||
{9 /* feature id */, Units::Metric, 60 /* speed */},
|
||||
{10 /* feature id */, Units::Metric, kNoneMaxSpeed},
|
||||
{11 /* feature id */, Units::Metric, 40 /* speed */, 50 /* speed */},
|
||||
{12 /* feature id */, Units::Metric, 40 /* speed */, 60 /* speed */},
|
||||
};
|
||||
TestMaxspeedsSerialization(maxspeeds);
|
||||
}
|
||||
|
||||
UNIT_TEST(MaxspeedsSerializer_BigImperial)
|
||||
{
|
||||
std::vector<FeatureMaxspeed> const maxspeeds = {
|
||||
{0 /* feature id */, Units::Imperial, 30 /* speed */},
|
||||
{1 /* feature id */, Units::Imperial, 5 /* speed */},
|
||||
{4 /* feature id */, Units::Imperial, 3 /* speed */},
|
||||
{5 /* feature id */, Units::Imperial, 5 /* speed */},
|
||||
{7 /* feature id */, Units::Imperial, 30 /* speed */, 50 /* speed */},
|
||||
{8 /* feature id */, Units::Imperial, 70 /* speed */},
|
||||
{9 /* feature id */, Units::Imperial, 50 /* speed */},
|
||||
{10 /* feature id */, Units::Imperial, 40 /* speed */, 50 /* speed */},
|
||||
{11 /* feature id */, Units::Imperial, 30 /* speed */, 50 /* speed */},
|
||||
};
|
||||
TestMaxspeedsSerialization(maxspeeds);
|
||||
}
|
||||
|
||||
UNIT_TEST(Maxspeed_Smoke)
|
||||
{
|
||||
{
|
||||
Maxspeed maxspeed;
|
||||
TEST(!maxspeed.IsValid(), ());
|
||||
TEST(!maxspeed.IsBidirectional(), ());
|
||||
TEST_EQUAL(maxspeed.GetSpeedInUnits(true /* forward */), kInvalidSpeed, ());
|
||||
TEST_EQUAL(maxspeed.GetSpeedKmPH(true /* forward */), kInvalidSpeed, ());
|
||||
TEST_EQUAL(maxspeed.GetSpeedInUnits(false /* forward */), kInvalidSpeed, ());
|
||||
TEST_EQUAL(maxspeed.GetSpeedKmPH(false /* forward */), kInvalidSpeed, ());
|
||||
}
|
||||
|
||||
{
|
||||
Maxspeed maxspeed = {Units::Metric, 20 /* forward */, kInvalidSpeed /* backward */};
|
||||
TEST(maxspeed.IsValid(), ());
|
||||
TEST(!maxspeed.IsBidirectional(), ());
|
||||
TEST_EQUAL(maxspeed.GetSpeedInUnits(true /* forward */), 20, ());
|
||||
TEST_EQUAL(maxspeed.GetSpeedKmPH(true /* forward */), 20, ());
|
||||
TEST_EQUAL(maxspeed.GetSpeedInUnits(false /* forward */), 20, ());
|
||||
TEST_EQUAL(maxspeed.GetSpeedKmPH(false /* forward */), 20, ());
|
||||
}
|
||||
|
||||
{
|
||||
Maxspeed maxspeed = {Units::Metric, 30 /* forward */, 40 /* backward */};
|
||||
TEST(maxspeed.IsValid(), ());
|
||||
TEST(maxspeed.IsBidirectional(), ());
|
||||
TEST_EQUAL(maxspeed.GetSpeedInUnits(true /* forward */), 30, ());
|
||||
TEST_EQUAL(maxspeed.GetSpeedKmPH(true /* forward */), 30, ());
|
||||
TEST_EQUAL(maxspeed.GetSpeedInUnits(false /* forward */), 40, ());
|
||||
TEST_EQUAL(maxspeed.GetSpeedKmPH(false /* forward */), 40, ());
|
||||
}
|
||||
}
|
||||
} // namespace maxspeeds_test
|
||||
75
libs/routing/routing_tests/mwm_hierarchy_test.cpp
Normal file
75
libs/routing/routing_tests/mwm_hierarchy_test.cpp
Normal file
|
|
@ -0,0 +1,75 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/mwm_hierarchy_handler.hpp"
|
||||
|
||||
#include "storage/country_parent_getter.hpp"
|
||||
#include "storage/routing_helpers.hpp"
|
||||
|
||||
namespace mwm_hierarchy_test
|
||||
{
|
||||
using namespace routing;
|
||||
|
||||
UNIT_TEST(CountryParentGetter_Smoke)
|
||||
{
|
||||
storage::CountryParentGetter getter;
|
||||
TEST_EQUAL(getter("Belarus_Hrodna Region"), "Belarus", ());
|
||||
TEST_EQUAL(getter("Russia_Arkhangelsk Oblast_Central"), "Russian Federation", ());
|
||||
TEST_EQUAL(getter("Crimea"), "", ());
|
||||
|
||||
TEST_EQUAL(getter("Israel"), "Israel Region", ());
|
||||
TEST_EQUAL(getter("Palestine"), "Palestine Region", ());
|
||||
TEST_EQUAL(getter("Jerusalem"), "", ());
|
||||
TEST_EQUAL(getter("US_New York_New York"), "New York", ());
|
||||
TEST_EQUAL(getter("UK_England_West Midlands"), "United Kingdom", ());
|
||||
}
|
||||
|
||||
uint16_t GetCountryID(std::shared_ptr<NumMwmIds> const & mwmIDs, std::string mwmName)
|
||||
{
|
||||
return mwmIDs->GetId(platform::CountryFile(std::move(mwmName)));
|
||||
}
|
||||
|
||||
UNIT_TEST(MwmHierarchyHandler_Smoke)
|
||||
{
|
||||
storage::CountryParentGetter getter;
|
||||
auto mwmIDs = CreateNumMwmIds(getter.GetStorageForTesting());
|
||||
routing::MwmHierarchyHandler handler(mwmIDs, getter);
|
||||
|
||||
TEST(!handler.HasCrossBorderPenalty(GetCountryID(mwmIDs, "Belarus_Maglieu Region"),
|
||||
GetCountryID(mwmIDs, "Belarus_Vitebsk Region")),
|
||||
());
|
||||
TEST(handler.HasCrossBorderPenalty(GetCountryID(mwmIDs, "Belarus_Hrodna Region"),
|
||||
GetCountryID(mwmIDs, "Lithuania_East")),
|
||||
());
|
||||
TEST(!handler.HasCrossBorderPenalty(GetCountryID(mwmIDs, "Belarus_Maglieu Region"),
|
||||
GetCountryID(mwmIDs, "Russia_Smolensk Oblast")),
|
||||
());
|
||||
TEST(handler.HasCrossBorderPenalty(GetCountryID(mwmIDs, "Ukraine_Kherson Oblast"), GetCountryID(mwmIDs, "Crimea")),
|
||||
());
|
||||
TEST(handler.HasCrossBorderPenalty(GetCountryID(mwmIDs, "Russia_Krasnodar Krai"), GetCountryID(mwmIDs, "Crimea")),
|
||||
());
|
||||
TEST(!handler.HasCrossBorderPenalty(GetCountryID(mwmIDs, "Denmark_Region Zealand"),
|
||||
GetCountryID(mwmIDs, "Denmark_Region of Southern Denmark")),
|
||||
());
|
||||
|
||||
TEST(handler.HasCrossBorderPenalty(GetCountryID(mwmIDs, "Ukraine_Zakarpattia Oblast"),
|
||||
GetCountryID(mwmIDs, "Slovakia_Region of Kosice")),
|
||||
());
|
||||
TEST(handler.HasCrossBorderPenalty(GetCountryID(mwmIDs, "Ukraine_Zakarpattia Oblast"),
|
||||
GetCountryID(mwmIDs, "Hungary_Northern Great Plain")),
|
||||
());
|
||||
TEST(!handler.HasCrossBorderPenalty(GetCountryID(mwmIDs, "Hungary_Northern Great Plain"),
|
||||
GetCountryID(mwmIDs, "Slovakia_Region of Kosice")),
|
||||
());
|
||||
|
||||
TEST(!handler.HasCrossBorderPenalty(GetCountryID(mwmIDs, "Ireland_Connacht"),
|
||||
GetCountryID(mwmIDs, "UK_Northern Ireland")),
|
||||
());
|
||||
TEST(handler.HasCrossBorderPenalty(GetCountryID(mwmIDs, "Ireland_Leinster"), GetCountryID(mwmIDs, "UK_Wales")), ());
|
||||
|
||||
char const * ip[] = {"Israel", "Jerusalem", "Palestine"};
|
||||
for (auto s1 : ip)
|
||||
for (auto s2 : ip)
|
||||
TEST(!handler.HasCrossBorderPenalty(GetCountryID(mwmIDs, s1), GetCountryID(mwmIDs, s2)), (s1, s2));
|
||||
}
|
||||
|
||||
} // namespace mwm_hierarchy_test
|
||||
74
libs/routing/routing_tests/nearest_edge_finder_tests.cpp
Normal file
74
libs/routing/routing_tests/nearest_edge_finder_tests.cpp
Normal file
|
|
@ -0,0 +1,74 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/routing_tests/road_graph_builder.hpp"
|
||||
|
||||
#include "routing/nearest_edge_finder.hpp"
|
||||
#include "routing/road_graph.hpp"
|
||||
|
||||
#include "routing_common/maxspeed_conversion.hpp"
|
||||
|
||||
#include "geometry/point_with_altitude.hpp"
|
||||
|
||||
#include "base/checked_cast.hpp"
|
||||
|
||||
namespace nearest_edge_finder_tests
|
||||
{
|
||||
using namespace routing;
|
||||
using namespace routing_test;
|
||||
using namespace std;
|
||||
|
||||
void TestNearestOnMock1(m2::PointD const & point, size_t const candidatesCount,
|
||||
vector<pair<Edge, geometry::PointWithAltitude>> const & expected)
|
||||
{
|
||||
unique_ptr<RoadGraphMockSource> graph(new RoadGraphMockSource());
|
||||
InitRoadGraphMockSourceWithTest1(*graph);
|
||||
|
||||
NearestEdgeFinder finder(point, nullptr /* isEdgeProjGood */);
|
||||
for (size_t i = 0; i < graph->GetRoadCount(); ++i)
|
||||
{
|
||||
FeatureID const featureId = MakeTestFeatureID(base::checked_cast<uint32_t>(i));
|
||||
auto const & roadInfo = graph->GetRoadInfo(featureId, {true /* forward */, false /* in city */, Maxspeed()});
|
||||
finder.AddInformationSource(IRoadGraph::FullRoadInfo(featureId, roadInfo));
|
||||
}
|
||||
|
||||
vector<pair<Edge, geometry::PointWithAltitude>> result;
|
||||
TEST(finder.HasCandidates(), ());
|
||||
finder.MakeResult(result, candidatesCount);
|
||||
|
||||
TEST_EQUAL(result, expected, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(StarterPosAtBorder_Mock1Graph)
|
||||
{
|
||||
vector<pair<Edge, geometry::PointWithAltitude>> const expected = {
|
||||
make_pair(Edge::MakeReal(MakeTestFeatureID(0), true /* forward */, 0,
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 0)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(5, 0))),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 0)))};
|
||||
TestNearestOnMock1(m2::PointD(0, 0), 1, expected);
|
||||
}
|
||||
|
||||
UNIT_TEST(MiddleEdgeTest_Mock1Graph)
|
||||
{
|
||||
vector<pair<Edge, geometry::PointWithAltitude>> const expected = {
|
||||
make_pair(Edge::MakeReal(MakeTestFeatureID(0), true /* forward */, 0,
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 0)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(5, 0))),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(3, 0)))};
|
||||
TestNearestOnMock1(m2::PointD(3, 3), 1, expected);
|
||||
}
|
||||
|
||||
UNIT_TEST(MiddleSegmentTest_Mock1Graph)
|
||||
{
|
||||
vector<pair<Edge, geometry::PointWithAltitude>> const expected = {
|
||||
make_pair(Edge::MakeReal(MakeTestFeatureID(0), true /* forward */, 2,
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(10, 0)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(15, 0))),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(12.5, 0))),
|
||||
make_pair(Edge::MakeReal(MakeTestFeatureID(0), false /* forward */, 2,
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(15, 0)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(10, 0))),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(12.5, 0)))};
|
||||
TestNearestOnMock1(m2::PointD(12.5, 2.5), 2, expected);
|
||||
}
|
||||
} // namespace nearest_edge_finder_tests
|
||||
858
libs/routing/routing_tests/opening_hours_serdes_tests.cpp
Normal file
858
libs/routing/routing_tests/opening_hours_serdes_tests.cpp
Normal file
|
|
@ -0,0 +1,858 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/opening_hours_serdes.hpp"
|
||||
#include "routing/routing_tests/index_graph_tools.hpp"
|
||||
|
||||
#include "coding/bit_streams.hpp"
|
||||
#include "coding/reader.hpp"
|
||||
#include "coding/writer.hpp"
|
||||
|
||||
#include "base/string_utils.hpp"
|
||||
|
||||
#include <ctime>
|
||||
#include <memory>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
namespace opening_hours_serdes_tests
|
||||
{
|
||||
using namespace routing;
|
||||
using namespace routing_test;
|
||||
|
||||
using Buffer = std::vector<uint8_t>;
|
||||
|
||||
struct OHSerDesTestFixture
|
||||
{
|
||||
OHSerDesTestFixture()
|
||||
: m_memWriter(m_buffer)
|
||||
, m_bitWriter(std::make_unique<BitWriter<MemWriter<Buffer>>>(m_memWriter))
|
||||
{}
|
||||
|
||||
BitWriter<MemWriter<Buffer>> & GetWriter() { return *m_bitWriter; }
|
||||
BitReader<ReaderSource<MemReader>> & GetReader()
|
||||
{
|
||||
if (m_bitReader)
|
||||
return *m_bitReader;
|
||||
|
||||
m_memReader = std::make_unique<MemReader>(m_buffer.data(), m_buffer.size());
|
||||
m_readerSource = std::make_unique<ReaderSource<MemReader>>(*m_memReader);
|
||||
m_bitReader = std::make_unique<BitReader<ReaderSource<MemReader>>>(*m_readerSource);
|
||||
return *m_bitReader;
|
||||
}
|
||||
|
||||
void Enable(OpeningHoursSerDes::Header::Bits feature) { m_serializer.Enable(feature); }
|
||||
|
||||
void EnableAll()
|
||||
{
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Year);
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Month);
|
||||
Enable(OpeningHoursSerDes::Header::Bits::MonthDay);
|
||||
Enable(OpeningHoursSerDes::Header::Bits::WeekDay);
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Hours);
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Minutes);
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Off);
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Holiday);
|
||||
}
|
||||
|
||||
void EnableForRouting()
|
||||
{
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Year);
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Month);
|
||||
Enable(OpeningHoursSerDes::Header::Bits::MonthDay);
|
||||
Enable(OpeningHoursSerDes::Header::Bits::WeekDay);
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Hours);
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Minutes);
|
||||
}
|
||||
|
||||
bool IsEnabled(OpeningHoursSerDes::Header::Bits feature) { return m_serializer.IsEnabled(feature); }
|
||||
bool Serialize(std::string const & oh) { return m_serializer.Serialize(GetWriter(), oh); }
|
||||
osmoh::OpeningHours Deserialize() { return m_serializer.Deserialize(GetReader()); }
|
||||
void SerializeEverything() { m_serializer.SetSerializeEverything(); }
|
||||
|
||||
void Flush() { m_bitWriter.reset(); }
|
||||
|
||||
OpeningHoursSerDes m_serializer;
|
||||
|
||||
Buffer m_buffer;
|
||||
MemWriter<Buffer> m_memWriter;
|
||||
std::unique_ptr<BitWriter<MemWriter<Buffer>>> m_bitWriter;
|
||||
|
||||
std::unique_ptr<MemReader> m_memReader;
|
||||
std::unique_ptr<ReaderSource<MemReader>> m_readerSource;
|
||||
std::unique_ptr<BitReader<ReaderSource<MemReader>>> m_bitReader;
|
||||
};
|
||||
|
||||
void TestYear(osmoh::RuleSequence const & rule, uint32_t start, uint32_t end)
|
||||
{
|
||||
TEST_EQUAL(rule.GetYears().size(), 1, ());
|
||||
TEST_EQUAL(rule.GetYears().back().GetStart(), start, ());
|
||||
TEST_EQUAL(rule.GetYears().back().GetEnd(), end, ());
|
||||
}
|
||||
|
||||
void TestWeekday(osmoh::RuleSequence const & rule, Weekday start, Weekday end)
|
||||
{
|
||||
TEST_EQUAL(rule.GetWeekdays().GetWeekdayRanges().size(), 1, ());
|
||||
auto const & weekday = rule.GetWeekdays().GetWeekdayRanges()[0];
|
||||
|
||||
TEST_EQUAL(weekday.GetStart(), start, ());
|
||||
TEST_EQUAL(weekday.GetEnd(), end, ());
|
||||
}
|
||||
|
||||
void TestHoliday(osmoh::RuleSequence const & rule, bool forSchool)
|
||||
{
|
||||
TEST_EQUAL(rule.GetWeekdays().GetHolidays().size(), 1, ());
|
||||
TEST_EQUAL(rule.GetWeekdays().GetHolidays().back().IsPlural(), !forSchool, ());
|
||||
}
|
||||
|
||||
void TestModifier(osmoh::RuleSequence const & rule, osmoh::RuleSequence::Modifier modifier)
|
||||
{
|
||||
TEST_EQUAL(rule.GetModifier(), modifier, ());
|
||||
}
|
||||
|
||||
void TestTime(osmoh::RuleSequence const & rule, uint32_t startH, uint32_t startM, uint32_t endH, uint32_t endM)
|
||||
{
|
||||
TEST_EQUAL(rule.GetTimes().size(), 1, ());
|
||||
auto const & time = rule.GetTimes()[0];
|
||||
|
||||
TEST_EQUAL(time.GetStart().GetHoursCount(), startH, ());
|
||||
TEST_EQUAL(time.GetStart().GetMinutesCount(), startM, ());
|
||||
|
||||
TEST_EQUAL(time.GetEnd().GetHoursCount(), endH, ());
|
||||
TEST_EQUAL(time.GetEnd().GetMinutesCount(), endM, ());
|
||||
}
|
||||
|
||||
void TestMonth(osmoh::RuleSequence const & rule, uint32_t startYear, Month startMonth,
|
||||
osmoh::MonthDay::TDayNum startDay, uint32_t endYear, Month endMonth, osmoh::MonthDay::TDayNum endDay)
|
||||
{
|
||||
TEST_EQUAL(rule.GetMonths().size(), 1, ());
|
||||
auto const & range = rule.GetMonths().back();
|
||||
|
||||
TEST_EQUAL(range.GetStart().GetYear(), startYear, ());
|
||||
TEST_EQUAL(range.GetStart().GetMonth(), startMonth, ());
|
||||
TEST_EQUAL(range.GetStart().GetDayNum(), startDay, ());
|
||||
|
||||
TEST_EQUAL(range.GetEnd().GetYear(), endYear, ());
|
||||
TEST_EQUAL(range.GetEnd().GetMonth(), endMonth, ());
|
||||
TEST_EQUAL(range.GetEnd().GetDayNum(), endDay, ());
|
||||
}
|
||||
|
||||
void TestMonth(osmoh::RuleSequence const & rule, Month startMonth, osmoh::MonthDay::TDayNum startDay, Month endMonth,
|
||||
osmoh::MonthDay::TDayNum endDay)
|
||||
{
|
||||
TestMonth(rule, 0 /* startYear */, startMonth, startDay, 0 /* endYear */, endMonth, endDay);
|
||||
}
|
||||
|
||||
void TestMonth(osmoh::RuleSequence const & rule, Month startMonth, Month endMonth)
|
||||
{
|
||||
TestMonth(rule, 0 /* startYear */, startMonth, 0 /* startDay */, 0 /* endYear*/, endMonth, 0 /* endDay */);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_EnableTests_1)
|
||||
{
|
||||
TEST(!IsEnabled(OpeningHoursSerDes::Header::Bits::Year), ());
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Year);
|
||||
TEST(IsEnabled(OpeningHoursSerDes::Header::Bits::Year), ());
|
||||
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Month);
|
||||
TEST(IsEnabled(OpeningHoursSerDes::Header::Bits::Month), ());
|
||||
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Minutes);
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Minutes);
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Minutes);
|
||||
TEST(IsEnabled(OpeningHoursSerDes::Header::Bits::Minutes), ());
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_EnableTests_2)
|
||||
{
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Year);
|
||||
Enable(OpeningHoursSerDes::Header::Bits::WeekDay);
|
||||
TEST(Serialize("2019 - 2051"), ());
|
||||
TEST(Serialize("Mo-Su"), ());
|
||||
// Not enabled
|
||||
TEST(!Serialize("Apr - May"), ());
|
||||
TEST(!Serialize("2019 Nov 30 - 2090 Mar 31"), ());
|
||||
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Month);
|
||||
Enable(OpeningHoursSerDes::Header::Bits::MonthDay);
|
||||
TEST(Serialize("Apr - May"), ());
|
||||
TEST(Serialize("2019 Nov 30 - 2090 Mar 31"), ());
|
||||
}
|
||||
|
||||
// Test on serialization ranges where start is later than end.
|
||||
// It is wrong but still possible data.
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_CannotSerialize)
|
||||
{
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Year);
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Month);
|
||||
TEST(!Serialize("2020 - 2019"), ());
|
||||
TEST(!Serialize("2020 May 20 - 2018 Nov 30"), ());
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_YearOnly)
|
||||
{
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Year);
|
||||
|
||||
TEST(Serialize("2019 - 2090"), ());
|
||||
Flush();
|
||||
|
||||
osmoh::OpeningHours oh = Deserialize();
|
||||
TEST(oh.IsValid(), ());
|
||||
TEST_EQUAL(oh.GetRule().size(), 1, ());
|
||||
|
||||
auto const & rule = oh.GetRule().back();
|
||||
TestYear(rule, 2019, 2090);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_YearAndMonthOnly)
|
||||
{
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Year);
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Month);
|
||||
Enable(OpeningHoursSerDes::Header::Bits::MonthDay);
|
||||
|
||||
TEST(Serialize("2019 Apr 10 - 2051 May 19"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
TEST(oh.IsValid(), ());
|
||||
TEST_EQUAL(oh.GetRule().size(), 1, ());
|
||||
|
||||
auto const & rule = oh.GetRule().back();
|
||||
TestMonth(rule, 2019, Month::Apr, 10, 2051, Month::May, 19);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_Weekday_1)
|
||||
{
|
||||
Enable(OpeningHoursSerDes::Header::Bits::WeekDay);
|
||||
|
||||
TEST(Serialize("Mo-Fr"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
TEST(oh.IsValid(), ());
|
||||
TEST_EQUAL(oh.GetRule().size(), 1, ());
|
||||
|
||||
auto const & rule = oh.GetRule().back();
|
||||
TestWeekday(rule, Weekday::Monday, Weekday::Friday);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_Weekday_2)
|
||||
{
|
||||
Enable(OpeningHoursSerDes::Header::Bits::WeekDay);
|
||||
|
||||
TEST(Serialize("Mo-Tu, Fr-Su"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
TEST(oh.IsValid(), ());
|
||||
TEST_EQUAL(oh.GetRule().size(), 2, ());
|
||||
|
||||
auto rule = oh.GetRule()[0];
|
||||
TestWeekday(rule, Weekday::Monday, Weekday::Tuesday);
|
||||
|
||||
rule = oh.GetRule()[1];
|
||||
TestWeekday(rule, Weekday::Friday, Weekday::Sunday);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_Weekday_Hours_1)
|
||||
{
|
||||
Enable(OpeningHoursSerDes::Header::Bits::WeekDay);
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Hours);
|
||||
Enable(OpeningHoursSerDes::Header::Bits::Minutes);
|
||||
|
||||
TEST(Serialize("10:00 - 15:00"), ());
|
||||
TEST(Serialize("Mo-Fr 09:00 - 23:00"), ());
|
||||
TEST(Serialize("Sa - Su 10:30 - 13:00 ; Mo-Fr 00:30 - 23:45"), ());
|
||||
Flush();
|
||||
|
||||
{
|
||||
auto const oh = Deserialize();
|
||||
TEST(oh.IsValid(), ());
|
||||
TEST_EQUAL(oh.GetRule().size(), 1, ());
|
||||
auto rule = oh.GetRule().back();
|
||||
|
||||
TestTime(rule, 10, 0, 15, 0);
|
||||
}
|
||||
{
|
||||
auto const oh = Deserialize();
|
||||
TEST(oh.IsValid(), ());
|
||||
TEST_EQUAL(oh.GetRule().size(), 1, ());
|
||||
auto rule = oh.GetRule().back();
|
||||
|
||||
TestWeekday(rule, Weekday::Monday, Weekday::Friday);
|
||||
TestTime(rule, 9, 0, 23, 0);
|
||||
}
|
||||
{
|
||||
auto const oh = Deserialize();
|
||||
TEST(oh.IsValid(), ());
|
||||
TEST_EQUAL(oh.GetRule().size(), 2, ());
|
||||
|
||||
auto rule = oh.GetRule()[0];
|
||||
TestWeekday(rule, Weekday::Saturday, Weekday::Sunday);
|
||||
TestTime(rule, 10, 30, 13, 0);
|
||||
|
||||
rule = oh.GetRule()[1];
|
||||
TestWeekday(rule, Weekday::Monday, Weekday::Friday);
|
||||
TestTime(rule, 0, 30, 23, 45);
|
||||
}
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_Off_SerDes_1_AndUsage)
|
||||
{
|
||||
SerializeEverything();
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("Tu-Su ; Mo OFF"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
TEST(oh.IsValid(), ());
|
||||
TEST_EQUAL(oh.GetRule().size(), 2, ());
|
||||
|
||||
auto rule = oh.GetRule()[0];
|
||||
TestWeekday(rule, Weekday::Tuesday, Weekday::Sunday);
|
||||
|
||||
rule = oh.GetRule()[1];
|
||||
TestWeekday(rule, Weekday::Monday, Weekday::None);
|
||||
TestModifier(rule, osmoh::RuleSequence::Modifier::Closed);
|
||||
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2020, Month::Feb, Weekday::Thursday, 17 /* hh */, 30 /* mm */)), ());
|
||||
TEST(oh.IsClosed(GetUnixtimeByDate(2020, Month::Feb, Weekday::Monday, 17 /* hh */, 30 /* mm */)), ());
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_Off_SerDes_2)
|
||||
{
|
||||
SerializeEverything();
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("Mo off; Tu-Fr 09:00-13:00,14:00-17:00; Sa 09:00-13:00,14:00-16:00; Su off"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
TEST_EQUAL(oh.GetRule().size(), 6, ());
|
||||
|
||||
auto rule = oh.GetRule()[0];
|
||||
TestWeekday(rule, Weekday::Monday, Weekday::None);
|
||||
TestModifier(rule, osmoh::RuleSequence::Modifier::Closed);
|
||||
|
||||
rule = oh.GetRule()[1];
|
||||
TestWeekday(rule, Weekday::Tuesday, Weekday::Friday);
|
||||
TestTime(rule, 9, 0, 13, 0);
|
||||
|
||||
rule = oh.GetRule()[2];
|
||||
TestWeekday(rule, Weekday::Tuesday, Weekday::Friday);
|
||||
TestTime(rule, 14, 0, 17, 0);
|
||||
|
||||
rule = oh.GetRule()[3];
|
||||
TestWeekday(rule, Weekday::Saturday, Weekday::None);
|
||||
TestTime(rule, 9, 0, 13, 0);
|
||||
|
||||
rule = oh.GetRule()[4];
|
||||
TestWeekday(rule, Weekday::Saturday, Weekday::None);
|
||||
TestTime(rule, 14, 0, 16, 0);
|
||||
|
||||
rule = oh.GetRule()[5];
|
||||
TestWeekday(rule, Weekday::Sunday, Weekday::None);
|
||||
TestModifier(rule, osmoh::RuleSequence::Modifier::Closed);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_OffJustOff)
|
||||
{
|
||||
SerializeEverything();
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("off"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
|
||||
TEST_EQUAL(oh.GetRule().size(), 1, ());
|
||||
|
||||
auto rule = oh.GetRule()[0];
|
||||
TestModifier(rule, osmoh::RuleSequence::Modifier::Closed);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_OffJustClosed)
|
||||
{
|
||||
SerializeEverything();
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("closed"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
|
||||
TEST_EQUAL(oh.GetRule().size(), 1, ());
|
||||
|
||||
auto rule = oh.GetRule()[0];
|
||||
TestModifier(rule, osmoh::RuleSequence::Modifier::Closed);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_Open)
|
||||
{
|
||||
SerializeEverything();
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("open"), ());
|
||||
Flush();
|
||||
|
||||
auto oh = Deserialize();
|
||||
TEST_EQUAL(oh.GetRule().size(), 1, ());
|
||||
|
||||
// 1500000000 - Fri Jul 14 05:40:00 2017
|
||||
// 1581330500 - Mon Feb 10 13:28:20 2020
|
||||
time_t constexpr kDaySeconds = 24 * 3600;
|
||||
for (time_t someMoment = 1500000000; someMoment < 1581330500; someMoment += kDaySeconds)
|
||||
TEST(oh.IsOpen(someMoment), ());
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_TimeIsOver00)
|
||||
{
|
||||
SerializeEverything();
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("Mo 19:00-05:00"), ());
|
||||
Flush();
|
||||
|
||||
auto oh = Deserialize();
|
||||
TEST_EQUAL(oh.GetRule().size(), 1, ());
|
||||
|
||||
TEST(!oh.IsOpen(GetUnixtimeByDate(2020, Month::Feb, Weekday::Monday, 13 /* hh */, 30 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2020, Month::Feb, Weekday::Monday, 19 /* hh */, 30 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2020, Month::Feb, Weekday::Monday, 22 /* hh */, 30 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2020, Month::Feb, Weekday::Tuesday, 02 /* hh */, 30 /* mm */)), ());
|
||||
TEST(!oh.IsOpen(GetUnixtimeByDate(2020, Month::Feb, Weekday::Tuesday, 06 /* hh */, 30 /* mm */)), ());
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_DefaultOpen)
|
||||
{
|
||||
SerializeEverything();
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("Mo-Sa"), ());
|
||||
Flush();
|
||||
|
||||
auto oh = Deserialize();
|
||||
TEST_EQUAL(oh.GetRule().size(), 1, ());
|
||||
|
||||
auto const & rule = oh.GetRule().back();
|
||||
TestWeekday(rule, Weekday::Monday, Weekday::Saturday);
|
||||
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2020, Month::Feb, Weekday::Monday, 13 /* hh */, 30 /* mm */)), ());
|
||||
TEST(!oh.IsOpen(GetUnixtimeByDate(2020, Month::Feb, Weekday::Sunday, 13 /* hh */, 30 /* mm */)), ());
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_SkipRuleOldYear)
|
||||
{
|
||||
SerializeEverything();
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("Mo-Fr 07:00-17:00; 2014 Jul 28-2014 Aug 01 off"), ());
|
||||
Flush();
|
||||
|
||||
// Skip rule with old year range.
|
||||
auto const oh = Deserialize();
|
||||
TEST_EQUAL(oh.GetRule().size(), 1, ());
|
||||
auto const & rule = oh.GetRule().back();
|
||||
|
||||
TestWeekday(rule, Weekday::Monday, Weekday::Friday);
|
||||
TestTime(rule, 7, 0, 17, 0);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_10_plus)
|
||||
{
|
||||
SerializeEverything();
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("Fr 10:00+"), ());
|
||||
Flush();
|
||||
|
||||
// Skip rule with old year range.
|
||||
auto const oh = Deserialize();
|
||||
TEST_EQUAL(oh.GetRule().size(), 1, ());
|
||||
auto const & rule = oh.GetRule().back();
|
||||
|
||||
TestWeekday(rule, Weekday::Friday, Weekday::None);
|
||||
TestTime(rule, 10, 0, 0, 0);
|
||||
|
||||
TEST(!oh.IsOpen(GetUnixtimeByDate(2020, Month::Mar, Weekday::Friday, 9 /* hh */, 30 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2020, Month::Mar, Weekday::Friday, 10 /* hh */, 30 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2020, Month::Mar, Weekday::Friday, 15 /* hh */, 30 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2020, Month::Mar, Weekday::Friday, 20 /* hh */, 30 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2020, Month::Mar, Weekday::Friday, 23 /* hh */, 30 /* mm */)), ());
|
||||
TEST(!oh.IsOpen(GetUnixtimeByDate(2020, Month::Mar, Weekday::Saturday, 00 /* hh */, 30 /* mm */)), ());
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_24_7)
|
||||
{
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("24/7"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
TEST(oh.IsTwentyFourHours(), ());
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_ExamplesFromOsmAccessConditional_1)
|
||||
{
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("Apr 01-Jun 30"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
|
||||
TEST_EQUAL(oh.GetRule().size(), 1, ());
|
||||
auto const & rule = oh.GetRule().back();
|
||||
|
||||
TestMonth(rule, Month::Apr, 1, Month::Jun, 30);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_ExamplesFromOsmAccessConditional_2)
|
||||
{
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("22:00-06:00"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
|
||||
TEST_EQUAL(oh.GetRule().size(), 1, ());
|
||||
auto const & rule = oh.GetRule().back();
|
||||
|
||||
TestTime(rule, 22, 0, 6, 0);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_ExamplesFromOsmAccessConditional_3)
|
||||
{
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("Oct-Mar 18:00-08:00, Apr-Sep 21:30-07:00"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
|
||||
TEST_EQUAL(oh.GetRule().size(), 2, ());
|
||||
auto rule = oh.GetRule()[0];
|
||||
TestMonth(rule, Month::Oct, Month::Mar);
|
||||
TestTime(rule, 18, 0, 8, 0);
|
||||
|
||||
rule = oh.GetRule()[1];
|
||||
TestMonth(rule, Month::Apr, Month::Sep);
|
||||
TestTime(rule, 21, 30, 7, 0);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_ExamplesFromOsmAccessConditional_4)
|
||||
{
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("apr-oct"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
|
||||
TEST_EQUAL(oh.GetRule().size(), 1, ());
|
||||
auto const & rule = oh.GetRule().back();
|
||||
|
||||
TestMonth(rule, Month::Apr, Month::Oct);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_ExamplesFromOsmAccessConditional_5)
|
||||
{
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("Mo-Fr 08:30-09:30,15:00-16:00"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
|
||||
TEST_EQUAL(oh.GetRule().size(), 2, ());
|
||||
|
||||
auto rule = oh.GetRule()[0];
|
||||
TestWeekday(rule, Weekday::Monday, Weekday::Friday);
|
||||
TestTime(rule, 8, 30, 9, 30);
|
||||
|
||||
rule = oh.GetRule()[1];
|
||||
TestWeekday(rule, Weekday::Monday, Weekday::Friday);
|
||||
TestTime(rule, 15, 0, 16, 0);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_ExamplesFromOsmAccessConditional_6)
|
||||
{
|
||||
SerializeEverything();
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("Su,PH 11:00-18:00"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
|
||||
TEST_EQUAL(oh.GetRule().size(), 2, ());
|
||||
|
||||
auto rule = oh.GetRule()[0];
|
||||
TestWeekday(rule, Weekday::Sunday, Weekday::None);
|
||||
|
||||
rule = oh.GetRule()[1];
|
||||
TestHoliday(rule, false /* forSchool */);
|
||||
TestTime(rule, 11, 0, 18, 0);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_EnableForRouting_1)
|
||||
{
|
||||
EnableForRouting();
|
||||
|
||||
TEST(Serialize("Su,PH 11:00-18:00"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
|
||||
TEST_EQUAL(oh.GetRule().size(), 1, ());
|
||||
|
||||
auto rule = oh.GetRule()[0];
|
||||
TestWeekday(rule, Weekday::Sunday, Weekday::None);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_EnableForRouting_2)
|
||||
{
|
||||
EnableForRouting();
|
||||
|
||||
TEST(Serialize("Mo,Tu,Th,Fr 08:00-08:30,15:00-15:30; We 08:00-08:30,12:00-12:30; SH off"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
|
||||
TEST_EQUAL(oh.GetRule().size(), 10, ());
|
||||
|
||||
auto rule = oh.GetRule()[0];
|
||||
TestWeekday(rule, Weekday::Monday, Weekday::None);
|
||||
TestTime(rule, 8, 0, 8, 30);
|
||||
|
||||
rule = oh.GetRule()[1];
|
||||
TestWeekday(rule, Weekday::Tuesday, Weekday::None);
|
||||
TestTime(rule, 8, 0, 8, 30);
|
||||
|
||||
rule = oh.GetRule()[2];
|
||||
TestWeekday(rule, Weekday::Thursday, Weekday::None);
|
||||
TestTime(rule, 8, 0, 8, 30);
|
||||
|
||||
rule = oh.GetRule()[3];
|
||||
TestWeekday(rule, Weekday::Friday, Weekday::None);
|
||||
TestTime(rule, 8, 0, 8, 30);
|
||||
|
||||
rule = oh.GetRule()[4];
|
||||
TestWeekday(rule, Weekday::Monday, Weekday::None);
|
||||
TestTime(rule, 15, 0, 15, 30);
|
||||
|
||||
rule = oh.GetRule()[5];
|
||||
TestWeekday(rule, Weekday::Tuesday, Weekday::None);
|
||||
TestTime(rule, 15, 0, 15, 30);
|
||||
|
||||
rule = oh.GetRule()[6];
|
||||
TestWeekday(rule, Weekday::Thursday, Weekday::None);
|
||||
TestTime(rule, 15, 0, 15, 30);
|
||||
|
||||
rule = oh.GetRule()[7];
|
||||
TestWeekday(rule, Weekday::Friday, Weekday::None);
|
||||
TestTime(rule, 15, 0, 15, 30);
|
||||
|
||||
rule = oh.GetRule()[8];
|
||||
TestWeekday(rule, Weekday::Wednesday, Weekday::None);
|
||||
TestTime(rule, 8, 0, 8, 30);
|
||||
|
||||
rule = oh.GetRule()[9];
|
||||
TestWeekday(rule, Weekday::Wednesday, Weekday::None);
|
||||
TestTime(rule, 12, 0, 12, 30);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_WeekdayAndHolidayOff)
|
||||
{
|
||||
SerializeEverything();
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("Mo-Fr 10:00-18:00; Sa 10:00-13:00; PH off"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
|
||||
TEST_EQUAL(oh.GetRule().size(), 3, ());
|
||||
|
||||
auto rule = oh.GetRule()[0];
|
||||
TestWeekday(rule, Weekday::Monday, Weekday::Friday);
|
||||
TestTime(rule, 10, 0, 18, 0);
|
||||
|
||||
rule = oh.GetRule()[1];
|
||||
TestWeekday(rule, Weekday::Saturday, Weekday::None);
|
||||
TestTime(rule, 10, 0, 13, 0);
|
||||
|
||||
rule = oh.GetRule()[2];
|
||||
TestHoliday(rule, false /* forSchool */);
|
||||
TestModifier(rule, osmoh::RuleSequence::Modifier::Closed);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_WeekDay_OneDay)
|
||||
{
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("We 16:00-20:00"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
|
||||
TEST_EQUAL(oh.GetRule().size(), 1, ());
|
||||
auto const & rule = oh.GetRule().back();
|
||||
|
||||
TestWeekday(rule, Weekday::Wednesday, Weekday::None);
|
||||
TestTime(rule, 16, 0, 20, 0);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_Hours_Usage_1)
|
||||
{
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("10:00-20:00"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2020, Month::Feb, Weekday::Thursday, 17 /* hh */, 30 /* mm */)), ());
|
||||
TEST(oh.IsClosed(GetUnixtimeByDate(2020, Month::Feb, Weekday::Monday, 07 /* hh */, 30 /* mm */)), ());
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_Weekday_Usage_1)
|
||||
{
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("We 16:00-20:00"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
|
||||
TEST(oh.IsClosed(GetUnixtimeByDate(2020, Month::Feb, Weekday::Thursday, 17 /* hh */, 30 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2020, Month::Feb, Weekday::Wednesday, 17 /* hh */, 30 /* mm */)), ());
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_Weekday_Usage_2)
|
||||
{
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("Mo-Fr 16:00-20:00, Sa-Su 09:00-14:00"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2020, Month::Feb, Weekday::Monday, 17 /* hh */, 30 /* mm */)), ());
|
||||
TEST(oh.IsClosed(GetUnixtimeByDate(2020, Month::Feb, Weekday::Thursday, 15 /* hh */, 30 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2023, Month::Apr, Weekday::Saturday, 13 /* hh */, 30 /* mm */)), ());
|
||||
TEST(oh.IsClosed(GetUnixtimeByDate(2023, Month::Apr, Weekday::Saturday, 8 /* hh */, 30 /* mm */)), ());
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_Weekday_Usage_3)
|
||||
{
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("Mo-Su 19:00-13:00"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
|
||||
TEST(oh.IsClosed(GetUnixtimeByDate(2020, Month::Feb, 6, 17 /* hh */, 30 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2020, Month::Feb, 7, 03 /* hh */, 30 /* mm */)), ());
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_Month_Usage)
|
||||
{
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("Apr - May"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2023, Month::Apr, 8, 03 /* hh */, 30 /* mm */)), ());
|
||||
TEST(oh.IsClosed(GetUnixtimeByDate(2020, Month::Feb, 5, 17 /* hh */, 30 /* mm */)), ());
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_MonthDay_Usage)
|
||||
{
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("Feb 10 - May 5"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
|
||||
TEST(oh.IsClosed(GetUnixtimeByDate(2020, Month::Feb, 5, 19 /* hh */, 00 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2020, Month::Feb, 12, 19 /* hh */, 00 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2020, Month::May, 2, 19 /* hh */, 00 /* mm */)), ());
|
||||
TEST(oh.IsClosed(GetUnixtimeByDate(2020, Month::May, 15, 19 /* hh */, 00 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2021, Month::Mar, 26, 19 /* hh */, 00 /* mm */)), ());
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_MonthDayYear_Usage)
|
||||
{
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("2019 Feb 10 - 2051 May 5"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
|
||||
TEST(oh.IsClosed(GetUnixtimeByDate(2019, Month::Feb, 5, 19 /* hh */, 00 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2019, Month::Feb, 12, 19 /* hh */, 00 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2020, Month::Feb, 5, 19 /* hh */, 00 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2019, Month::Mar, 26, 19 /* hh */, 00 /* mm */)), ());
|
||||
TEST(oh.IsClosed(GetUnixtimeByDate(2052, Month::Mar, 26, 19 /* hh */, 00 /* mm */)), ());
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_MonthHours_Usage)
|
||||
{
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("Apr-Nov 01:20-04:50"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
|
||||
TEST(oh.IsClosed(GetUnixtimeByDate(2019, Month::Feb, 5, 19 /* hh */, 00 /* mm */)), ());
|
||||
TEST(oh.IsClosed(GetUnixtimeByDate(2020, Month::May, 5, 19 /* hh */, 00 /* mm */)), ());
|
||||
TEST(oh.IsClosed(GetUnixtimeByDate(2020, Month::May, 6, 01 /* hh */, 00 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2020, Month::May, 6, 01 /* hh */, 32 /* mm */)), ());
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_InverseMonths_Usage_1)
|
||||
{
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("Mar - Nov"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2019, Month::Mar, 20, 20 /* hh */, 00 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2019, Month::May, 20, 20 /* hh */, 00 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2019, Month::Nov, 20, 20 /* hh */, 00 /* mm */)), ());
|
||||
TEST(!oh.IsOpen(GetUnixtimeByDate(2019, Month::Dec, 20, 20 /* hh */, 00 /* mm */)), ());
|
||||
TEST(!oh.IsOpen(GetUnixtimeByDate(2019, Month::Jan, 20, 20 /* hh */, 00 /* mm */)), ());
|
||||
TEST(!oh.IsOpen(GetUnixtimeByDate(2020, Month::Feb, 20, 20 /* hh */, 00 /* mm */)), ());
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(OHSerDesTestFixture, OpeningHoursSerDes_InverseMonths_Usage_2)
|
||||
{
|
||||
EnableAll();
|
||||
|
||||
TEST(Serialize("Nov - Mar"), ());
|
||||
Flush();
|
||||
|
||||
auto const oh = Deserialize();
|
||||
|
||||
TEST(!oh.IsOpen(GetUnixtimeByDate(2019, Month::Sep, 20, 20 /* hh */, 00 /* mm */)), ());
|
||||
TEST(!oh.IsOpen(GetUnixtimeByDate(2019, Month::Oct, 20, 20 /* hh */, 00 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2019, Month::Nov, 20, 20 /* hh */, 00 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2019, Month::Dec, 20, 20 /* hh */, 00 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2019, Month::Jan, 20, 20 /* hh */, 00 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2019, Month::Feb, 20, 20 /* hh */, 00 /* mm */)), ());
|
||||
TEST(oh.IsOpen(GetUnixtimeByDate(2019, Month::Mar, 20, 20 /* hh */, 00 /* mm */)), ());
|
||||
TEST(!oh.IsOpen(GetUnixtimeByDate(2020, Month::Apr, 20, 20 /* hh */, 00 /* mm */)), ());
|
||||
TEST(!oh.IsOpen(GetUnixtimeByDate(2020, Month::May, 20, 20 /* hh */, 00 /* mm */)), ());
|
||||
}
|
||||
} // namespace opening_hours_serdes_tests
|
||||
81
libs/routing/routing_tests/position_accumulator_tests.cpp
Normal file
81
libs/routing/routing_tests/position_accumulator_tests.cpp
Normal file
|
|
@ -0,0 +1,81 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/position_accumulator.hpp"
|
||||
|
||||
#include "geometry/mercator.hpp"
|
||||
#include "geometry/point2d.hpp"
|
||||
|
||||
#include "base/math.hpp"
|
||||
|
||||
namespace position_accumulator_tests
|
||||
{
|
||||
using namespace routing;
|
||||
|
||||
double constexpr kEps = 1e-10;
|
||||
double constexpr kEpsMeters = 0.1;
|
||||
|
||||
UNIT_CLASS_TEST(PositionAccumulator, Smoke)
|
||||
{
|
||||
PushNextPoint({0.0, 0.0});
|
||||
PushNextPoint({0.00005, 0.0});
|
||||
PushNextPoint({0.0001, 0.0});
|
||||
TEST_EQUAL(GetPointsForTesting().size(), 2, ());
|
||||
TEST(AlmostEqualAbs(GetDirection(), m2::PointD(0.0001, 0.0), kEps), (GetDirection()));
|
||||
TEST(AlmostEqualAbs(GetTrackLengthMForTesting(), 11.13, kEpsMeters), (GetTrackLengthMForTesting()));
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(PositionAccumulator, GoodSegment)
|
||||
{
|
||||
double constexpr kStepShortButValid = 0.00001;
|
||||
|
||||
// The distance from points with i = -15 to point with i = -6 is a little more then
|
||||
// |PositionAccumulator::kMinValidSegmentLengthM| meters. But the distance from
|
||||
// point with i = -4 to point with i = 0 is less then |PositionAccumulator::kMinValidSegmentLengthM|.
|
||||
// So the direction is calculated based on two points.
|
||||
for (signed i = -15; i <= 0; ++i)
|
||||
PushNextPoint({kStepShortButValid * i, 0.0});
|
||||
TEST_EQUAL(GetPointsForTesting().size(), 2, ());
|
||||
TEST(AlmostEqualAbs(GetDirection(), m2::PointD(9 * kStepShortButValid, 0.0), kEps), (GetDirection()));
|
||||
TEST(AlmostEqualAbs(GetTrackLengthMForTesting(), 10.02, kEpsMeters), (GetTrackLengthMForTesting()));
|
||||
|
||||
double constexpr kStepGood = 0.0001;
|
||||
for (size_t i = 0; i < 10; ++i)
|
||||
PushNextPoint({kStepGood * i, 0.0});
|
||||
|
||||
TEST_EQUAL(GetPointsForTesting().size(), 8, ());
|
||||
TEST(AlmostEqualAbs(GetDirection(), m2::PointD(0.0007, 0.0), kEps), (GetDirection()));
|
||||
TEST(AlmostEqualAbs(GetTrackLengthMForTesting(), 77.92, kEpsMeters), (GetTrackLengthMForTesting()));
|
||||
}
|
||||
|
||||
// Test on removing too outdated elements from the position accumulator.
|
||||
// Adding short but still valid segments.
|
||||
UNIT_CLASS_TEST(PositionAccumulator, RemovingOutdated)
|
||||
{
|
||||
double constexpr kStep = 0.00002;
|
||||
for (size_t i = 0; i < 100; ++i)
|
||||
PushNextPoint({kStep * i, 0.0});
|
||||
|
||||
TEST_EQUAL(GetPointsForTesting().size(), 8, ());
|
||||
TEST(AlmostEqualAbs(GetDirection(), m2::PointD(0.0007, 0.0), kEps), (GetDirection()));
|
||||
}
|
||||
|
||||
// Test on adding segments longer than |PositionAccumulator::kMaxValidSegmentLengthM|
|
||||
// and shorter than |PositionAccumulator::kMinValidSegmentLengthM|.
|
||||
UNIT_CLASS_TEST(PositionAccumulator, LongSegment)
|
||||
{
|
||||
PushNextPoint({0.0, 0.0});
|
||||
PushNextPoint({0.001, 0.0}); // Longer than |MaxValidSegmentLengthM|.
|
||||
TEST_EQUAL(GetPointsForTesting().size(), 1, ());
|
||||
PushNextPoint({0.001001, 0.0}); // Shorter than |kMinValidSegmentLengthM|, so it's ignored.
|
||||
PushNextPoint({0.00102, 0.0});
|
||||
PushNextPoint({0.00104, 0.0});
|
||||
// The distance from point {0.001, 0.0} to this one is greater then
|
||||
// |PositionAccumulator::kMinValidSegmentLengthM|, so the point is added.
|
||||
PushNextPoint({0.0012, 0.0});
|
||||
TEST_EQUAL(GetPointsForTesting().size(), 2, ());
|
||||
TEST(AlmostEqualAbs(GetDirection(), m2::PointD(0.0002, 0.0), kEps), (GetDirection()));
|
||||
PushNextPoint({0.00201, 0.0}); // Longer than |PositionAccumulator::kMaxValidSegmentLengthM|.
|
||||
TEST_EQUAL(GetPointsForTesting().size(), 1, ());
|
||||
TEST(AlmostEqualAbs(GetDirection(), m2::PointD(0.0, 0.0), kEps), (GetDirection()));
|
||||
}
|
||||
} // namespace position_accumulator_tests
|
||||
987
libs/routing/routing_tests/restriction_test.cpp
Normal file
987
libs/routing/routing_tests/restriction_test.cpp
Normal file
|
|
@ -0,0 +1,987 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "generator/generator_tests_support/routing_helpers.hpp"
|
||||
|
||||
#include "routing/routing_tests/index_graph_tools.hpp"
|
||||
#include "routing/routing_tests/world_graph_builder.hpp"
|
||||
|
||||
#include "routing/fake_ending.hpp"
|
||||
#include "routing/geometry.hpp"
|
||||
#include "routing/restriction_loader.hpp"
|
||||
|
||||
#include "geometry/point2d.hpp"
|
||||
|
||||
#include <memory>
|
||||
#include <utility>
|
||||
#include <vector>
|
||||
|
||||
namespace restriction_test
|
||||
{
|
||||
using namespace routing;
|
||||
using namespace routing_test;
|
||||
using namespace std;
|
||||
|
||||
using Algorithm = AStarAlgorithm<Segment, SegmentEdge, RouteWeight>;
|
||||
|
||||
UNIT_CLASS_TEST(RestrictionTest, CrossGraph_NoUTurn)
|
||||
{
|
||||
Init(BuildCrossGraph());
|
||||
SetStarter(MakeFakeEnding(0 /* featureId */, 0 /* segmentIdx */, m2::PointD(-1, 0), *m_graph),
|
||||
MakeFakeEnding(7, 0, m2::PointD(1, 2), *m_graph));
|
||||
|
||||
vector<m2::PointD> const expectedGeom = {{-1.0 /* x */, 0.0 /* y */}, {0.0, 0.0}, {1.0, 0.0}, {1.0, 1.0}, {1.0, 2.0}};
|
||||
TestRouteGeometry(*m_starter, Algorithm::Result::OK, expectedGeom);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RestrictionTest, CrossGraph_UTurn)
|
||||
{
|
||||
Init(BuildCrossGraph());
|
||||
SetStarter(MakeFakeEnding(0 /* featureId */, 0 /* segmentIdx */, m2::PointD(-1, 0), *m_graph),
|
||||
MakeFakeEnding(7, 0, m2::PointD(1, 2), *m_graph));
|
||||
|
||||
RestrictionVec restrictionsNo = {{1 /* feature from */, 6 /* feature to */}};
|
||||
vector<m2::PointD> const expectedGeom = {{-1.0, 0.0}, {0.0, 0.0}, {1.0, 0.0}, {1.0, -1.0},
|
||||
{1.0, 0.0}, {1.0, 1.0}, {1.0, 2.0}};
|
||||
|
||||
TestRestrictions(6.0 /* expectedTime */,
|
||||
MakeFakeEnding(0 /* featureId */, 0 /* segmentIdx */, m2::PointD(-1, 0), *m_graph),
|
||||
MakeFakeEnding(7, 0, m2::PointD(1, 2), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
// Finish
|
||||
// 3 *
|
||||
// ^
|
||||
// |
|
||||
// F4
|
||||
// |
|
||||
// 2 *
|
||||
// ^ ↖
|
||||
// | F1
|
||||
// | ↖
|
||||
// 1 | *
|
||||
// F0 ↖
|
||||
// | F2
|
||||
// | ↖
|
||||
// 0 *<--F3---<--F3---*<--F5--* Start
|
||||
// 0 1 2 3
|
||||
// Note. F0, F1 and F2 are one segment features. F3 is a two segments feature.
|
||||
unique_ptr<SingleVehicleWorldGraph> BuildTriangularGraph()
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
loader->AddRoad(0 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 0.0}, {0.0, 2.0}}));
|
||||
loader->AddRoad(1 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 1.0}, {0.0, 2.0}}));
|
||||
loader->AddRoad(2 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 0.0}, {1.0, 1.0}}));
|
||||
loader->AddRoad(3 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 0.0}, {1.0, 0.0}, {0.0, 0.0}}));
|
||||
loader->AddRoad(4 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 2.0}, {0.0, 3.0}}));
|
||||
loader->AddRoad(5 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{3.0, 0.0}, {2.0, 0.0}}));
|
||||
|
||||
vector<Joint> const joints = {
|
||||
MakeJoint({{2, 0}, {3, 0}, {5, 1}}), /* joint at point (2, 0) */
|
||||
MakeJoint({{3, 2}, {0, 0}}), /* joint at point (0, 0) */
|
||||
MakeJoint({{2, 1}, {1, 0}}), /* joint at point (1, 1) */
|
||||
MakeJoint({{0, 1}, {1, 1}, {4, 0}}), /* joint at point (0, 2) */
|
||||
MakeJoint({{5, 0}}), /* joint at point (3, 0) */
|
||||
MakeJoint({{4, 1}}) /* joint at point (0, 3) */
|
||||
};
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
return BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
}
|
||||
|
||||
// Route through triangular graph without any restrictions.
|
||||
UNIT_CLASS_TEST(RestrictionTest, TriangularGraph)
|
||||
{
|
||||
Init(BuildTriangularGraph());
|
||||
|
||||
vector<m2::PointD> const expectedGeom = {{3 /* x */, 0 /* y */}, {2, 0}, {1, 1}, {0, 2}, {0, 3}};
|
||||
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(5 /* featureId */, 0 /* segmentIdx */, m2::PointD(3, 0), *m_graph),
|
||||
MakeFakeEnding(4, 0, m2::PointD(0, 3), *m_graph), {}, *this);
|
||||
}
|
||||
|
||||
// Route through triangular graph with restriction type no from feature 2 to feature 1.
|
||||
UNIT_CLASS_TEST(RestrictionTest, TriangularGraph_RestrictionNoF2F1)
|
||||
{
|
||||
Init(BuildTriangularGraph());
|
||||
RestrictionVec restrictionsNo = {{2 /* feature from */, 1 /* feature to */}};
|
||||
vector<m2::PointD> const expectedGeom = {{3 /* x */, 0 /* y */}, {2, 0}, {1, 0}, {0, 0}, {0, 2}, {0, 3}};
|
||||
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(5 /* featureId */, 0 /* senmentIdx */, m2::PointD(3, 0), *m_graph),
|
||||
MakeFakeEnding(4, 0, m2::PointD(0, 3), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RestrictionTest, TriangularGraph_RestrictionNoF5F2)
|
||||
{
|
||||
Init(BuildTriangularGraph());
|
||||
RestrictionVec restrictionsNo = {{5 /* feature from */, 2 /* feature to */}};
|
||||
vector<m2::PointD> const expectedGeom = {{3 /* x */, 0 /* y */}, {2, 0}, {1, 0}, {0, 0}, {0, 2}, {0, 3}};
|
||||
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(5 /* featureId */, 0 /* segmentIdx */, m2::PointD(3, 0), *m_graph),
|
||||
MakeFakeEnding(4, 0, m2::PointD(0, 3), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RestrictionTest, TriangularGraph_RestrictionOnlyF5F3)
|
||||
{
|
||||
Init(BuildTriangularGraph());
|
||||
RestrictionVec restrictionsOnly = {{{5 /* feature from */, 3 /* feature to */}}};
|
||||
RestrictionVec restrictionsNo;
|
||||
ConvertRestrictionsOnlyToNo(m_graph->GetIndexGraphForTests(kTestNumMwmId), restrictionsOnly, restrictionsNo);
|
||||
vector<m2::PointD> const expectedGeom = {{3 /* x */, 0 /* y */}, {2, 0}, {1, 0}, {0, 0}, {0, 2}, {0, 3}};
|
||||
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(5 /* featureId */, 0 /* segmentIdx */, m2::PointD(3, 0), *m_graph),
|
||||
MakeFakeEnding(4, 0, m2::PointD(0, 3), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RestrictionTest, TriangularGraph_RestrictionNoF5F2RestrictionOnlyF5F3)
|
||||
{
|
||||
Init(BuildTriangularGraph());
|
||||
RestrictionVec restrictionsNo = {{5 /* feature from */, 2 /* feature to */}};
|
||||
|
||||
RestrictionVec restrictionsOnly = {{5 /* feature from */, 3 /* feature to */}};
|
||||
ConvertRestrictionsOnlyToNo(m_graph->GetIndexGraphForTests(kTestNumMwmId), restrictionsOnly, restrictionsNo);
|
||||
|
||||
vector<m2::PointD> const expectedGeom = {{3 /* x */, 0 /* y */}, {2, 0}, {1, 0}, {0, 0}, {0, 2}, {0, 3}};
|
||||
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(5 /* featureId */, 0 /* segmentIdx */, m2::PointD(3, 0), *m_graph),
|
||||
MakeFakeEnding(4, 0, m2::PointD(0, 3), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
// Finish
|
||||
// 3 *
|
||||
// |
|
||||
// F4
|
||||
// |
|
||||
// 2 *
|
||||
// | ╲
|
||||
// F0 F2
|
||||
// | ╲
|
||||
// 1 * *
|
||||
// | ╲
|
||||
// F0 F2
|
||||
// | ╲
|
||||
// 0 *---F1--*--F1--*--F3---* Start
|
||||
// 0 1 2 3
|
||||
// Note. All features are two setments and two-way.
|
||||
unique_ptr<SingleVehicleWorldGraph> BuildTwowayCornerGraph()
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
loader->AddRoad(0 /* feature id */, false /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 0.0}, {0.0, 1.0}, {0.0, 2.0}}));
|
||||
loader->AddRoad(1 /* feature id */, false /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 0.0}, {1.0, 0.0}, {0.0, 0.0}}));
|
||||
loader->AddRoad(2 /* feature id */, false /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 0.0}, {1.0, 1.0}, {0.0, 2.0}}));
|
||||
loader->AddRoad(3 /* feature id */, false /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{3.0, 0.0}, {2.0, 0.0}}));
|
||||
loader->AddRoad(4 /* feature id */, false /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 2.0}, {0.0, 3.0}}));
|
||||
|
||||
vector<Joint> const joints = {
|
||||
MakeJoint({{1 /* feature id */, 2 /* point id */}, {0, 0}})
|
||||
/* joint at point (0, 0) */,
|
||||
MakeJoint({{1, 0}, {2, 0}, {3, 1}}), /* joint at point (2, 0) */
|
||||
MakeJoint({{2, 2}, {0, 2}, {4, 0}}), /* joint at point (0, 2) */
|
||||
MakeJoint({{4, 1}}), /* joint at point (0, 3) */
|
||||
MakeJoint({{3, 0}}), /* joint at point (3, 0) */
|
||||
};
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
return BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RestrictionTest, TwowayCornerGraph)
|
||||
{
|
||||
Init(BuildTwowayCornerGraph());
|
||||
vector<m2::PointD> const expectedGeom = {{3 /* x */, 0 /* y */}, {2, 0}, {1, 1}, {0, 2}, {0, 3}};
|
||||
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(3 /* featureId */, 0 /* segmentIdx */, m2::PointD(3, 0), *m_graph),
|
||||
MakeFakeEnding(4, 0, m2::PointD(0, 3), *m_graph), {}, *this);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RestrictionTest, TwowayCornerGraph_RestrictionF3F2No)
|
||||
{
|
||||
Init(BuildTwowayCornerGraph());
|
||||
RestrictionVec restrictionsNo = {{3 /* feature from */, 2 /* feature to */}};
|
||||
vector<m2::PointD> const expectedGeom = {{3 /* x */, 0 /* y */}, {2, 0}, {1, 0}, {0, 0}, {0, 1}, {0, 2}, {0, 3}};
|
||||
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(3 /* featureId */, 0 /* segmentIdx */, m2::PointD(3, 0), *m_graph),
|
||||
MakeFakeEnding(4, 0, m2::PointD(0, 3), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RestrictionTest, TwowayCornerGraph_RestrictionF3F1Only)
|
||||
{
|
||||
Init(BuildTwowayCornerGraph());
|
||||
RestrictionVec restrictionsOnly = {{3 /* feature from */, 1 /* feature to */}};
|
||||
RestrictionVec restrictionsNo;
|
||||
ConvertRestrictionsOnlyToNo(m_graph->GetIndexGraphForTests(kTestNumMwmId), restrictionsOnly, restrictionsNo);
|
||||
vector<m2::PointD> const expectedGeom = {{3 /* x */, 0 /* y */}, {2, 0}, {1, 0}, {0, 0}, {0, 1}, {0, 2}, {0, 3}};
|
||||
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(3 /* featureId */, 0 /* segmentIdx */, m2::PointD(3, 0), *m_graph),
|
||||
MakeFakeEnding(4, 0, m2::PointD(0, 3), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
// Finish
|
||||
// 3 *
|
||||
// ^
|
||||
// |
|
||||
// F11
|
||||
// |
|
||||
// 2 *<---F5----*<---F6---*
|
||||
// ^ ↖ ^ ↖ ^
|
||||
// | F7 | F8 |
|
||||
// | ↖ F1 ↖ F2
|
||||
// | ↖ | ↖ |
|
||||
// 1 F0 * *
|
||||
// | ^ ↖ ^
|
||||
// | F1 F9 F2
|
||||
// | | ↖ |
|
||||
// 0 *<----F4---*<---F3----*<--F10---* Start
|
||||
// 0 1 2 3
|
||||
// Note. F1 and F2 are two segments features. The others are one segment ones.
|
||||
unique_ptr<SingleVehicleWorldGraph> BuildTwoSquaresGraph()
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
loader->AddRoad(0 /* feature id */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 0.0}, {0.0, 2.0}}));
|
||||
loader->AddRoad(1 /* feature id */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 0.0}, {1.0, 1.0}, {1.0, 2.0}}));
|
||||
loader->AddRoad(2 /* feature id */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 0.0}, {2.0, 1.0}, {2.0, 2.0}}));
|
||||
loader->AddRoad(3 /* feature id */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 0.0}, {1.0, 0.0}}));
|
||||
loader->AddRoad(4 /* feature id */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 0.0}, {0.0, 0.0}}));
|
||||
loader->AddRoad(5 /* feature id */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 2.0}, {0.0, 2.0}}));
|
||||
loader->AddRoad(6 /* feature id */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 2.0}, {1.0, 2.0}}));
|
||||
loader->AddRoad(7 /* feature id */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 1.0}, {0.0, 2.0}}));
|
||||
loader->AddRoad(8 /* feature id */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 1.0}, {1.0, 2.0}}));
|
||||
loader->AddRoad(9 /* feature id */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 0.0}, {1.0, 1.0}}));
|
||||
loader->AddRoad(10 /* feature id */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{3.0, 0.0}, {2.0, 0.0}}));
|
||||
loader->AddRoad(11 /* feature id */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 2.0}, {0.0, 3.0}}));
|
||||
|
||||
vector<Joint> const joints = {
|
||||
MakeJoint({{4 /* featureId */, 1 /* pointId */}, {0, 0}}), /* joint at point (0, 0) */
|
||||
MakeJoint({{0, 1}, {5, 1}, {7, 1}, {11, 0}}), /* joint at point (0, 2) */
|
||||
MakeJoint({{4, 0}, {1, 0}, {3, 1}}), /* joint at point (1, 0) */
|
||||
MakeJoint({{5, 0}, {1, 2}, {6, 1}, {8, 1}}), /* joint at point (1, 2) */
|
||||
MakeJoint({{3, 0}, {2, 0}, {9, 0}, {10, 1}}), /* joint at point (2, 0) */
|
||||
MakeJoint({{2, 2}, {6, 0}}), /* joint at point (2, 2) */
|
||||
MakeJoint({{1, 1}, {9, 1}, {7, 0}}), /* joint at point (1, 1) */
|
||||
MakeJoint({{2, 1}, {8, 0}}), /* joint at point (2, 1) */
|
||||
MakeJoint({{10, 0}}), /* joint at point (3, 0) */
|
||||
MakeJoint({{11, 1}}), /* joint at point (0, 3) */
|
||||
};
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
return BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RestrictionTest, TwoSquaresGraph)
|
||||
{
|
||||
Init(BuildTwoSquaresGraph());
|
||||
vector<m2::PointD> const expectedGeom = {{3 /* x */, 0 /* y */}, {2, 0}, {1, 1}, {0, 2}, {0, 3}};
|
||||
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(10 /* featureId */, 0 /* segmentIdx */, m2::PointD(3, 0), *m_graph),
|
||||
MakeFakeEnding(11, 0, m2::PointD(0, 3), *m_graph), {}, *this);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RestrictionTest, TwoSquaresGraph_RestrictionF10F3Only)
|
||||
{
|
||||
Init(BuildTwoSquaresGraph());
|
||||
RestrictionVec restrictionsOnly = {{10 /* feature from */, 3 /* feature to */}};
|
||||
RestrictionVec restrictionsNo;
|
||||
ConvertRestrictionsOnlyToNo(m_graph->GetIndexGraphForTests(kTestNumMwmId), restrictionsOnly, restrictionsNo);
|
||||
|
||||
vector<m2::PointD> const expectedGeom = {{3 /* x */, 0 /* y */}, {2, 0}, {1, 0}, {1, 1}, {0, 2}, {0, 3}};
|
||||
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(10 /* featureId */, 0 /* segmentIdx */, m2::PointD(3, 0), *m_graph),
|
||||
MakeFakeEnding(11, 0, m2::PointD(0, 3), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RestrictionTest, TwoSquaresGraph_RestrictionF10F3OnlyF3F4Only)
|
||||
{
|
||||
Init(BuildTwoSquaresGraph());
|
||||
RestrictionVec restrictionsOnly = {{3 /* feature from */, 4 /* feature to */},
|
||||
{10 /* feature from */, 3 /* feature to */}};
|
||||
RestrictionVec restrictionsNo;
|
||||
ConvertRestrictionsOnlyToNo(m_graph->GetIndexGraphForTests(kTestNumMwmId), restrictionsOnly, restrictionsNo);
|
||||
|
||||
vector<m2::PointD> const expectedGeom = {{3 /* x */, 0 /* y */}, {2, 0}, {1, 0}, {0, 0}, {0, 2}, {0, 3}};
|
||||
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(10 /* featureId */, 0 /* segmentIdx */, m2::PointD(3, 0), *m_graph),
|
||||
MakeFakeEnding(11, 0, m2::PointD(0, 3), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RestrictionTest, TwoSquaresGraph_RestrictionF2F8NoRestrictionF9F1Only)
|
||||
{
|
||||
Init(BuildTwoSquaresGraph());
|
||||
RestrictionVec restrictionsNo = {{2 /* feature from */, 8 /* feature to */}}; // Invalid restriction.
|
||||
RestrictionVec restrictionsOnly = {{9 /* feature from */, 1 /* feature to */}}; // Invalid restriction.
|
||||
ConvertRestrictionsOnlyToNo(m_graph->GetIndexGraphForTests(kTestNumMwmId), restrictionsOnly, restrictionsNo);
|
||||
|
||||
vector<m2::PointD> const expectedGeom = {{3 /* x */, 0 /* y */}, {2, 0}, {1, 1}, {0, 2}, {0, 3}};
|
||||
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(10 /* featureId */, 0 /* segmentIdx */, m2::PointD(3, 0), *m_graph),
|
||||
MakeFakeEnding(11, 0, m2::PointD(0, 3), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
// 2 *
|
||||
// |
|
||||
// F6
|
||||
// |Finish
|
||||
// 1 *-F4-*-F5-*
|
||||
// | |
|
||||
// F2 F3
|
||||
// | |
|
||||
// 0 *---F1----*---F0---* Start
|
||||
// 0 1 2
|
||||
// Note 1. All features are two-way. (It's possible to std::move along any direction of the features.)
|
||||
// Note 2. Any feature contains of one segment.
|
||||
unique_ptr<SingleVehicleWorldGraph> BuildFlagGraph()
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
loader->AddRoad(0 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 0.0}, {1.0, 0.0}}));
|
||||
loader->AddRoad(1 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 0.0}, {0.0, 0.0}}));
|
||||
loader->AddRoad(2 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 0.0}, {0.0, 1.0}}));
|
||||
loader->AddRoad(3 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 0.0}, {1.0, 1.0}}));
|
||||
loader->AddRoad(4 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 1.0}, {0.5, 1.0}}));
|
||||
loader->AddRoad(5 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.5, 1.0}, {1.0, 1.0}}));
|
||||
loader->AddRoad(6 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.5, 1.0}, {0.5, 2.0}}));
|
||||
|
||||
vector<Joint> const joints = {
|
||||
MakeJoint({{1 /* feature id */, 1 /* point id */}, {2, 0}}), /* joint at point (0, 0) */
|
||||
MakeJoint({{2, 1}, {4, 0}}), /* joint at point (0, 1) */
|
||||
MakeJoint({{4, 1}, {5, 0}, {6, 0}}), /* joint at point (0.5, 1) */
|
||||
MakeJoint({{1, 0}, {3, 0}, {0, 1}}), /* joint at point (1, 0) */
|
||||
MakeJoint({{3, 1}, {5, 1}}), /* joint at point (1, 1) */
|
||||
MakeJoint({{6, 1}}), /* joint at point (0.5, 2) */
|
||||
MakeJoint({{0, 0}}), /* joint at point (2, 0) */
|
||||
};
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
return BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
}
|
||||
|
||||
// Route through flag graph without any restrictions.
|
||||
UNIT_TEST(FlagGraph)
|
||||
{
|
||||
unique_ptr<WorldGraph> graph = BuildFlagGraph();
|
||||
auto starter = MakeStarter(MakeFakeEnding(0 /* featureId */, 0 /* segmentIdx */, m2::PointD(2, 0), *graph),
|
||||
MakeFakeEnding(6, 0, m2::PointD(0.5, 1), *graph), *graph);
|
||||
vector<m2::PointD> const expectedGeom = {{2 /* x */, 0 /* y */}, {1, 0}, {1, 1}, {0.5, 1}};
|
||||
TestRouteGeometry(*starter, Algorithm::Result::OK, expectedGeom);
|
||||
}
|
||||
|
||||
// Route through flag graph with one restriciton (type no) from F0 to F3.
|
||||
UNIT_CLASS_TEST(RestrictionTest, FlagGraph_RestrictionF0F3No)
|
||||
{
|
||||
Init(BuildFlagGraph());
|
||||
RestrictionVec restrictionsNo = {{0 /* feature from */, 3 /* feature to */}};
|
||||
vector<m2::PointD> const expectedGeom = {{2 /* x */, 0 /* y */}, {1, 0}, {0, 0}, {0, 1}, {0.5, 1}};
|
||||
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(0 /* featureId */, 0 /* segmentIdx */, m2::PointD(2, 0), *m_graph),
|
||||
MakeFakeEnding(6, 0, m2::PointD(0.5, 1), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
// Route through flag graph with one restriciton (type only) from F0 to F1.
|
||||
UNIT_CLASS_TEST(RestrictionTest, FlagGraph_RestrictionF0F1Only)
|
||||
{
|
||||
Init(BuildFlagGraph());
|
||||
RestrictionVec restrictionsNo = {{0 /* feature from */, 1 /* feature to */}};
|
||||
vector<m2::PointD> const expectedGeom = {{2 /* x */, 0 /* y */}, {1, 0}, {1, 1}, {0.5, 1}};
|
||||
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(0 /* featureId */, 0 /* segmentIdx */, m2::PointD(2, 0), *m_graph),
|
||||
MakeFakeEnding(6, 0, m2::PointD(0.5, 1), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RestrictionTest, FlagGraph_PermutationsF1F3NoF7F8OnlyF8F4OnlyF4F6Only)
|
||||
{
|
||||
Init(BuildFlagGraph());
|
||||
RestrictionVec restrictionsNo = {{0 /* feature from */, 3 /* feature to */}};
|
||||
|
||||
RestrictionVec restrictionsOnly = {{0 /* feature from */, 1 /* feature to */},
|
||||
{1 /* feature from */, 2 /* feature to */}};
|
||||
|
||||
ConvertRestrictionsOnlyToNo(m_graph->GetIndexGraphForTests(kTestNumMwmId), restrictionsOnly, restrictionsNo);
|
||||
|
||||
vector<m2::PointD> const expectedGeom = {{2 /* x */, 0 /* y */}, {1, 0}, {0, 0}, {0, 1}, {0.5, 1}};
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(0 /* featureId */, 0 /* segmentIdx */, m2::PointD(2, 0), *m_graph),
|
||||
MakeFakeEnding(6, 0, m2::PointD(0.5, 1), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
// 1 *-F4-*-F5-*---F6---* Finish
|
||||
// | |
|
||||
// F2 F3
|
||||
// | |
|
||||
// 0 *---F1----*---F0---* Start
|
||||
// 0 1 2
|
||||
// Note 1. All features except for F7 are two-way.
|
||||
// Note 2. Any feature contains of one segment.
|
||||
unique_ptr<SingleVehicleWorldGraph> BuildPosterGraph()
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
loader->AddRoad(0 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 0.0}, {1.0, 0.0}}));
|
||||
loader->AddRoad(1 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 0.0}, {0.0, 0.0}}));
|
||||
loader->AddRoad(2 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 0.0}, {0.0, 1.0}}));
|
||||
loader->AddRoad(3 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 0.0}, {1.0, 1.0}}));
|
||||
loader->AddRoad(4 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 1.0}, {0.5, 1.0}}));
|
||||
loader->AddRoad(5 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.5, 1.0}, {1.0, 1.0}}));
|
||||
loader->AddRoad(6 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 1.0}, {2.0, 1.0}}));
|
||||
|
||||
vector<Joint> const joints = {
|
||||
MakeJoint({{1 /* feature id */, 1 /* point id */}, {2, 0}}), /* joint at point (0, 0) */
|
||||
MakeJoint({{2, 1}, {4, 0}}), /* joint at point (0, 1) */
|
||||
MakeJoint({{4, 1}, {5, 0}}), /* joint at point (0.5, 1) */
|
||||
MakeJoint({{1, 0}, {3, 0}, {0, 1}}), /* joint at point (1, 0) */
|
||||
MakeJoint({{3, 1}, {5, 1}, {6, 0}}), /* joint at point (1, 1) */
|
||||
MakeJoint({{0, 0}}), /* joint at point (2, 0) */
|
||||
MakeJoint({{6, 1}}), /* joint at point (2, 1) */
|
||||
};
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
return BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
}
|
||||
|
||||
// Route through poster graph without any restrictions.
|
||||
UNIT_TEST(PosterGraph)
|
||||
{
|
||||
unique_ptr<WorldGraph> graph = BuildPosterGraph();
|
||||
auto starter = MakeStarter(MakeFakeEnding(0 /* featureId */, 0 /* segmentIdx */, m2::PointD(2, 0), *graph),
|
||||
MakeFakeEnding(6, 0, m2::PointD(2, 1), *graph), *graph);
|
||||
vector<m2::PointD> const expectedGeom = {{2 /* x */, 0 /* y */}, {1, 0}, {1, 1}, {2, 1}};
|
||||
|
||||
TestRouteGeometry(*starter, Algorithm::Result::OK, expectedGeom);
|
||||
}
|
||||
|
||||
// Route through poster graph with restrictions F0-F3 (type no).
|
||||
UNIT_CLASS_TEST(RestrictionTest, PosterGraph_RestrictionF0F3No)
|
||||
{
|
||||
Init(BuildPosterGraph());
|
||||
RestrictionVec restrictionsNo = {{0 /* feature from */, 3 /* feature to */}};
|
||||
vector<m2::PointD> const expectedGeom = {{2 /* x */, 0 /* y */}, {1, 0}, {0, 0}, {0, 1}, {0.5, 1}, {1, 1}, {2, 1}};
|
||||
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(0 /* featureId */, 0 /* segmentIdx */, m2::PointD(2, 0), *m_graph),
|
||||
MakeFakeEnding(6, 0, m2::PointD(2, 1), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
// Route through poster graph with restrictions F0-F1 (type only).
|
||||
UNIT_CLASS_TEST(RestrictionTest, PosterGraph_RestrictionF0F1Only)
|
||||
{
|
||||
Init(BuildPosterGraph());
|
||||
|
||||
RestrictionVec restrictionsOnly = {{0 /* feature from */, 1 /* feature to */}};
|
||||
RestrictionVec restrictionsNo;
|
||||
ConvertRestrictionsOnlyToNo(m_graph->GetIndexGraphForTests(kTestNumMwmId), restrictionsOnly, restrictionsNo);
|
||||
|
||||
vector<m2::PointD> const expectedGeom = {{2 /* x */, 0 /* y */}, {1, 0}, {0, 0}, {0, 1}, {0.5, 1}, {1, 1}, {2, 1}};
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(0 /* featureId */, 0 /* segmentIdx */, m2::PointD(2, 0), *m_graph),
|
||||
MakeFakeEnding(6, 0, m2::PointD(2, 1), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
// 1 *--F1-->*
|
||||
// ↗ ↘
|
||||
// F1 F1
|
||||
// ↗ ↘
|
||||
// 0 Start *---F3--->*---F0--->-------F0----->*---F2-->* Finish
|
||||
// -1 0 1 2 3 4
|
||||
// Note. F0 is a two segments feature. F1 is a three segment one. F2 and F3 are one segment
|
||||
// features.
|
||||
unique_ptr<WorldGraph> BuildTwoWayGraph()
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
loader->AddRoad(0 /* feature id */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 0.0}, {1.0, 0.0}, {3.0, 0}}));
|
||||
loader->AddRoad(1 /* feature id */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 0.0}, {1.0, 1.0}, {2.0, 1.0}, {3.0, 0.0}}));
|
||||
loader->AddRoad(2 /* feature id */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{3.0, 0.0}, {4.0, 0.0}}));
|
||||
loader->AddRoad(3 /* feature id */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{-1.0, 0.0}, {0.0, 0.0}}));
|
||||
|
||||
vector<Joint> const joints = {
|
||||
MakeJoint({{0 /* feature id */, 0 /* point id */}, {1, 0}, {3, 1}}), /* joint at point (0, 0) */
|
||||
MakeJoint({{0 /* feature id */, 2 /* point id */}, {1, 3}, {2, 0}}), /* joint at point (3, 0) */
|
||||
MakeJoint({{3 /* feature id */, 0 /* point id */}}), /* joint at point (-1, 0) */
|
||||
MakeJoint({{2 /* feature id */, 1 /* point id */}}), /* joint at point (4, 0) */
|
||||
};
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
return BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
}
|
||||
|
||||
UNIT_TEST(TwoWayGraph)
|
||||
{
|
||||
unique_ptr<WorldGraph> graph = BuildTwoWayGraph();
|
||||
auto starter = MakeStarter(MakeFakeEnding(3 /* featureId */, 0 /* segmentIdx */, m2::PointD(-1, 0), *graph),
|
||||
MakeFakeEnding(2, 0, m2::PointD(4, 0), *graph), *graph);
|
||||
vector<m2::PointD> const expectedGeom = {{-1 /* x */, 0 /* y */}, {0, 0}, {1, 0}, {3, 0}, {4, 0}};
|
||||
|
||||
TestRouteGeometry(*starter, Algorithm::Result::OK, expectedGeom);
|
||||
}
|
||||
|
||||
// 1 *---F4----*
|
||||
// | |
|
||||
// F2 F3
|
||||
// | |
|
||||
// 0 *<--F5---*<--F1----*<--F0---* Start
|
||||
// Finish
|
||||
// 0 1 2 3
|
||||
// Note 1. F0, F1 and F5 are one-way features. F3, F2 and F4 are two-way features.
|
||||
// Note 2. Any feature contains of one segment.
|
||||
unique_ptr<SingleVehicleWorldGraph> BuildSquaresGraph()
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
loader->AddRoad(0 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{3.0, 0.0}, {2.0, 0.0}}));
|
||||
loader->AddRoad(1 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 0.0}, {1.0, 0.0}}));
|
||||
loader->AddRoad(2 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 0.0}, {1.0, 1.0}}));
|
||||
loader->AddRoad(3 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 0.0}, {2.0, 1.0}}));
|
||||
loader->AddRoad(4 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 1.0}, {1.0, 1.0}}));
|
||||
loader->AddRoad(5 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 0.0}, {0.0, 0.0}}));
|
||||
|
||||
vector<Joint> const joints = {
|
||||
MakeJoint({{0 /* feature id */, 0 /* point id */}}), /* joint at point (3, 0) */
|
||||
MakeJoint({{0, 1}, {3, 0}, {1, 0}}), /* joint at point (2, 0) */
|
||||
MakeJoint({{3, 1}, {4, 0}}), /* joint at point (2, 1) */
|
||||
MakeJoint({{2, 1}, {4, 1}}), /* joint at point (1, 1) */
|
||||
MakeJoint({{1, 1}, {2, 0}, {5, 0}}), /* joint at point (1, 0) */
|
||||
MakeJoint({{5, 1}}) /* joint at point (0, 0) */
|
||||
};
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
return BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
}
|
||||
|
||||
UNIT_TEST(SquaresGraph)
|
||||
{
|
||||
unique_ptr<WorldGraph> graph = BuildSquaresGraph();
|
||||
auto starter = MakeStarter(MakeFakeEnding(0 /* featureId */, 0 /* segmentIdx */, m2::PointD(3, 0), *graph),
|
||||
MakeFakeEnding(5, 0, m2::PointD(0, 0), *graph), *graph);
|
||||
vector<m2::PointD> const expectedGeom = {{3 /* x */, 0 /* y */}, {2, 0}, {1, 0}, {0, 0}};
|
||||
TestRouteGeometry(*starter, Algorithm::Result::OK, expectedGeom);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RestrictionTest, SquaresGraph_RestrictionF0F1OnlyF1F5Only)
|
||||
{
|
||||
Init(BuildSquaresGraph());
|
||||
RestrictionVec restrictionsNo;
|
||||
RestrictionVec restrictionsOnly = {{0 /* feature from */, 3 /* feature to */}};
|
||||
|
||||
ConvertRestrictionsOnlyToNo(m_graph->GetIndexGraphForTests(kTestNumMwmId), restrictionsOnly, restrictionsNo);
|
||||
|
||||
vector<m2::PointD> const expectedGeom = {{3.0, 0.0}, {2.0, 0.0}, {2.0, 1.0}, {1.0, 1.0}, {1.0, 0.0}, {0.0, 0.0}};
|
||||
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(0 /* featureId */, 0 /* segmentIdx */, m2::PointD(3, 0), *m_graph),
|
||||
MakeFakeEnding(5, 0, m2::PointD(0, 0), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
// 0 Start *--F0--->*<--F1---*---F1---*---F1--->*---F2-->* Finish
|
||||
// 0 1 2 3 4 5
|
||||
// Note. F0 and F2 are one segment one-way features. F1 is a 3 segment two-way feature.
|
||||
unique_ptr<SingleVehicleWorldGraph> BuildLineGraph()
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
loader->AddRoad(0 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 0.0}, {0.0, 1.0}}));
|
||||
loader->AddRoad(1 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 0.0}, {2.0, 0.0}, {3.0, 0.0}, {4.0, 0.0}}));
|
||||
loader->AddRoad(2 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{4.0, 0.0}, {5.0, 0.0}}));
|
||||
|
||||
vector<Joint> const joints = {
|
||||
MakeJoint({{0 /* feature id */, 0 /* point id */}}), /* joint at point (0, 0) */
|
||||
MakeJoint({{0, 1}, {1, 0}}), /* joint at point (1, 0) */
|
||||
MakeJoint({{1, 3}, {2, 0}}), /* joint at point (4, 0) */
|
||||
MakeJoint({{2, 1}}), /* joint at point (5, 0) */
|
||||
};
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
return BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
}
|
||||
|
||||
// This test checks that despite the fact uturn on F1 is prohibited (moving from F1 to F1 is
|
||||
// prohibited)
|
||||
// it's still possible to std::move from F1 to F1 in straight direction.
|
||||
UNIT_CLASS_TEST(RestrictionTest, LineGraph_RestrictionF1F1No)
|
||||
{
|
||||
Init(BuildLineGraph());
|
||||
RestrictionVec restrictionsNo = {{1 /* feature from */, 1 /* feature to */}};
|
||||
vector<m2::PointD> const expectedGeom = {{0 /* x */, 0 /* y */}, {1, 0}, {2, 0}, {3, 0}, {4, 0}, {5, 0}};
|
||||
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(0 /* featureId */, 0 /* segmentIdx */, m2::PointD(0, 0), *m_graph),
|
||||
MakeFakeEnding(2, 0, m2::PointD(5, 0), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
// 2 *---F2-->*
|
||||
// ^
|
||||
// F0
|
||||
// |
|
||||
// 1 *---F1-->* Finish
|
||||
// ^
|
||||
// F0
|
||||
// |
|
||||
// 0 *
|
||||
// 0 1
|
||||
// Start
|
||||
unique_ptr<SingleVehicleWorldGraph> BuildFGraph()
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
loader->AddRoad(0 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 0.0}, {0.0, 1.0}, {0.0, 2.0}}));
|
||||
loader->AddRoad(1 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 1.0}, {1.0, 1.0}}));
|
||||
loader->AddRoad(2 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 2.0}, {1.0, 2.0}}));
|
||||
|
||||
vector<Joint> const joints = {
|
||||
MakeJoint({{0 /* feature id */, 0 /* point id */}}), /* joint at point (0, 0) */
|
||||
MakeJoint({{0, 1}, {1, 0}}), /* joint at point (0, 1) */
|
||||
MakeJoint({{0, 2}, {2, 0}}), /* joint at point (0, 2) */
|
||||
MakeJoint({{1, 1}}), /* joint at point (1, 1) */
|
||||
MakeJoint({{2, 1}}), /* joint at point (1, 2) */
|
||||
};
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
return BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
}
|
||||
|
||||
// This test checks that having a Only restriction from F0 to F2 it's still possible std::move
|
||||
// from F0 to F1.
|
||||
UNIT_CLASS_TEST(RestrictionTest, FGraph_RestrictionF0F2Only)
|
||||
{
|
||||
Init(BuildFGraph());
|
||||
RestrictionVec restrictionsNo;
|
||||
RestrictionVec restrictionsOnly = {{0 /* feature from */, 2 /* feature to */}};
|
||||
ConvertRestrictionsOnlyToNo(m_graph->GetIndexGraphForTests(kTestNumMwmId), restrictionsOnly, restrictionsNo);
|
||||
|
||||
vector<m2::PointD> const expectedGeom = {{0 /* x */, 0 /* y */}, {0, 1}, {1, 1}};
|
||||
|
||||
TestRestrictions(expectedGeom, Algorithm::Result::OK,
|
||||
MakeFakeEnding(0 /* featureId */, 0 /* segmentIdx */, m2::PointD(0, 0), *m_graph),
|
||||
MakeFakeEnding(1, 0, m2::PointD(1, 1), *m_graph), std::move(restrictionsNo), *this);
|
||||
}
|
||||
|
||||
/// @todo By VNG: no-pass-through behaviour was changed.
|
||||
/// @see IndexGraphStarter::CheckLength
|
||||
// *---F4---*
|
||||
// | |
|
||||
// F3 F5
|
||||
// | |
|
||||
// 0 Start *---F0---*---F1---*---F2---* Finish
|
||||
// 0 1 2 3
|
||||
unique_ptr<SingleVehicleWorldGraph> BuildNonPassThroughGraph(bool passThroughStart, bool passThroughShortWay,
|
||||
bool passThroughLongWay)
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
loader->AddRoad(0 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 0.0}, {1.0, 0.0}}));
|
||||
loader->SetPassThroughAllowed(0 /* feature id */, passThroughStart);
|
||||
loader->AddRoad(1 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 0.0}, {2.0, 0.0}}));
|
||||
loader->SetPassThroughAllowed(1 /* feature id */, passThroughShortWay);
|
||||
loader->AddRoad(2 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 0.0}, {3.0, 0.0}}));
|
||||
loader->AddRoad(3 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 0.0}, {1.0, 1.0}}));
|
||||
loader->AddRoad(4 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 1.0}, {2.0, 1.0}}));
|
||||
loader->SetPassThroughAllowed(4 /* feature id */, passThroughLongWay);
|
||||
loader->AddRoad(5 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 1.0}, {2.0, 0.0}}));
|
||||
|
||||
vector<Joint> const joints = {
|
||||
MakeJoint({{0 /* feature id */, 0 /* point id */}}), /* joint at point (0, 0) */
|
||||
MakeJoint({{0, 1}, {1, 0}, {3, 0}}), /* joint at point (1, 0) */
|
||||
MakeJoint({{1, 1}, {2, 0}, {5, 1}}), /* joint at point (2, 0) */
|
||||
MakeJoint({{3, 1}, {4, 0}}), /* joint at point (1, 1) */
|
||||
MakeJoint({{4, 1}, {5, 0}}), /* joint at point (2, 1) */
|
||||
MakeJoint({{2, 1}}), /* joint at point (3, 0) */
|
||||
};
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
return BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RestrictionTest, NonPassThroughStart)
|
||||
{
|
||||
Init(BuildNonPassThroughGraph(false /* passThroughStart */, true /* passThroughShortWay */,
|
||||
true /* passThroughLongWay */));
|
||||
|
||||
SetStarter(MakeFakeEnding(0 /* featureId */, 0 /* segmentIdx */, m2::PointD(0, 0), *m_graph),
|
||||
MakeFakeEnding(2, 0, m2::PointD(3, 0), *m_graph));
|
||||
|
||||
vector<m2::PointD> const expectedGeom = {{0 /* x */, 0 /* y */}, {1, 0}, {2, 0}, {3, 0}};
|
||||
TestRouteGeometry(*m_starter, Algorithm::Result::OK, expectedGeom);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RestrictionTest, NonPassThroughShortWay)
|
||||
{
|
||||
Init(BuildNonPassThroughGraph(true /* passThroughStart */, false /* passThroughShortWay */,
|
||||
true /* passThroughLongWay */));
|
||||
|
||||
SetStarter(MakeFakeEnding(0 /* featureId */, 0 /* segmentIdx */, m2::PointD(0, 0), *m_graph),
|
||||
MakeFakeEnding(2, 0, m2::PointD(3, 0), *m_graph));
|
||||
|
||||
// vector<m2::PointD> const expectedGeom = {{0 /* x */, 0 /* y */}, {1, 0}, {1, 1}, {2, 1}, {2, 0}, {3, 0}};
|
||||
vector<m2::PointD> const expectedGeom = {{0 /* x */, 0 /* y */}, {1, 0}, {2, 0}, {3, 0}};
|
||||
TestRouteGeometry(*m_starter, Algorithm::Result::OK, expectedGeom);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RestrictionTest, NonPassThroughWay)
|
||||
{
|
||||
Init(BuildNonPassThroughGraph(true /* passThroughStart */, false /* passThroughShortWay */,
|
||||
false /* passThroughLongWay */));
|
||||
|
||||
SetStarter(MakeFakeEnding(0 /* featureId */, 0 /* segmentIdx */, m2::PointD(0, 0), *m_graph),
|
||||
MakeFakeEnding(2, 0, m2::PointD(3, 0), *m_graph));
|
||||
|
||||
vector<m2::PointD> const expectedGeom = {{0 /* x */, 0 /* y */}, {1, 0}, {2, 0}, {3, 0}};
|
||||
TestRouteGeometry(*m_starter, Algorithm::Result::OK, expectedGeom);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RestrictionTest, NontransiStartAndShortWay)
|
||||
{
|
||||
Init(BuildNonPassThroughGraph(false /* passThroughStart */, false /* passThroughShortWay */,
|
||||
true /* passThroughLongWay */));
|
||||
// We can get F1 because F0 is in the same non-pass-through area/
|
||||
vector<m2::PointD> const expectedGeom = {{0 /* x */, 0 /* y */}, {1, 0}, {2, 0}, {3, 0}};
|
||||
|
||||
SetStarter(MakeFakeEnding(0 /* featureId */, 0 /* segmentIdx */, m2::PointD(0, 0), *m_graph),
|
||||
MakeFakeEnding(2, 0, m2::PointD(3, 0), *m_graph));
|
||||
TestRouteGeometry(*m_starter, Algorithm::Result::OK, expectedGeom);
|
||||
}
|
||||
|
||||
// 2 *
|
||||
// ↗ ↘
|
||||
// F5 F4
|
||||
// ↗ ↘ Finish
|
||||
// 1 * *<- F3 ->*-> F8 -> *
|
||||
// ↖ ↑
|
||||
// F6 F2
|
||||
// Start ↖ ↑
|
||||
// 0 *-> F7 ->*-> F0 ->*-> F1 ->*
|
||||
// -1 0 1 2 3
|
||||
//
|
||||
unique_ptr<SingleVehicleWorldGraph> BuildTwoCubeGraph1()
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
loader->AddRoad(0 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 0.0}, {1.0, 0.0}}));
|
||||
loader->AddRoad(1 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 0.0}, {2.0, 0.0}}));
|
||||
loader->AddRoad(2 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 0.0}, {2.0, 1.0}}));
|
||||
loader->AddRoad(3 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 1.0}, {2.0, 1.0}}));
|
||||
loader->AddRoad(4 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 2.0}, {1.0, 1.0}}));
|
||||
loader->AddRoad(5 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{-1.0, 1.0}, {0.0, 2.0}}));
|
||||
loader->AddRoad(6 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 0.0}, {-1.0, 1.0}}));
|
||||
loader->AddRoad(7 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{-1.0, 0.0}, {0.0, 0.0}}));
|
||||
loader->AddRoad(8 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 1.0}, {3.0, 1.0}}));
|
||||
|
||||
vector<Joint> const joints = {
|
||||
// {{/* feature id */, /* point id */}, ... }
|
||||
MakeJoint({{7, 0}}), /* joint at point (-1, 0) */
|
||||
MakeJoint({{0, 0}, {6, 0}, {7, 1}}), /* joint at point (0, 0) */
|
||||
MakeJoint({{0, 1}, {1, 0}}), /* joint at point (1, 0) */
|
||||
MakeJoint({{1, 1}, {2, 0}}), /* joint at point (2, 0) */
|
||||
MakeJoint({{2, 1}, {3, 1}, {8, 0}}), /* joint at point (2, 1) */
|
||||
MakeJoint({{3, 0}, {4, 1}}), /* joint at point (1, 1) */
|
||||
MakeJoint({{5, 1}, {4, 0}}), /* joint at point (0, 2) */
|
||||
MakeJoint({{6, 1}, {5, 0}}), /* joint at point (-1, 1) */
|
||||
MakeJoint({{8, 1}}), /* joint at point (3, 1) */
|
||||
};
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
return BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
}
|
||||
|
||||
// 2 *
|
||||
// ↗ ↘
|
||||
// F5 F4
|
||||
// ↗ ↘ Finish
|
||||
// 1 * *<- F3 ->*-> F8 -> *-> F10 -> *
|
||||
// ↖ ↑ ↗
|
||||
// F6 F2 F9
|
||||
// Start ↖ ↑ ↗
|
||||
// 0 *-> F7 ->*-> F0 ->*-> F1 ->*
|
||||
// -1 0 1 2 3 4
|
||||
//
|
||||
unique_ptr<SingleVehicleWorldGraph> BuildTwoCubeGraph2()
|
||||
{
|
||||
unique_ptr<TestGeometryLoader> loader = make_unique<TestGeometryLoader>();
|
||||
loader->AddRoad(0 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 0.0}, {1.0, 0.0}}));
|
||||
loader->AddRoad(1 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 0.0}, {2.0, 0.0}}));
|
||||
loader->AddRoad(2 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 0.0}, {2.0, 1.0}}));
|
||||
loader->AddRoad(3 /* feature id */, false /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 1.0}, {2.0, 1.0}}));
|
||||
loader->AddRoad(4 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 2.0}, {1.0, 1.0}}));
|
||||
loader->AddRoad(5 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{-1.0, 1.0}, {0.0, 2.0}}));
|
||||
loader->AddRoad(6 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 0.0}, {-1.0, 1.0}}));
|
||||
loader->AddRoad(7 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{-1.0, 0.0}, {0.0, 0.0}}));
|
||||
loader->AddRoad(8 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 1.0}, {3.0, 1.0}}));
|
||||
loader->AddRoad(9 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 0.0}, {3.0, 1.0}}));
|
||||
loader->AddRoad(10 /* feature id */, true /* one way */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{3.0, 1.0}, {4.0, 1.0}}));
|
||||
|
||||
vector<Joint> const joints = {
|
||||
// {{/* feature id */, /* point id */}, ... }
|
||||
MakeJoint({{7, 0}}), /* joint at point (-1, 0) */
|
||||
MakeJoint({{0, 0}, {6, 0}, {7, 1}}), /* joint at point (0, 0) */
|
||||
MakeJoint({{0, 1}, {1, 0}}), /* joint at point (1, 0) */
|
||||
MakeJoint({{1, 1}, {2, 0}, {9, 0}}), /* joint at point (2, 0) */
|
||||
MakeJoint({{2, 1}, {3, 1}, {8, 0}}), /* joint at point (2, 1) */
|
||||
MakeJoint({{3, 0}, {4, 1}}), /* joint at point (1, 1) */
|
||||
MakeJoint({{5, 1}, {4, 0}}), /* joint at point (0, 2) */
|
||||
MakeJoint({{6, 1}, {5, 0}}), /* joint at point (-1, 1) */
|
||||
MakeJoint({{8, 1}, {9, 1}, {10, 0}}), /* joint at point (3, 1) */
|
||||
MakeJoint({{10, 1}}) /* joint at point (4, 1) */
|
||||
};
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
return BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RestrictionTest, RestrictionNoWithWayAsVia_1)
|
||||
{
|
||||
Init(BuildTwoCubeGraph1());
|
||||
|
||||
m2::PointD const start(-1.0, 0.0);
|
||||
m2::PointD const finish(3.0, 1.0);
|
||||
auto const test = [&](vector<m2::PointD> const & expectedGeom, RestrictionVec && restrictionsNo)
|
||||
{
|
||||
TestRestrictions(
|
||||
expectedGeom, Algorithm::Result::OK, MakeFakeEnding(7 /* featureId */, 0 /* segmentIdx */, start, *m_graph),
|
||||
MakeFakeEnding(8 /* featureId */, 0 /* segmentIdx */, finish, *m_graph), std::move(restrictionsNo), *this);
|
||||
};
|
||||
|
||||
// Can not go from |0| to |2| via |1|
|
||||
RestrictionVec restrictionsNo = {{0 /* feature 0 */, 1 /* feature 1 */, 2 /* feature 2 */}};
|
||||
|
||||
// Check that without restrictions we can find path better.
|
||||
test({start, {0.0, 0.0}, {-1.0, 1.0}, {0.0, 2.0}, {1.0, 1.0}, {2.0, 1.0}, finish}, std::move(restrictionsNo));
|
||||
|
||||
test({start, {0.0, 0.0}, {1.0, 0.0}, {2.0, 0.0}, {2.0, 1.0}, finish}, RestrictionVec());
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RestrictionTest, RestrictionNoWithWayAsVia_2)
|
||||
{
|
||||
Init(BuildTwoCubeGraph2());
|
||||
|
||||
m2::PointD const start(-1.0, 0.0);
|
||||
m2::PointD const finish(4.0, 1.0);
|
||||
auto const test = [&](vector<m2::PointD> const & expectedGeom, RestrictionVec && restrictionsNo)
|
||||
{
|
||||
TestRestrictions(
|
||||
expectedGeom, Algorithm::Result::OK, MakeFakeEnding(7 /* featureId */, 0 /* segmentIdx */, start, *m_graph),
|
||||
MakeFakeEnding(10 /* featureId */, 0 /* segmentIdx */, finish, *m_graph), std::move(restrictionsNo), *this);
|
||||
};
|
||||
|
||||
// Can go from |0| to |9| only via |1|
|
||||
RestrictionVec restrictionsNo = {{0 /* feature 0 */, 1 /* feature 1 */, 9 /* feature 2 */}};
|
||||
|
||||
// Check that without restrictions we can find path better.
|
||||
test({start, {0.0, 0.0}, {1.0, 0.0}, {2.0, 0.0}, {2.0, 1.0}, {3.0, 1.0}, finish}, std::move(restrictionsNo));
|
||||
|
||||
test({start, {0.0, 0.0}, {1.0, 0.0}, {2.0, 0.0}, {3.0, 1.0}, finish}, RestrictionVec());
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RestrictionTest, RestrictionOnlyWithWayAsVia_1)
|
||||
{
|
||||
Init(BuildTwoCubeGraph2());
|
||||
|
||||
m2::PointD const start(-1.0, 0.0);
|
||||
m2::PointD const finish(4.0, 1.0);
|
||||
auto const test = [&](vector<m2::PointD> const & expectedGeom, RestrictionVec && restrictionsNo)
|
||||
{
|
||||
TestRestrictions(
|
||||
expectedGeom, Algorithm::Result::OK, MakeFakeEnding(7 /* featureId */, 0 /* segmentIdx */, start, *m_graph),
|
||||
MakeFakeEnding(10 /* featureId */, 0 /* segmentIdx */, finish, *m_graph), std::move(restrictionsNo), *this);
|
||||
};
|
||||
|
||||
RestrictionVec restrictionsNo;
|
||||
// Can go from |0| to |2| only via |1|
|
||||
RestrictionVec restrictionsOnly = {{0 /* feature 0 */, 1 /* feature 1 */, 2 /* feature 2 */}};
|
||||
ConvertRestrictionsOnlyToNo(m_graph->GetIndexGraphForTests(kTestNumMwmId), restrictionsOnly, restrictionsNo);
|
||||
|
||||
// Check that without restrictions we can find path better.
|
||||
test({start, {0, 0}, {1, 0}, {2, 0}, {2, 1}, {3, 1}, finish}, std::move(restrictionsNo));
|
||||
test({start, {0, 0}, {1, 0}, {2, 0}, {3, 1}, finish}, RestrictionVec());
|
||||
}
|
||||
} // namespace restriction_test
|
||||
703
libs/routing/routing_tests/road_access_test.cpp
Normal file
703
libs/routing/routing_tests/road_access_test.cpp
Normal file
|
|
@ -0,0 +1,703 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/road_access.hpp"
|
||||
#include "routing/road_access_serialization.hpp"
|
||||
|
||||
#include "routing/routing_tests/index_graph_tools.hpp"
|
||||
|
||||
#include "coding/reader.hpp"
|
||||
#include "coding/writer.hpp"
|
||||
|
||||
#include <algorithm>
|
||||
#include <cstdint>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
#include "3party/opening_hours/opening_hours.hpp"
|
||||
|
||||
namespace road_access_test
|
||||
{
|
||||
using namespace routing;
|
||||
using namespace routing_test;
|
||||
using namespace std;
|
||||
|
||||
using TestEdge = TestIndexGraphTopology::Edge;
|
||||
|
||||
void FillRoadAccessBySample_1(RoadAccess & roadAccess)
|
||||
{
|
||||
RoadAccess::WayToAccess wayToAccess = {
|
||||
{1 /* featureId */, RoadAccess::Type::No},
|
||||
{2 /* featureId */, RoadAccess::Type::Private},
|
||||
};
|
||||
|
||||
RoadAccess::PointToAccess pointToAccess = {
|
||||
{RoadPoint(3 /* featureId */, 0 /* pointId */), RoadAccess::Type::No},
|
||||
{RoadPoint(4 /* featureId */, 7 /* pointId */), RoadAccess::Type::Private},
|
||||
};
|
||||
|
||||
roadAccess.SetAccess(std::move(wayToAccess), std::move(pointToAccess));
|
||||
}
|
||||
|
||||
void FillRoadAccessBySample_2(RoadAccess & roadAccess)
|
||||
{
|
||||
RoadAccess::WayToAccess wayToAccess = {
|
||||
{1 /* featureId */, RoadAccess::Type::Private},
|
||||
{2 /* featureId */, RoadAccess::Type::Destination},
|
||||
};
|
||||
|
||||
RoadAccess::PointToAccess pointToAccess = {
|
||||
{RoadPoint(3 /* featureId */, 10 /* pointId */), RoadAccess::Type::Destination},
|
||||
{RoadPoint(4 /* featureId */, 0 /* pointId */), RoadAccess::Type::No},
|
||||
};
|
||||
|
||||
roadAccess.SetAccess(std::move(wayToAccess), std::move(pointToAccess));
|
||||
}
|
||||
|
||||
void FillRoadAccessBySampleConditional_1(RoadAccess & roadAccess)
|
||||
{
|
||||
std::vector<std::string> const openingHoursStrings = {
|
||||
"Mo-Su", "10:00-18:00", "Mo-Fr 10:00-14:00", "09:00-13:00", "Apr - May", "2010 - 2100"};
|
||||
|
||||
std::vector<osmoh::OpeningHours> openingHours;
|
||||
for (auto const & oh : openingHoursStrings)
|
||||
{
|
||||
openingHours.emplace_back(oh);
|
||||
TEST(openingHours.back().IsValid(), ());
|
||||
}
|
||||
|
||||
RoadAccess::Conditional conditional_1;
|
||||
conditional_1.Insert(RoadAccess::Type::No, std::move(openingHours[0]));
|
||||
conditional_1.Insert(RoadAccess::Type::Private, std::move(openingHours[1]));
|
||||
|
||||
RoadAccess::Conditional conditional_2;
|
||||
conditional_2.Insert(RoadAccess::Type::Destination, std::move(openingHours[2]));
|
||||
|
||||
RoadAccess::Conditional conditional_3;
|
||||
conditional_3.Insert(RoadAccess::Type::No, std::move(openingHours[4]));
|
||||
conditional_3.Insert(RoadAccess::Type::Destination, std::move(openingHours[3]));
|
||||
|
||||
RoadAccess::Conditional conditional_4;
|
||||
conditional_4.Insert(RoadAccess::Type::Destination, std::move(openingHours[5]));
|
||||
|
||||
RoadAccess::WayToAccessConditional wayToAccessConditional = {{1 /* featureId */, conditional_1},
|
||||
{2 /* featureId */, conditional_2}};
|
||||
|
||||
RoadAccess::PointToAccessConditional pointToAccessConditional = {
|
||||
{RoadPoint(3 /* featureId */, 0 /* pointId */), conditional_3},
|
||||
{RoadPoint(4 /* featureId */, 7 /* pointId */), conditional_4}};
|
||||
|
||||
roadAccess.SetAccessConditional(std::move(wayToAccessConditional), std::move(pointToAccessConditional));
|
||||
}
|
||||
|
||||
void FillRoadAccessBySampleConditional_2(RoadAccess & roadAccess)
|
||||
{
|
||||
std::vector<std::string> const openingHoursStrings = {
|
||||
"Mo", "Apr-May 03:00-04:25", "Mo-Sa 12:00-13:00", "2010-2098", "Nov-Apr", "19:00-21:00"};
|
||||
|
||||
std::vector<osmoh::OpeningHours> openingHours;
|
||||
for (auto const & oh : openingHoursStrings)
|
||||
{
|
||||
openingHours.emplace_back(oh);
|
||||
TEST(openingHours.back().IsValid(), (oh));
|
||||
}
|
||||
|
||||
RoadAccess::Conditional conditional_1;
|
||||
conditional_1.Insert(RoadAccess::Type::Private, std::move(openingHours[0]));
|
||||
|
||||
RoadAccess::Conditional conditional_2;
|
||||
conditional_2.Insert(RoadAccess::Type::No, std::move(openingHours[1]));
|
||||
conditional_2.Insert(RoadAccess::Type::Private, std::move(openingHours[2]));
|
||||
|
||||
RoadAccess::Conditional conditional_3;
|
||||
conditional_3.Insert(RoadAccess::Type::Destination, std::move(openingHours[3]));
|
||||
|
||||
RoadAccess::Conditional conditional_4;
|
||||
conditional_4.Insert(RoadAccess::Type::No, std::move(openingHours[4]));
|
||||
conditional_4.Insert(RoadAccess::Type::No, std::move(openingHours[5]));
|
||||
|
||||
RoadAccess::WayToAccessConditional wayToAccessConditional = {{1 /* featureId */, conditional_1},
|
||||
{2 /* featureId */, conditional_2}};
|
||||
|
||||
RoadAccess::PointToAccessConditional pointToAccessConditional = {
|
||||
{RoadPoint(3 /* featureId */, 10 /* pointId */), conditional_3},
|
||||
{RoadPoint(4 /* featureId */, 2 /* pointId */), conditional_4}};
|
||||
|
||||
roadAccess.SetAccessConditional(std::move(wayToAccessConditional), std::move(pointToAccessConditional));
|
||||
}
|
||||
|
||||
class RoadAccessSerDesTest
|
||||
{
|
||||
public:
|
||||
void Serialize(RoadAccessSerializer::RoadAccessByVehicleType const & roadAccessAllTypes)
|
||||
{
|
||||
MemWriter writer(m_buffer);
|
||||
RoadAccessSerializer::Serialize(writer, roadAccessAllTypes);
|
||||
}
|
||||
|
||||
void TestDeserialize(VehicleType vehicleType, RoadAccess const & answer)
|
||||
{
|
||||
RoadAccess deserializedRoadAccess;
|
||||
|
||||
MemReader memReader(m_buffer.data(), m_buffer.size());
|
||||
ReaderSource<MemReader> src(memReader);
|
||||
RoadAccessSerializer::Deserialize(src, vehicleType, deserializedRoadAccess);
|
||||
TEST_EQUAL(answer, deserializedRoadAccess, ());
|
||||
}
|
||||
|
||||
void ClearBuffer() { m_buffer.clear(); }
|
||||
|
||||
private:
|
||||
vector<uint8_t> m_buffer;
|
||||
};
|
||||
|
||||
UNIT_CLASS_TEST(RoadAccessSerDesTest, RoadAccess_Serdes)
|
||||
{
|
||||
RoadAccess roadAccessCar;
|
||||
FillRoadAccessBySample_1(roadAccessCar);
|
||||
|
||||
RoadAccess roadAccessPedestrian;
|
||||
FillRoadAccessBySample_2(roadAccessPedestrian);
|
||||
|
||||
RoadAccessSerializer::RoadAccessByVehicleType roadAccessAllTypes;
|
||||
roadAccessAllTypes[static_cast<size_t>(VehicleType::Car)] = roadAccessCar;
|
||||
roadAccessAllTypes[static_cast<size_t>(VehicleType::Pedestrian)] = roadAccessPedestrian;
|
||||
|
||||
Serialize(roadAccessAllTypes);
|
||||
TestDeserialize(VehicleType::Car, roadAccessCar);
|
||||
TestDeserialize(VehicleType::Pedestrian, roadAccessPedestrian);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RoadAccessSerDesTest, RoadAccess_Serdes_Conditional_One_Vehicle)
|
||||
{
|
||||
auto constexpr kVehicleTypeCount = static_cast<size_t>(VehicleType::Count);
|
||||
for (size_t vehicleTypeId = 0; vehicleTypeId < kVehicleTypeCount; ++vehicleTypeId)
|
||||
{
|
||||
RoadAccess roadAccess;
|
||||
FillRoadAccessBySampleConditional_1(roadAccess);
|
||||
|
||||
RoadAccessSerializer::RoadAccessByVehicleType roadAccessAllTypes;
|
||||
roadAccessAllTypes[vehicleTypeId] = roadAccess;
|
||||
|
||||
Serialize(roadAccessAllTypes);
|
||||
TestDeserialize(static_cast<VehicleType>(vehicleTypeId), roadAccess);
|
||||
ClearBuffer();
|
||||
}
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RoadAccessSerDesTest, RoadAccess_Serdes_Conditional_Several_Vehicles)
|
||||
{
|
||||
RoadAccess roadAccessCar;
|
||||
FillRoadAccessBySampleConditional_1(roadAccessCar);
|
||||
|
||||
RoadAccess roadAccessPedestrian;
|
||||
FillRoadAccessBySampleConditional_2(roadAccessPedestrian);
|
||||
|
||||
RoadAccessSerializer::RoadAccessByVehicleType roadAccessAllTypes;
|
||||
roadAccessAllTypes[static_cast<size_t>(VehicleType::Car)] = roadAccessCar;
|
||||
roadAccessAllTypes[static_cast<size_t>(VehicleType::Pedestrian)] = roadAccessPedestrian;
|
||||
|
||||
Serialize(roadAccessAllTypes);
|
||||
TestDeserialize(VehicleType::Car, roadAccessCar);
|
||||
TestDeserialize(VehicleType::Pedestrian, roadAccessPedestrian);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RoadAccessSerDesTest, RoadAccess_Serdes_Conditional_Mixed_Several_Vehicles)
|
||||
{
|
||||
RoadAccess roadAccessCar;
|
||||
FillRoadAccessBySampleConditional_1(roadAccessCar);
|
||||
FillRoadAccessBySample_1(roadAccessCar);
|
||||
|
||||
RoadAccess roadAccessPedestrian;
|
||||
FillRoadAccessBySampleConditional_2(roadAccessPedestrian);
|
||||
FillRoadAccessBySample_2(roadAccessPedestrian);
|
||||
|
||||
RoadAccessSerializer::RoadAccessByVehicleType roadAccessAllTypes;
|
||||
roadAccessAllTypes[static_cast<size_t>(VehicleType::Car)] = roadAccessCar;
|
||||
roadAccessAllTypes[static_cast<size_t>(VehicleType::Pedestrian)] = roadAccessPedestrian;
|
||||
|
||||
Serialize(roadAccessAllTypes);
|
||||
TestDeserialize(VehicleType::Car, roadAccessCar);
|
||||
TestDeserialize(VehicleType::Pedestrian, roadAccessPedestrian);
|
||||
}
|
||||
|
||||
UNIT_TEST(RoadAccess_WayBlocked)
|
||||
{
|
||||
// Add edges to the graph in the following format: (from, to, weight).
|
||||
// Block edges in the following format: (from, to).
|
||||
|
||||
uint32_t const numVertices = 4;
|
||||
TestIndexGraphTopology graph(numVertices);
|
||||
|
||||
graph.AddDirectedEdge(0, 1, 1.0);
|
||||
graph.AddDirectedEdge(1, 2, 1.0);
|
||||
graph.AddDirectedEdge(2, 3, 1.0);
|
||||
|
||||
double const expectedWeight = 0.0;
|
||||
vector<TestEdge> const expectedEdges = {};
|
||||
|
||||
graph.SetEdgeAccess(1, 2, RoadAccess::Type::No);
|
||||
|
||||
TestTopologyGraph(graph, 0, 3, false /* pathFound */, expectedWeight, expectedEdges);
|
||||
}
|
||||
|
||||
UNIT_TEST(RoadAccess_WayBlocking)
|
||||
{
|
||||
uint32_t const numVertices = 6;
|
||||
TestIndexGraphTopology graph(numVertices);
|
||||
|
||||
graph.AddDirectedEdge(0, 1, 1.0);
|
||||
graph.AddDirectedEdge(1, 2, 1.0);
|
||||
graph.AddDirectedEdge(2, 5, 1.0);
|
||||
graph.AddDirectedEdge(0, 3, 1.0);
|
||||
graph.AddDirectedEdge(3, 4, 2.0);
|
||||
graph.AddDirectedEdge(4, 5, 1.0);
|
||||
|
||||
double expectedWeight;
|
||||
vector<TestEdge> expectedEdges;
|
||||
|
||||
expectedWeight = 3.0;
|
||||
expectedEdges = {{0, 1}, {1, 2}, {2, 5}};
|
||||
TestTopologyGraph(graph, 0, 5, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
// Test avoid access=private while we have route with RoadAccess::Type::Yes.
|
||||
graph.SetEdgeAccess(1, 2, RoadAccess::Type::Private);
|
||||
expectedWeight = 4.0;
|
||||
expectedEdges = {{0, 3}, {3, 4}, {4, 5}};
|
||||
TestTopologyGraph(graph, 0, 5, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
// Test avoid access=destination while we have route with RoadAccess::Type::Yes.
|
||||
graph.SetEdgeAccess(1, 2, RoadAccess::Type::Destination);
|
||||
TestTopologyGraph(graph, 0, 5, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
// Test avoid access=no while we have route with RoadAccess::Type::Yes.
|
||||
graph.SetEdgeAccess(1, 2, RoadAccess::Type::No);
|
||||
TestTopologyGraph(graph, 0, 5, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
// Test it's possible to build the route because private usage restriction is not strict:
|
||||
// we use minimal possible number of access=yes/access={private, destination} crossing
|
||||
// but allow to use private/destination if there is no other way.
|
||||
graph.SetEdgeAccess(3, 4, RoadAccess::Type::Private);
|
||||
TestTopologyGraph(graph, 0, 5, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
// Test we have the same behaviour for access=destination.
|
||||
graph.SetEdgeAccess(3, 4, RoadAccess::Type::Destination);
|
||||
TestTopologyGraph(graph, 0, 5, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
// Test we have strict restriction for access=no and can not build route.
|
||||
graph.SetEdgeAccess(3, 4, RoadAccess::Type::No);
|
||||
TestTopologyGraph(graph, 0, 5, false /* pathFound */, expectedWeight, expectedEdges);
|
||||
}
|
||||
|
||||
UNIT_TEST(RoadAccess_BarrierBypassing)
|
||||
{
|
||||
uint32_t const numVertices = 6;
|
||||
TestIndexGraphTopology graph(numVertices);
|
||||
|
||||
graph.AddDirectedEdge(0, 1, 1.0);
|
||||
graph.AddDirectedEdge(1, 2, 1.0);
|
||||
graph.AddDirectedEdge(2, 5, 1.0);
|
||||
graph.AddDirectedEdge(0, 3, 1.0);
|
||||
graph.AddDirectedEdge(3, 4, 2.0);
|
||||
graph.AddDirectedEdge(4, 5, 1.0);
|
||||
|
||||
double expectedWeight;
|
||||
vector<TestEdge> expectedEdges;
|
||||
|
||||
expectedWeight = 3.0;
|
||||
expectedEdges = {{0, 1}, {1, 2}, {2, 5}};
|
||||
TestTopologyGraph(graph, 0, 5, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
// Test avoid access=private while we have route with RoadAccess::Type::Yes.
|
||||
graph.SetVertexAccess(1, RoadAccess::Type::Private);
|
||||
expectedWeight = 4.0;
|
||||
expectedEdges = {{0, 3}, {3, 4}, {4, 5}};
|
||||
TestTopologyGraph(graph, 0, 5, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
// Test avoid access=destination while we have route with RoadAccess::Type::Yes.
|
||||
graph.SetVertexAccess(1, RoadAccess::Type::Destination);
|
||||
TestTopologyGraph(graph, 0, 5, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
// Test avoid access=no while we have route with RoadAccess::Type::Yes.
|
||||
graph.SetVertexAccess(1, RoadAccess::Type::No);
|
||||
TestTopologyGraph(graph, 0, 5, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
// Test it's possible to build the route because private usage restriction is not strict:
|
||||
// we use minimal possible number of access=yes/access={private, destination} crossing
|
||||
// but allow to use private/destination if there is no other way.
|
||||
graph.SetVertexAccess(3, RoadAccess::Type::Private);
|
||||
TestTopologyGraph(graph, 0, 5, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
// Test we have the same behaviour for access=destination.
|
||||
graph.SetVertexAccess(3, RoadAccess::Type::Destination);
|
||||
TestTopologyGraph(graph, 0, 5, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
// Test we have strict restriction for access=no and can not build route.
|
||||
graph.SetVertexAccess(3, RoadAccess::Type::No);
|
||||
TestTopologyGraph(graph, 0, 5, false /* pathFound */, expectedWeight, expectedEdges);
|
||||
}
|
||||
|
||||
UNIT_TEST(RoadAccess_WayBlockedConditional)
|
||||
{
|
||||
uint32_t const numVertices = 4;
|
||||
TestIndexGraphTopology graph(numVertices);
|
||||
|
||||
graph.AddDirectedEdge(0, 1, 1.0);
|
||||
graph.AddDirectedEdge(1, 2, 1.0);
|
||||
graph.AddDirectedEdge(2, 3, 1.0);
|
||||
|
||||
double expectedWeight = 3.0;
|
||||
vector<TestEdge> expectedEdges = {{0, 1}, {1, 2}, {2, 3}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
graph.SetEdgeAccessConditional(1, 2, RoadAccess::Type::No, "Jan - Jul");
|
||||
|
||||
auto const april = []() { return GetUnixtimeByDate(2020, Month::Apr, 1, 12 /* hh */, 00 /* mm */); };
|
||||
|
||||
graph.SetCurrentTimeGetter(april);
|
||||
expectedWeight = 0;
|
||||
expectedEdges = {};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, false /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
auto const november = []() { return GetUnixtimeByDate(2020, Month::Nov, 1, 12 /* hh */, 00 /* mm */); };
|
||||
|
||||
graph.SetCurrentTimeGetter(november);
|
||||
expectedWeight = 3.0;
|
||||
expectedEdges = {{0, 1}, {1, 2}, {2, 3}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
}
|
||||
|
||||
UNIT_TEST(RoadAccess_PointBlockedConditional)
|
||||
{
|
||||
uint32_t const numVertices = 4;
|
||||
TestIndexGraphTopology graph(numVertices);
|
||||
|
||||
graph.AddDirectedEdge(0, 1, 1.0);
|
||||
graph.AddDirectedEdge(1, 2, 1.0);
|
||||
graph.AddDirectedEdge(2, 3, 1.0);
|
||||
|
||||
double expectedWeight = 3.0;
|
||||
vector<TestEdge> expectedEdges = {{0, 1}, {1, 2}, {2, 3}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, true /* pathFound */, expectedWeight,
|
||||
expectedEdges);
|
||||
|
||||
graph.SetVertexAccessConditional(1, RoadAccess::Type::No, "Jan - Jul");
|
||||
|
||||
auto const april = []() {
|
||||
return GetUnixtimeByDate(2020, Month::Apr, 1, 12 /* hh */, 00 /* mm */);
|
||||
};
|
||||
|
||||
graph.SetCurrentTimeGetter(april);
|
||||
expectedWeight = 0;
|
||||
expectedEdges = {};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, false /* pathFound */, expectedWeight,
|
||||
expectedEdges);
|
||||
|
||||
auto const november = []() {
|
||||
return GetUnixtimeByDate(2020, Month::Nov, 1, 12 /* hh */, 00 /* mm */);
|
||||
};
|
||||
|
||||
graph.SetCurrentTimeGetter(november);
|
||||
expectedWeight = 3.0;
|
||||
expectedEdges = {{0, 1}, {1, 2}, {2, 3}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, true /* pathFound */, expectedWeight,
|
||||
expectedEdges);
|
||||
}
|
||||
|
||||
UNIT_TEST(RoadAccess_WayBlockedAvoidConditional)
|
||||
{
|
||||
uint32_t const numVertices = 4;
|
||||
TestIndexGraphTopology graph(numVertices);
|
||||
|
||||
graph.AddDirectedEdge(0, 1, 1.0);
|
||||
graph.AddDirectedEdge(0, 2, 10.0);
|
||||
graph.AddDirectedEdge(1, 3, 1.0);
|
||||
graph.AddDirectedEdge(2, 3, 10.0);
|
||||
|
||||
double expectedWeight = 2.0;
|
||||
vector<TestEdge> expectedEdges = {{0, 1}, {1, 3}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
graph.SetEdgeAccessConditional(0, 1, RoadAccess::Type::No, "Mo-Fr 10:00 - 19:00");
|
||||
|
||||
auto const mondayAlmostTenHours = []()
|
||||
{ return GetUnixtimeByDate(2020, Month::Apr, Weekday::Monday, 9 /* hh */, 50 /* mm */); };
|
||||
|
||||
// In this time we probably will able to pass 0->1 edge, but we are not sure, so we should avoid
|
||||
// such edges.
|
||||
graph.SetCurrentTimeGetter(mondayAlmostTenHours);
|
||||
expectedWeight = 20.0;
|
||||
expectedEdges = {{0, 2}, {2, 3}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
graph.SetEdgeAccess(0, 2, RoadAccess::Type::No);
|
||||
|
||||
// But if this is the only path (we blocked 0->2 above), we should pass edge 0->1 anyway.
|
||||
graph.SetCurrentTimeGetter(mondayAlmostTenHours);
|
||||
expectedWeight = 2.0;
|
||||
expectedEdges = {{0, 1}, {1, 3}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
auto const mondayTwelveHours = []()
|
||||
{ return GetUnixtimeByDate(2020, Month::Apr, Weekday::Monday, 12 /* hh */, 00 /* mm */); };
|
||||
|
||||
// But if we sure that in this time edge: 0->1 will be blocked, we definitely should not pass
|
||||
// 0->1. In this case no way will be found.
|
||||
graph.SetCurrentTimeGetter(mondayTwelveHours);
|
||||
expectedWeight = 0.0;
|
||||
expectedEdges = {};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, false /* pathFound */, expectedWeight, expectedEdges);
|
||||
}
|
||||
|
||||
UNIT_TEST(RoadAccess_PointBlockedAvoidConditional)
|
||||
{
|
||||
uint32_t const numVertices = 4;
|
||||
TestIndexGraphTopology graph(numVertices);
|
||||
|
||||
graph.AddDirectedEdge(0, 1, 1.0);
|
||||
graph.AddDirectedEdge(0, 2, 10.0);
|
||||
graph.AddDirectedEdge(1, 3, 1.0);
|
||||
graph.AddDirectedEdge(2, 3, 10.0);
|
||||
|
||||
double expectedWeight = 2.0;
|
||||
vector<TestEdge> expectedEdges = {{0, 1}, {1, 3}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, true /* pathFound */, expectedWeight,
|
||||
expectedEdges);
|
||||
|
||||
graph.SetVertexAccessConditional(1, RoadAccess::Type::No, "Mo-Fr 10:00 - 19:00");
|
||||
|
||||
auto const mondayAlmostTenHours = []() {
|
||||
return GetUnixtimeByDate(2020, Month::Apr, Weekday::Monday, 9 /* hh */, 50 /* mm */);
|
||||
};
|
||||
|
||||
// In this time we probably will able to pass vertex: 1, but we are not sure, so we should avoid
|
||||
// such edges.
|
||||
graph.SetCurrentTimeGetter(mondayAlmostTenHours);
|
||||
expectedWeight = 20.0;
|
||||
expectedEdges = {{0, 2}, {2, 3}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, true /* pathFound */, expectedWeight,
|
||||
expectedEdges);
|
||||
|
||||
graph.SetEdgeAccess(0, 2, RoadAccess::Type::No);
|
||||
|
||||
// But if this is the only path (we blocked 0->2 above), we should pass through vertex: 1 anyway.
|
||||
graph.SetCurrentTimeGetter(mondayAlmostTenHours);
|
||||
expectedWeight = 2.0;
|
||||
expectedEdges = {{0, 1}, {1, 3}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, true /* pathFound */, expectedWeight,
|
||||
expectedEdges);
|
||||
|
||||
auto const mondayTwelveHours = []() {
|
||||
return GetUnixtimeByDate(2020, Month::Apr, Weekday::Monday, 12 /* hh */, 00 /* mm */);
|
||||
};
|
||||
|
||||
// But if we sure that in this time vertex: 1 will be blocked, we definitely should not pass
|
||||
// through vertex: 1. In this case no way will be found.
|
||||
graph.SetCurrentTimeGetter(mondayTwelveHours);
|
||||
expectedWeight = 0.0;
|
||||
expectedEdges = {};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, false /* pathFound */, expectedWeight,
|
||||
expectedEdges);
|
||||
}
|
||||
|
||||
UNIT_TEST(RoadAccess_WayBlockedConditional_Yes_No)
|
||||
{
|
||||
uint32_t const numVertices = 4;
|
||||
TestIndexGraphTopology graph(numVertices);
|
||||
|
||||
graph.AddDirectedEdge(0, 1, 1.0);
|
||||
graph.AddDirectedEdge(1, 2, 1.0);
|
||||
graph.AddDirectedEdge(2, 3, 1.0);
|
||||
|
||||
double expectedWeight = 3.0;
|
||||
vector<TestEdge> expectedEdges = {{0, 1}, {1, 2}, {2, 3}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
graph.SetEdgeAccessConditional(1, 2, RoadAccess::Type::No, "Mo-Fr");
|
||||
graph.SetEdgeAccessConditional(1, 2, RoadAccess::Type::Yes, "Sa-Su");
|
||||
|
||||
auto const tuesday = []() { return GetUnixtimeByDate(2020, Month::Apr, Weekday::Tuesday, 10 /* hh */, 00 /* mm */); };
|
||||
|
||||
// Way is blocked from Monday to Friday
|
||||
graph.SetCurrentTimeGetter(tuesday);
|
||||
expectedWeight = 0;
|
||||
expectedEdges = {};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, false /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
auto const saturday = []()
|
||||
{ return GetUnixtimeByDate(2020, Month::Nov, Weekday::Saturday, 10 /* hh */, 00 /* mm */); };
|
||||
|
||||
// And open from Saturday to Sunday
|
||||
graph.SetCurrentTimeGetter(saturday);
|
||||
expectedWeight = 3.0;
|
||||
expectedEdges = {{0, 1}, {1, 2}, {2, 3}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
}
|
||||
|
||||
UNIT_TEST(RoadAccess_PointBlockedConditional_Yes_No)
|
||||
{
|
||||
uint32_t const numVertices = 4;
|
||||
TestIndexGraphTopology graph(numVertices);
|
||||
|
||||
graph.AddDirectedEdge(0, 1, 1.0);
|
||||
graph.AddDirectedEdge(1, 2, 1.0);
|
||||
graph.AddDirectedEdge(2, 3, 1.0);
|
||||
|
||||
double expectedWeight = 3.0;
|
||||
vector<TestEdge> expectedEdges = {{0, 1}, {1, 2}, {2, 3}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, true /* pathFound */, expectedWeight,
|
||||
expectedEdges);
|
||||
|
||||
graph.SetVertexAccessConditional(1, RoadAccess::Type::No, "Mo-Fr");
|
||||
graph.SetVertexAccessConditional(1, RoadAccess::Type::Yes, "Sa-Su");
|
||||
|
||||
auto const tuesday = []() {
|
||||
return GetUnixtimeByDate(2020, Month::Apr, Weekday::Tuesday, 10 /* hh */, 00 /* mm */);
|
||||
};
|
||||
|
||||
// Way is blocked from Monday to Friday
|
||||
graph.SetCurrentTimeGetter(tuesday);
|
||||
expectedWeight = 0;
|
||||
expectedEdges = {};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, false /* pathFound */, expectedWeight,
|
||||
expectedEdges);
|
||||
|
||||
auto const saturday = []() {
|
||||
return GetUnixtimeByDate(2020, Month::Nov, Weekday::Saturday, 10 /* hh */, 00 /* mm */);
|
||||
};
|
||||
|
||||
// And open from Saturday to Sunday
|
||||
graph.SetCurrentTimeGetter(saturday);
|
||||
expectedWeight = 3.0;
|
||||
expectedEdges = {{0, 1}, {1, 2}, {2, 3}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, true /* pathFound */, expectedWeight,
|
||||
expectedEdges);
|
||||
}
|
||||
|
||||
UNIT_TEST(RoadAccess_WayBlockedAvoidPrivateConditional)
|
||||
{
|
||||
uint32_t const numVertices = 4;
|
||||
TestIndexGraphTopology graph(numVertices);
|
||||
|
||||
graph.AddDirectedEdge(0, 1, 1.0);
|
||||
graph.AddDirectedEdge(0, 2, 10.0);
|
||||
graph.AddDirectedEdge(1, 3, 1.0);
|
||||
graph.AddDirectedEdge(2, 3, 10.0);
|
||||
|
||||
double expectedWeight = 2.0;
|
||||
vector<TestEdge> expectedEdges = {{0, 1}, {1, 3}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
graph.SetEdgeAccessConditional(0, 1, RoadAccess::Type::Private, "Mo-Fr 19:00 - 23:00");
|
||||
|
||||
auto const mondayAlmostTwentyHalfHours = []()
|
||||
{ return GetUnixtimeByDate(2020, Month::Apr, Weekday::Monday, 20 /* hh */, 30 /* mm */); };
|
||||
|
||||
// We should avoid ways with private accesses. At 20:30 edge: 0->1 definitely has private access,
|
||||
// thus the answer is: 0->2->3.
|
||||
graph.SetCurrentTimeGetter(mondayAlmostTwentyHalfHours);
|
||||
expectedWeight = 20.0;
|
||||
expectedEdges = {{0, 2}, {2, 3}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
graph.SetEdgeAccess(0, 2, RoadAccess::Type::No);
|
||||
|
||||
// But if this is the only path (we blocked 0->2 above), we should pass through edge: 0->1 anyway.
|
||||
graph.SetCurrentTimeGetter(mondayAlmostTwentyHalfHours);
|
||||
expectedWeight = 2.0;
|
||||
expectedEdges = {{0, 1}, {1, 3}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
}
|
||||
|
||||
UNIT_TEST(RoadAccess_WayBlockedAlwaysNoExceptMonday)
|
||||
{
|
||||
uint32_t const numVertices = 4;
|
||||
TestIndexGraphTopology graph(numVertices);
|
||||
|
||||
graph.AddDirectedEdge(0, 1, 1.0);
|
||||
graph.AddDirectedEdge(1, 2, 1.0);
|
||||
graph.AddDirectedEdge(2, 3, 1.0);
|
||||
|
||||
double expectedWeight = 3.0;
|
||||
vector<TestEdge> expectedEdges = {{0, 1}, {1, 2}, {2, 3}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
// Always access no for edge: 1->2.
|
||||
graph.SetEdgeAccess(1, 2, RoadAccess::Type::No);
|
||||
expectedWeight = 0;
|
||||
expectedEdges = {};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, false /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
// Except Monday, access yes in this day.
|
||||
graph.SetEdgeAccessConditional(1, 2, RoadAccess::Type::Yes, "Mo");
|
||||
|
||||
auto const monday = []() { return GetUnixtimeByDate(2020, Month::Apr, Weekday::Monday, 10 /* hh */, 00 /* mm */); };
|
||||
|
||||
graph.SetCurrentTimeGetter(monday);
|
||||
expectedWeight = 3.0;
|
||||
expectedEdges = {{0, 1}, {1, 2}, {2, 3}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 3 /* to */, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
}
|
||||
|
||||
UNIT_TEST(RoadAccess_WayBlockedWhenStartButOpenWhenReach)
|
||||
{
|
||||
uint32_t const numVertices = 7;
|
||||
TestIndexGraphTopology graph(numVertices);
|
||||
|
||||
graph.AddDirectedEdge(0, 1, 1.0);
|
||||
graph.AddDirectedEdge(1, 2, 1.0);
|
||||
graph.AddDirectedEdge(2, 3, 10800.0);
|
||||
graph.AddDirectedEdge(3, 4, 1.0);
|
||||
graph.AddDirectedEdge(4, 5, 1.0);
|
||||
|
||||
// Alternative way from |3| to |5|.
|
||||
graph.AddDirectedEdge(3, 6, 1000.0);
|
||||
graph.AddDirectedEdge(6, 5, 1000.0);
|
||||
|
||||
double expectedWeight = 10804.0;
|
||||
vector<TestEdge> expectedEdges = {{0, 1}, {1, 2}, {2, 3}, {3, 4}, {4, 5}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 5 /* to */, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
auto const startAt_11_50 = []()
|
||||
{ return GetUnixtimeByDate(2020, Month::Apr, Weekday::Monday, 11 /* hh */, 50 /* mm */); };
|
||||
|
||||
graph.SetCurrentTimeGetter(startAt_11_50);
|
||||
// When we will be at |3|, current time should be:
|
||||
// 11:50:00 + (0, 1) weight + (1, 2) weight + (2, 3) weight == 14:50:01, so we should ignore
|
||||
// access: (3, 4).
|
||||
graph.SetEdgeAccessConditional(3, 4, RoadAccess::Type::No, "10:00 - 13:00");
|
||||
expectedWeight = 10804.0;
|
||||
expectedEdges = {{0, 1}, {1, 2}, {2, 3}, {3, 4}, {4, 5}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 5 /* to */, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
auto const startAt_10_50 = []()
|
||||
{ return GetUnixtimeByDate(2020, Month::Apr, Weekday::Monday, 10 /* hh */, 50 /* mm */); };
|
||||
|
||||
graph.SetCurrentTimeGetter(startAt_10_50);
|
||||
// When we will be at |3|, current time should be:
|
||||
// 11:50:00 + (0, 1) weight + (1, 2) weight + (2, 3) weight == 12:50:01. This time places in
|
||||
// dangerous zone, but we are not sure, so we should chose alternative way.
|
||||
expectedWeight = 12802.0;
|
||||
expectedEdges = {{0, 1}, {1, 2}, {2, 3}, {3, 6}, {6, 5}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 5 /* to */, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
// Block alternative way.
|
||||
graph.SetEdgeAccess(3, 6, RoadAccess::Type::No);
|
||||
// We are still in dangerous zone, but alternative way is blocked, so we should chose dangerous
|
||||
// way.
|
||||
expectedWeight = 10804.0;
|
||||
expectedEdges = {{0, 1}, {1, 2}, {2, 3}, {3, 4}, {4, 5}};
|
||||
TestTopologyGraph(graph, 0 /* from */, 5 /* to */, true /* pathFound */, expectedWeight, expectedEdges);
|
||||
|
||||
auto const startAt_9_00 = []()
|
||||
{ return GetUnixtimeByDate(2020, Month::Apr, Weekday::Monday, 9 /* hh */, 00 /* mm */); };
|
||||
|
||||
graph.SetCurrentTimeGetter(startAt_9_00);
|
||||
// If we start at 9:00:00 we will arrive at |3| at:
|
||||
// 9:00:00 + (0, 1) weight + (1, 2) weight + (2, 3) weight == 12:00:02
|
||||
// At this time are sure that (3, 4) way is blocked, so (remember that we also blocked alternative
|
||||
// way) no way should be found.
|
||||
expectedWeight = 0.0;
|
||||
expectedEdges = {};
|
||||
TestTopologyGraph(graph, 0 /* from */, 5 /* to */, false /* pathFound */, expectedWeight, expectedEdges);
|
||||
}
|
||||
} // namespace road_access_test
|
||||
239
libs/routing/routing_tests/road_graph_builder.cpp
Normal file
239
libs/routing/routing_tests/road_graph_builder.cpp
Normal file
|
|
@ -0,0 +1,239 @@
|
|||
#include "routing/routing_tests/road_graph_builder.hpp"
|
||||
|
||||
#include "routing/road_graph.hpp"
|
||||
|
||||
#include "indexer/mwm_set.hpp"
|
||||
|
||||
#include "geometry/point_with_altitude.hpp"
|
||||
|
||||
#include "base/checked_cast.hpp"
|
||||
#include "base/logging.hpp"
|
||||
#include "base/macros.hpp"
|
||||
|
||||
#include <algorithm>
|
||||
#include <memory>
|
||||
|
||||
namespace routing_test
|
||||
{
|
||||
using std::move;
|
||||
|
||||
auto constexpr kMaxSpeedKMpH = 5.0;
|
||||
|
||||
/// Class provides a valid instance of FeatureID for testing purposes
|
||||
class TestValidFeatureIDProvider : private MwmSet
|
||||
{
|
||||
public:
|
||||
TestValidFeatureIDProvider()
|
||||
{
|
||||
UNUSED_VALUE(Register(platform::LocalCountryFile::MakeForTesting("0")));
|
||||
|
||||
std::vector<std::shared_ptr<MwmInfo>> mwmsInfoList;
|
||||
GetMwmsInfo(mwmsInfoList);
|
||||
|
||||
m_mwmInfo = mwmsInfoList[0];
|
||||
}
|
||||
|
||||
FeatureID MakeFeatureID(uint32_t offset) const { return FeatureID(MwmSet::MwmId(m_mwmInfo), offset); }
|
||||
|
||||
private:
|
||||
/// @name MwmSet overrides
|
||||
//@{
|
||||
std::unique_ptr<MwmInfo> CreateInfo(platform::LocalCountryFile const &) const override
|
||||
{
|
||||
std::unique_ptr<MwmInfo> info(new MwmInfo());
|
||||
info->m_maxScale = 1;
|
||||
info->m_bordersRect = m2::RectD(0, 0, 1, 1);
|
||||
info->m_version.SetFormat(version::Format::lastFormat);
|
||||
return info;
|
||||
}
|
||||
std::unique_ptr<MwmValue> CreateValue(MwmInfo & info) const override
|
||||
{
|
||||
return std::make_unique<MwmValue>(info.GetLocalFile());
|
||||
}
|
||||
//@}
|
||||
|
||||
std::shared_ptr<MwmInfo> m_mwmInfo;
|
||||
};
|
||||
|
||||
void RoadGraphMockSource::AddRoad(RoadInfo && ri)
|
||||
{
|
||||
CHECK_GREATER_OR_EQUAL(ri.m_junctions.size(), 2, ("Empty road"));
|
||||
m_roads.push_back(std::move(ri));
|
||||
}
|
||||
|
||||
IRoadGraph::RoadInfo RoadGraphMockSource::GetRoadInfo(FeatureID const & featureId,
|
||||
SpeedParams const & /* speedParams */) const
|
||||
{
|
||||
CHECK_LESS(featureId.m_index, m_roads.size(), ("Invalid feature id."));
|
||||
return m_roads[featureId.m_index];
|
||||
}
|
||||
|
||||
double RoadGraphMockSource::GetSpeedKMpH(FeatureID const & featureId, SpeedParams const & /* speedParams */) const
|
||||
{
|
||||
CHECK_LESS(featureId.m_index, m_roads.size(), ("Invalid feature id."));
|
||||
return m_roads[featureId.m_index].m_speedKMPH;
|
||||
}
|
||||
|
||||
double RoadGraphMockSource::GetMaxSpeedKMpH() const
|
||||
{
|
||||
return kMaxSpeedKMpH;
|
||||
}
|
||||
|
||||
void RoadGraphMockSource::ForEachFeatureClosestToCross(m2::PointD const & /* cross */,
|
||||
ICrossEdgesLoader & edgesLoader) const
|
||||
{
|
||||
for (size_t roadId = 0; roadId < m_roads.size(); ++roadId)
|
||||
{
|
||||
edgesLoader(MakeTestFeatureID(base::checked_cast<uint32_t>(roadId)), m_roads[roadId].m_junctions,
|
||||
m_roads[roadId].m_bidirectional);
|
||||
}
|
||||
}
|
||||
|
||||
void RoadGraphMockSource::GetFeatureTypes(FeatureID const & featureId, feature::TypesHolder & types) const
|
||||
{
|
||||
UNUSED_VALUE(featureId);
|
||||
UNUSED_VALUE(types);
|
||||
}
|
||||
|
||||
void RoadGraphMockSource::GetJunctionTypes(geometry::PointWithAltitude const & junction,
|
||||
feature::TypesHolder & types) const
|
||||
{
|
||||
UNUSED_VALUE(junction);
|
||||
UNUSED_VALUE(types);
|
||||
}
|
||||
|
||||
IRoadGraph::Mode RoadGraphMockSource::GetMode() const
|
||||
{
|
||||
return IRoadGraph::Mode::IgnoreOnewayTag;
|
||||
}
|
||||
|
||||
FeatureID MakeTestFeatureID(uint32_t offset)
|
||||
{
|
||||
static TestValidFeatureIDProvider instance;
|
||||
return instance.MakeFeatureID(offset);
|
||||
}
|
||||
|
||||
void InitRoadGraphMockSourceWithTest1(RoadGraphMockSource & src)
|
||||
{
|
||||
IRoadGraph::RoadInfo ri0;
|
||||
ri0.m_bidirectional = true;
|
||||
ri0.m_speedKMPH = kMaxSpeedKMpH;
|
||||
ri0.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 0)));
|
||||
ri0.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(5, 0)));
|
||||
ri0.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(10, 0)));
|
||||
ri0.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(15, 0)));
|
||||
ri0.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(20, 0)));
|
||||
|
||||
IRoadGraph::RoadInfo ri1;
|
||||
ri1.m_bidirectional = true;
|
||||
ri1.m_speedKMPH = kMaxSpeedKMpH;
|
||||
ri1.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(10, -10)));
|
||||
ri1.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(10, -5)));
|
||||
ri1.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(10, 0)));
|
||||
ri1.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(10, 5)));
|
||||
ri1.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(10, 10)));
|
||||
|
||||
IRoadGraph::RoadInfo ri2;
|
||||
ri2.m_bidirectional = true;
|
||||
ri2.m_speedKMPH = kMaxSpeedKMpH;
|
||||
ri2.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(15, -5)));
|
||||
ri2.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(15, 0)));
|
||||
|
||||
IRoadGraph::RoadInfo ri3;
|
||||
ri3.m_bidirectional = true;
|
||||
ri3.m_speedKMPH = kMaxSpeedKMpH;
|
||||
ri3.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(20, 0)));
|
||||
ri3.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(25, 5)));
|
||||
ri3.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(15, 5)));
|
||||
ri3.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(20, 0)));
|
||||
|
||||
src.AddRoad(std::move(ri0));
|
||||
src.AddRoad(std::move(ri1));
|
||||
src.AddRoad(std::move(ri2));
|
||||
src.AddRoad(std::move(ri3));
|
||||
}
|
||||
|
||||
void InitRoadGraphMockSourceWithTest2(RoadGraphMockSource & graph)
|
||||
{
|
||||
IRoadGraph::RoadInfo ri0;
|
||||
ri0.m_bidirectional = true;
|
||||
ri0.m_speedKMPH = kMaxSpeedKMpH;
|
||||
ri0.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 0)));
|
||||
ri0.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(10, 0)));
|
||||
ri0.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(25, 0)));
|
||||
ri0.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(35, 0)));
|
||||
ri0.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(70, 0)));
|
||||
ri0.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(80, 0)));
|
||||
|
||||
IRoadGraph::RoadInfo ri1;
|
||||
ri1.m_bidirectional = true;
|
||||
ri1.m_speedKMPH = kMaxSpeedKMpH;
|
||||
ri1.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 0)));
|
||||
ri1.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(5, 10)));
|
||||
ri1.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(5, 40)));
|
||||
|
||||
IRoadGraph::RoadInfo ri2;
|
||||
ri2.m_bidirectional = true;
|
||||
ri2.m_speedKMPH = kMaxSpeedKMpH;
|
||||
ri2.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(12, 25)));
|
||||
ri2.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(10, 10)));
|
||||
ri2.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(10, 0)));
|
||||
|
||||
IRoadGraph::RoadInfo ri3;
|
||||
ri3.m_bidirectional = true;
|
||||
ri3.m_speedKMPH = kMaxSpeedKMpH;
|
||||
ri3.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(5, 10)));
|
||||
ri3.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(10, 10)));
|
||||
ri3.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(70, 10)));
|
||||
ri3.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(80, 10)));
|
||||
|
||||
IRoadGraph::RoadInfo ri4;
|
||||
ri4.m_bidirectional = true;
|
||||
ri4.m_speedKMPH = kMaxSpeedKMpH;
|
||||
ri4.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(25, 0)));
|
||||
ri4.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(27, 25)));
|
||||
|
||||
IRoadGraph::RoadInfo ri5;
|
||||
ri5.m_bidirectional = true;
|
||||
ri5.m_speedKMPH = kMaxSpeedKMpH;
|
||||
ri5.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(35, 0)));
|
||||
ri5.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(37, 30)));
|
||||
ri5.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(70, 30)));
|
||||
ri5.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(80, 30)));
|
||||
|
||||
IRoadGraph::RoadInfo ri6;
|
||||
ri6.m_bidirectional = true;
|
||||
ri6.m_speedKMPH = kMaxSpeedKMpH;
|
||||
ri6.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(70, 0)));
|
||||
ri6.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(70, 10)));
|
||||
ri6.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(70, 30)));
|
||||
|
||||
IRoadGraph::RoadInfo ri7;
|
||||
ri7.m_bidirectional = true;
|
||||
ri7.m_speedKMPH = kMaxSpeedKMpH;
|
||||
ri7.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(39, 55)));
|
||||
ri7.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(80, 55)));
|
||||
|
||||
IRoadGraph::RoadInfo ri8;
|
||||
ri8.m_bidirectional = true;
|
||||
ri8.m_speedKMPH = kMaxSpeedKMpH;
|
||||
ri8.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(5, 40)));
|
||||
ri8.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(18, 55)));
|
||||
ri8.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(39, 55)));
|
||||
ri8.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(37, 30)));
|
||||
ri8.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(27, 25)));
|
||||
ri8.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(12, 25)));
|
||||
ri8.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(5, 40)));
|
||||
|
||||
graph.AddRoad(std::move(ri0));
|
||||
graph.AddRoad(std::move(ri1));
|
||||
graph.AddRoad(std::move(ri2));
|
||||
graph.AddRoad(std::move(ri3));
|
||||
graph.AddRoad(std::move(ri4));
|
||||
graph.AddRoad(std::move(ri5));
|
||||
graph.AddRoad(std::move(ri6));
|
||||
graph.AddRoad(std::move(ri7));
|
||||
graph.AddRoad(std::move(ri8));
|
||||
}
|
||||
|
||||
} // namespace routing_test
|
||||
43
libs/routing/routing_tests/road_graph_builder.hpp
Normal file
43
libs/routing/routing_tests/road_graph_builder.hpp
Normal file
|
|
@ -0,0 +1,43 @@
|
|||
#pragma once
|
||||
#include "routing_algorithm.hpp"
|
||||
|
||||
#include "routing/road_graph.hpp"
|
||||
|
||||
#include "routing_common/maxspeed_conversion.hpp"
|
||||
#include "routing_common/vehicle_model.hpp"
|
||||
|
||||
#include <utility>
|
||||
#include <vector>
|
||||
|
||||
namespace routing_test
|
||||
{
|
||||
|
||||
class RoadGraphMockSource : public RoadGraphIFace
|
||||
{
|
||||
public:
|
||||
void AddRoad(RoadInfo && ri);
|
||||
|
||||
inline size_t GetRoadCount() const { return m_roads.size(); }
|
||||
|
||||
/// @name RoadGraphIFace overrides:
|
||||
/// @{
|
||||
RoadInfo GetRoadInfo(FeatureID const & f, routing::SpeedParams const & speedParams) const override;
|
||||
double GetSpeedKMpH(FeatureID const & featureId, routing::SpeedParams const & speedParams) const override;
|
||||
double GetMaxSpeedKMpH() const override;
|
||||
/// @}
|
||||
|
||||
void ForEachFeatureClosestToCross(m2::PointD const & cross, ICrossEdgesLoader & edgeLoader) const override;
|
||||
void GetFeatureTypes(FeatureID const & featureId, feature::TypesHolder & types) const override;
|
||||
void GetJunctionTypes(geometry::PointWithAltitude const & junction, feature::TypesHolder & types) const override;
|
||||
routing::IRoadGraph::Mode GetMode() const override;
|
||||
|
||||
private:
|
||||
std::vector<RoadInfo> m_roads;
|
||||
};
|
||||
|
||||
FeatureID MakeTestFeatureID(uint32_t offset);
|
||||
|
||||
void InitRoadGraphMockSourceWithTest1(RoadGraphMockSource & graphMock);
|
||||
void InitRoadGraphMockSourceWithTest2(RoadGraphMockSource & graphMock);
|
||||
|
||||
} // namespace routing_test
|
||||
109
libs/routing/routing_tests/road_graph_nearest_edges_test.cpp
Normal file
109
libs/routing/routing_tests/road_graph_nearest_edges_test.cpp
Normal file
|
|
@ -0,0 +1,109 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/road_graph.hpp"
|
||||
#include "routing/routing_tests/road_graph_builder.hpp"
|
||||
|
||||
#include "geometry/point_with_altitude.hpp"
|
||||
|
||||
#include <algorithm>
|
||||
#include <utility>
|
||||
|
||||
namespace routing_test
|
||||
{
|
||||
|
||||
using namespace routing;
|
||||
using namespace std;
|
||||
|
||||
UNIT_TEST(RoadGraph_NearestEdges)
|
||||
{
|
||||
// ^ 1st road
|
||||
// o
|
||||
// |
|
||||
// |
|
||||
// o
|
||||
// |
|
||||
// | 0th road
|
||||
// o--o--x--o--o >
|
||||
// |
|
||||
// |
|
||||
// o
|
||||
// |
|
||||
// |
|
||||
// o
|
||||
//
|
||||
// Two roads are intersecting in (0, 0).
|
||||
RoadGraphMockSource graph;
|
||||
{
|
||||
IRoadGraph::RoadInfo ri0;
|
||||
ri0.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(-2, 0)));
|
||||
ri0.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(-1, 0)));
|
||||
ri0.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 0)));
|
||||
ri0.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(1, 0)));
|
||||
ri0.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(2, 0)));
|
||||
ri0.m_speedKMPH = 5;
|
||||
ri0.m_bidirectional = true;
|
||||
|
||||
IRoadGraph::RoadInfo ri1;
|
||||
ri1.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(0, -2)));
|
||||
ri1.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(0, -1)));
|
||||
ri1.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 0)));
|
||||
ri1.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 1)));
|
||||
ri1.m_junctions.push_back(geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 2)));
|
||||
ri1.m_speedKMPH = 5;
|
||||
ri1.m_bidirectional = true;
|
||||
|
||||
graph.AddRoad(std::move(ri0));
|
||||
graph.AddRoad(std::move(ri1));
|
||||
}
|
||||
|
||||
// We are standing at x junction.
|
||||
geometry::PointWithAltitude const crossPos = geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 0));
|
||||
|
||||
// Expected outgoing edges.
|
||||
IRoadGraph::EdgeListT expectedOutgoing = {
|
||||
Edge::MakeReal(MakeTestFeatureID(0) /* first road */, false /* forward */, 1 /* segId */,
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 0)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(-1, 0))),
|
||||
Edge::MakeReal(MakeTestFeatureID(0) /* first road */, true /* forward */, 2 /* segId */,
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 0)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(1, 0))),
|
||||
Edge::MakeReal(MakeTestFeatureID(1) /* second road */, false /* forward */, 1 /* segId */,
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 0)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(0, -1))),
|
||||
Edge::MakeReal(MakeTestFeatureID(1) /* second road */, true /* forward */, 2 /* segId */,
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 0)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 1))),
|
||||
};
|
||||
sort(expectedOutgoing.begin(), expectedOutgoing.end());
|
||||
|
||||
// Expected ingoing edges.
|
||||
IRoadGraph::EdgeListT expectedIngoing = {
|
||||
Edge::MakeReal(MakeTestFeatureID(0) /* first road */, true /* forward */, 1 /* segId */,
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(-1, 0)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 0))),
|
||||
Edge::MakeReal(MakeTestFeatureID(0) /* first road */, false /* forward */, 2 /* segId */,
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(1, 0)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 0))),
|
||||
Edge::MakeReal(MakeTestFeatureID(1) /* second road */, true /* forward */, 1 /* segId */,
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(0, -1)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 0))),
|
||||
Edge::MakeReal(MakeTestFeatureID(1) /* second road */, false /* forward */, 2 /* segId */,
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 1)),
|
||||
geometry::MakePointWithAltitudeForTesting(m2::PointD(0, 0))),
|
||||
};
|
||||
sort(expectedIngoing.begin(), expectedIngoing.end());
|
||||
|
||||
// Check outgoing edges.
|
||||
IRoadGraph::EdgeListT actualOutgoing;
|
||||
graph.GetOutgoingEdges(crossPos, actualOutgoing);
|
||||
sort(actualOutgoing.begin(), actualOutgoing.end());
|
||||
TEST_EQUAL(expectedOutgoing, actualOutgoing, ());
|
||||
|
||||
// Check ingoing edges.
|
||||
IRoadGraph::EdgeListT actualIngoing;
|
||||
graph.GetIngoingEdges(crossPos, actualIngoing);
|
||||
sort(actualIngoing.begin(), actualIngoing.end());
|
||||
TEST_EQUAL(expectedIngoing, actualIngoing, ());
|
||||
}
|
||||
|
||||
} // namespace routing_test
|
||||
169
libs/routing/routing_tests/road_penalty_test.cpp
Normal file
169
libs/routing/routing_tests/road_penalty_test.cpp
Normal file
|
|
@ -0,0 +1,169 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/road_penalty.hpp"
|
||||
#include "routing/road_point.hpp"
|
||||
#include "routing/vehicle_mask.hpp"
|
||||
|
||||
#include <optional>
|
||||
#include <utility>
|
||||
|
||||
namespace road_penalty_test
|
||||
{
|
||||
using namespace routing;
|
||||
|
||||
UNIT_TEST(RoadPenalty_Basic)
|
||||
{
|
||||
RoadPenalty penalty;
|
||||
|
||||
// Test empty penalty
|
||||
TEST(!penalty.GetPenalty(RoadPoint(1, 0)).has_value(), ());
|
||||
TEST(!penalty.GetPenalty(RoadPoint(2, 1)).has_value(), ());
|
||||
}
|
||||
|
||||
UNIT_TEST(RoadPenalty_PointPenalties)
|
||||
{
|
||||
RoadPenalty penalty;
|
||||
|
||||
// Test point penalties
|
||||
RoadPenalty::PointToPenalty pointPenalties;
|
||||
pointPenalties[RoadPoint(1, 0)] = RoadPenalty::Penalty(RoadPenalty::Type::MediumCalming, VehicleType::Car);
|
||||
pointPenalties[RoadPoint(2, 3)] = RoadPenalty::Penalty(RoadPenalty::Type::Gate, VehicleType::Car);
|
||||
penalty.SetPointPenalties(std::move(pointPenalties));
|
||||
|
||||
auto p1 = penalty.GetPenalty(RoadPoint(1, 0));
|
||||
TEST(p1.has_value(), ());
|
||||
TEST_EQUAL(p1->m_type, RoadPenalty::Type::MediumCalming, ());
|
||||
TEST_EQUAL(p1->m_timeSeconds, 5, ());
|
||||
|
||||
auto p2 = penalty.GetPenalty(RoadPoint(2, 3));
|
||||
TEST(p2.has_value(), ());
|
||||
TEST_EQUAL(p2->m_type, RoadPenalty::Type::Gate, ());
|
||||
TEST_EQUAL(p2->m_timeSeconds, 30, ());
|
||||
|
||||
TEST(!penalty.GetPenalty(RoadPoint(1, 1)).has_value(), ());
|
||||
}
|
||||
|
||||
UNIT_TEST(RoadPenalty_TypeConversion)
|
||||
{
|
||||
// Test ToString/FromString
|
||||
TEST_EQUAL(ToString(RoadPenalty::Type::None), "None", ());
|
||||
TEST_EQUAL(ToString(RoadPenalty::Type::SmallCalming), "SmallCalming", ());
|
||||
TEST_EQUAL(ToString(RoadPenalty::Type::MediumCalming), "MediumCalming", ());
|
||||
TEST_EQUAL(ToString(RoadPenalty::Type::LargeCalming), "LargeCalming", ());
|
||||
TEST_EQUAL(ToString(RoadPenalty::Type::Gate), "Gate", ());
|
||||
TEST_EQUAL(ToString(RoadPenalty::Type::UncontrolledJunction), "UncontrolledJunction", ());
|
||||
TEST_EQUAL(ToString(RoadPenalty::Type::ControlledJunction), "ControlledJunction", ());
|
||||
|
||||
RoadPenalty::Type type;
|
||||
FromString("SmallCalming", type);
|
||||
TEST_EQUAL(type, RoadPenalty::Type::SmallCalming, ());
|
||||
|
||||
FromString("Gate", type);
|
||||
TEST_EQUAL(type, RoadPenalty::Type::Gate, ());
|
||||
|
||||
FromString("UncontrolledJunction", type);
|
||||
TEST_EQUAL(type, RoadPenalty::Type::UncontrolledJunction, ());
|
||||
|
||||
FromString("ControlledJunction", type);
|
||||
TEST_EQUAL(type, RoadPenalty::Type::ControlledJunction, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(RoadPenalty_Equality)
|
||||
{
|
||||
RoadPenalty penalty1, penalty2;
|
||||
TEST(penalty1 == penalty2, ());
|
||||
|
||||
RoadPenalty::PointToPenalty pointPenalties;
|
||||
pointPenalties[RoadPoint(1, 0)] = RoadPenalty::Penalty(RoadPenalty::Type::SmallCalming, VehicleType::Car);
|
||||
penalty1.SetPointPenalties(std::move(pointPenalties));
|
||||
|
||||
TEST(!(penalty1 == penalty2), ());
|
||||
|
||||
pointPenalties.clear();
|
||||
pointPenalties[RoadPoint(1, 0)] = RoadPenalty::Penalty(RoadPenalty::Type::SmallCalming, VehicleType::Car);
|
||||
penalty2.SetPointPenalties(std::move(pointPenalties));
|
||||
|
||||
TEST(penalty1 == penalty2, ());
|
||||
}
|
||||
|
||||
// Test vehicle mask functionality
|
||||
UNIT_TEST(RoadPenalty_VehicleMask)
|
||||
{
|
||||
// Test basic mask operations
|
||||
VehicleMask mask = 0;
|
||||
|
||||
// Set bit for Car (VehicleType::Car = 2)
|
||||
mask |= (1 << 2);
|
||||
TEST((mask & (1 << 2)) != 0, ());
|
||||
TEST((mask & (1 << 1)) == 0, ());
|
||||
|
||||
// Test mask with multiple vehicle types
|
||||
VehicleMask multiMask = 0;
|
||||
multiMask |= (1 << 0); // Pedestrian
|
||||
multiMask |= (1 << 1); // Bicycle
|
||||
multiMask |= (1 << 2); // Car
|
||||
|
||||
// Verify multiple bits are set
|
||||
TEST_EQUAL(__builtin_popcount(multiMask), 3, ());
|
||||
}
|
||||
|
||||
// Test default time penalties
|
||||
UNIT_TEST(RoadPenalty_DefaultTimes)
|
||||
{
|
||||
// Test GetTimePenalty with Car as default
|
||||
TEST_EQUAL(RoadPenalty::Penalty::GetTimePenalty(RoadPenalty::Type::None, VehicleType::Car), 0, ());
|
||||
TEST_EQUAL(RoadPenalty::Penalty::GetTimePenalty(RoadPenalty::Type::SmallCalming, VehicleType::Car), 3, ());
|
||||
TEST_EQUAL(RoadPenalty::Penalty::GetTimePenalty(RoadPenalty::Type::MediumCalming, VehicleType::Car), 5, ());
|
||||
TEST_EQUAL(RoadPenalty::Penalty::GetTimePenalty(RoadPenalty::Type::LargeCalming, VehicleType::Car), 7, ());
|
||||
TEST_EQUAL(RoadPenalty::Penalty::GetTimePenalty(RoadPenalty::Type::Gate, VehicleType::Car), 30, ());
|
||||
TEST_EQUAL(RoadPenalty::Penalty::GetTimePenalty(RoadPenalty::Type::UncontrolledJunction, VehicleType::Car), 15, ());
|
||||
TEST_EQUAL(RoadPenalty::Penalty::GetTimePenalty(RoadPenalty::Type::ControlledJunction, VehicleType::Car), 30, ());
|
||||
|
||||
// Test constructor with vehicle type
|
||||
RoadPenalty::Penalty smallCalming(RoadPenalty::Type::SmallCalming, VehicleType::Car);
|
||||
TEST_EQUAL(smallCalming.m_type, RoadPenalty::Type::SmallCalming, ());
|
||||
TEST_EQUAL(smallCalming.m_timeSeconds, 3, ());
|
||||
|
||||
RoadPenalty::Penalty gate(RoadPenalty::Type::Gate, VehicleType::Car);
|
||||
TEST_EQUAL(gate.m_type, RoadPenalty::Type::Gate, ());
|
||||
TEST_EQUAL(gate.m_timeSeconds, 30, ());
|
||||
}
|
||||
|
||||
// Test vehicle-specific time penalties
|
||||
UNIT_TEST(RoadPenalty_VehicleSpecificTimes)
|
||||
{
|
||||
// Test GetTimePenalty with different vehicle types
|
||||
TEST_EQUAL(RoadPenalty::Penalty::GetTimePenalty(RoadPenalty::Type::Gate, VehicleType::Car), 30, ());
|
||||
TEST_EQUAL(RoadPenalty::Penalty::GetTimePenalty(RoadPenalty::Type::Gate, VehicleType::Bicycle), 10, ());
|
||||
TEST_EQUAL(RoadPenalty::Penalty::GetTimePenalty(RoadPenalty::Type::Gate, VehicleType::Pedestrian), 10, ());
|
||||
TEST_EQUAL(RoadPenalty::Penalty::GetTimePenalty(RoadPenalty::Type::Gate, VehicleType::Transit), 5, ());
|
||||
|
||||
// Test constructor with vehicle type
|
||||
RoadPenalty::Penalty carGate(RoadPenalty::Type::Gate, VehicleType::Car);
|
||||
TEST_EQUAL(carGate.m_type, RoadPenalty::Type::Gate, ());
|
||||
TEST_EQUAL(carGate.m_timeSeconds, 30, ());
|
||||
|
||||
RoadPenalty::Penalty bicycleGate(RoadPenalty::Type::Gate, VehicleType::Bicycle);
|
||||
TEST_EQUAL(bicycleGate.m_type, RoadPenalty::Type::Gate, ());
|
||||
TEST_EQUAL(bicycleGate.m_timeSeconds, 10, ());
|
||||
|
||||
// Test traffic calming with different vehicles
|
||||
RoadPenalty::Penalty carCalming(RoadPenalty::Type::SmallCalming, VehicleType::Car);
|
||||
TEST_EQUAL(carCalming.m_type, RoadPenalty::Type::SmallCalming, ());
|
||||
TEST_EQUAL(carCalming.m_timeSeconds, 3, ());
|
||||
|
||||
RoadPenalty::Penalty bicycleCalming(RoadPenalty::Type::SmallCalming, VehicleType::Bicycle);
|
||||
TEST_EQUAL(bicycleCalming.m_type, RoadPenalty::Type::SmallCalming, ());
|
||||
TEST_EQUAL(bicycleCalming.m_timeSeconds, 0, ());
|
||||
|
||||
// Test junction penalties with different vehicles
|
||||
TEST_EQUAL(RoadPenalty::Penalty::GetTimePenalty(RoadPenalty::Type::UncontrolledJunction, VehicleType::Bicycle), 10,
|
||||
());
|
||||
TEST_EQUAL(RoadPenalty::Penalty::GetTimePenalty(RoadPenalty::Type::ControlledJunction, VehicleType::Bicycle), 30, ());
|
||||
TEST_EQUAL(RoadPenalty::Penalty::GetTimePenalty(RoadPenalty::Type::UncontrolledJunction, VehicleType::Pedestrian), 0,
|
||||
());
|
||||
TEST_EQUAL(RoadPenalty::Penalty::GetTimePenalty(RoadPenalty::Type::ControlledJunction, VehicleType::Pedestrian), 0,
|
||||
());
|
||||
}
|
||||
|
||||
} // namespace road_penalty_test
|
||||
439
libs/routing/routing_tests/route_tests.cpp
Normal file
439
libs/routing/routing_tests/route_tests.cpp
Normal file
|
|
@ -0,0 +1,439 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/route.hpp"
|
||||
#include "routing/routing_helpers.hpp"
|
||||
#include "routing/turns.hpp"
|
||||
|
||||
#include "routing/base/followed_polyline.hpp"
|
||||
|
||||
#include "routing/routing_tests/tools.hpp"
|
||||
|
||||
#include "platform/location.hpp"
|
||||
|
||||
#include "geometry/mercator.hpp"
|
||||
#include "geometry/point2d.hpp"
|
||||
#include "geometry/point_with_altitude.hpp"
|
||||
|
||||
#include <set>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
namespace route_tests
|
||||
{
|
||||
using namespace routing;
|
||||
using namespace routing::turns;
|
||||
using namespace std;
|
||||
|
||||
// For all test geometry: geometry[0] == geometry[1], since info about 1st point will be lost.
|
||||
static vector<m2::PointD> const kTestGeometry = {{0, 0}, {0, 0}, {1, 1}, {1, 2}, {1, 3}, {1, 4}};
|
||||
static vector<Segment> const kTestSegments = {
|
||||
{0, 0, 0, true}, {0, 0, 1, true}, {0, 0, 2, true}, {0, 0, 3, true}, {0, 0, 4, true}};
|
||||
static vector<turns::TurnItem> const kTestTurns({turns::TurnItem(1, turns::CarDirection::None),
|
||||
turns::TurnItem(2, turns::CarDirection::TurnLeft),
|
||||
turns::TurnItem(3, turns::CarDirection::TurnRight),
|
||||
turns::TurnItem(4, turns::CarDirection::None),
|
||||
turns::TurnItem(5, turns::CarDirection::ReachedYourDestination)});
|
||||
static vector<double> const kTestTimes = {0.0, 7.0, 10.0, 19.0, 20.0};
|
||||
static vector<RouteSegment::RoadNameInfo> const kTestNames = {{"Street0", "", "", "", "", false},
|
||||
{"Street1", "", "", "", "", false},
|
||||
{"Street2", "", "", "", "", false},
|
||||
{"", "", "", "", "", false},
|
||||
{"Street3", "", "", "", "", false}};
|
||||
|
||||
void GetTestRouteSegments(vector<m2::PointD> const & routePoints, vector<turns::TurnItem> const & turns,
|
||||
vector<RouteSegment::RoadNameInfo> const & streets, vector<double> const & times,
|
||||
vector<RouteSegment> & routeSegments)
|
||||
{
|
||||
RouteSegmentsFrom({}, routePoints, turns, streets, routeSegments);
|
||||
FillSegmentInfo(kTestTimes, routeSegments);
|
||||
}
|
||||
|
||||
location::GpsInfo GetGps(double x, double y)
|
||||
{
|
||||
location::GpsInfo info;
|
||||
info.m_latitude = mercator::YToLat(y);
|
||||
info.m_longitude = mercator::XToLon(x);
|
||||
info.m_horizontalAccuracy = 2;
|
||||
return info;
|
||||
}
|
||||
|
||||
vector<vector<Segment>> const GetSegments()
|
||||
{
|
||||
auto const segmentsAllReal = kTestSegments;
|
||||
vector<Segment> const segmentsAllFake = {{kFakeNumMwmId, 0, 0, true},
|
||||
{kFakeNumMwmId, 0, 1, true},
|
||||
{kFakeNumMwmId, 0, 2, true},
|
||||
{kFakeNumMwmId, 0, 3, true},
|
||||
{kFakeNumMwmId, 0, 4, true}};
|
||||
vector<Segment> const segmentsFakeHeadAndTail = {
|
||||
{kFakeNumMwmId, 0, 0, true}, {0, 0, 1, true}, {0, 0, 2, true}, {0, 0, 3, true}, {kFakeNumMwmId, 0, 4, true}};
|
||||
return {segmentsAllReal, segmentsFakeHeadAndTail, segmentsAllFake};
|
||||
}
|
||||
|
||||
UNIT_TEST(AddAbsentCountryToRouteTest)
|
||||
{
|
||||
Route route("TestRouter", 0 /* route id */);
|
||||
route.AddAbsentCountry("A");
|
||||
route.AddAbsentCountry("A");
|
||||
route.AddAbsentCountry("B");
|
||||
route.AddAbsentCountry("C");
|
||||
route.AddAbsentCountry("B");
|
||||
set<string> const & absent = route.GetAbsentCountries();
|
||||
TEST(absent.find("A") != absent.end(), ());
|
||||
TEST(absent.find("B") != absent.end(), ());
|
||||
TEST(absent.find("C") != absent.end(), ());
|
||||
}
|
||||
|
||||
UNIT_TEST(FinshRouteOnSomeDistanceToTheFinishPointTest)
|
||||
{
|
||||
for (auto const vehicleType : {VehicleType::Car, VehicleType::Bicycle, VehicleType::Pedestrian, VehicleType::Transit})
|
||||
{
|
||||
auto const settings = GetRoutingSettings(vehicleType);
|
||||
for (auto const & segments : GetSegments())
|
||||
{
|
||||
Route route("TestRouter", 0 /* route id */);
|
||||
route.SetRoutingSettings(settings);
|
||||
|
||||
vector<RouteSegment> routeSegments;
|
||||
RouteSegmentsFrom(segments, kTestGeometry, kTestTurns, {}, routeSegments);
|
||||
FillSegmentInfo(kTestTimes, routeSegments);
|
||||
route.SetRouteSegments(std::move(routeSegments));
|
||||
|
||||
route.SetGeometry(kTestGeometry.begin(), kTestGeometry.end());
|
||||
route.SetSubroteAttrs(vector<Route::SubrouteAttrs>(
|
||||
{Route::SubrouteAttrs(geometry::PointWithAltitude(kTestGeometry.front(), geometry::kDefaultAltitudeMeters),
|
||||
geometry::PointWithAltitude(kTestGeometry.back(), geometry::kDefaultAltitudeMeters), 0,
|
||||
kTestSegments.size())}));
|
||||
|
||||
// The route should be finished at some distance to the finish point.
|
||||
double const distToFinish = settings.m_finishToleranceM;
|
||||
|
||||
route.MoveIterator(GetGps(kTestGeometry.back().x, kTestGeometry.back().y - 0.1));
|
||||
TEST(!route.IsSubroutePassed(0), ());
|
||||
TEST_GREATER(route.GetCurrentDistanceToEndMeters(), distToFinish, ());
|
||||
|
||||
route.MoveIterator(GetGps(kTestGeometry.back().x, kTestGeometry.back().y - 0.02));
|
||||
TEST(!route.IsSubroutePassed(0), ());
|
||||
TEST_GREATER(route.GetCurrentDistanceToEndMeters(), distToFinish, ());
|
||||
|
||||
// Finish tolerance value for cars is greater then for other vehicle types.
|
||||
// The iterator for other types should be moved closer to the finish point.
|
||||
if (vehicleType == VehicleType::Car)
|
||||
route.MoveIterator(GetGps(kTestGeometry.back().x, kTestGeometry.back().y - 0.00014));
|
||||
else
|
||||
route.MoveIterator(GetGps(kTestGeometry.back().x, kTestGeometry.back().y - 0.00011));
|
||||
|
||||
TEST(route.IsSubroutePassed(0), ());
|
||||
TEST_LESS(route.GetCurrentDistanceToEndMeters(), distToFinish, ());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
UNIT_TEST(DistanceAndTimeToCurrentTurnTest)
|
||||
{
|
||||
// |curTurn.m_index| is an index of the point of |curTurn| at polyline |route.m_poly|.
|
||||
|
||||
Route route("TestRouter", 0 /* route id */);
|
||||
vector<RouteSegment> routeSegments;
|
||||
GetTestRouteSegments(kTestGeometry, kTestTurns, {}, kTestTimes, routeSegments);
|
||||
route.SetGeometry(kTestGeometry.begin(), kTestGeometry.end());
|
||||
vector<turns::TurnItem> turns(kTestTurns);
|
||||
|
||||
route.SetRouteSegments(std::move(routeSegments));
|
||||
|
||||
double distance;
|
||||
turns::TurnItem turn;
|
||||
|
||||
{
|
||||
// Initial point.
|
||||
auto pos = kTestGeometry[0];
|
||||
|
||||
route.GetNearestTurn(distance, turn);
|
||||
size_t currentTurnIndex = 2; // Turn with m_index == 1 is None.
|
||||
TEST_ALMOST_EQUAL_ABS(distance, mercator::DistanceOnEarth(pos, kTestGeometry[currentTurnIndex]), 0.1, ());
|
||||
TEST_EQUAL(turn, kTestTurns[currentTurnIndex - 1], ());
|
||||
|
||||
double timePassed = 0;
|
||||
|
||||
double time = route.GetCurrentTimeToEndSec();
|
||||
TEST_ALMOST_EQUAL_ABS(time, kTestTimes[4] - timePassed, 0.1, ());
|
||||
|
||||
time = route.GetCurrentTimeToNearestTurnSec();
|
||||
TEST_ALMOST_EQUAL_ABS(time, kTestTimes[currentTurnIndex - 1] - timePassed, 0.1, ());
|
||||
}
|
||||
{
|
||||
// Move between points 1 and 2.
|
||||
auto const pos = (kTestGeometry[1] + kTestGeometry[2]) / 2;
|
||||
route.MoveIterator(GetGps(pos.x, pos.y));
|
||||
|
||||
route.GetNearestTurn(distance, turn);
|
||||
size_t const currentTurnIndex = 2;
|
||||
TEST_ALMOST_EQUAL_ABS(distance, mercator::DistanceOnEarth(pos, kTestGeometry[currentTurnIndex]), 0.1, ());
|
||||
TEST_EQUAL(turn, kTestTurns[currentTurnIndex - 1], ());
|
||||
|
||||
double const timePassed = (kTestTimes[1 - 1] + kTestTimes[2 - 1]) / 2;
|
||||
|
||||
double time = route.GetCurrentTimeToEndSec();
|
||||
TEST_ALMOST_EQUAL_ABS(time, kTestTimes[4] - timePassed, 0.1, ());
|
||||
|
||||
time = route.GetCurrentTimeToNearestTurnSec();
|
||||
TEST_ALMOST_EQUAL_ABS(time, kTestTimes[currentTurnIndex - 1] - timePassed, 0.1, ());
|
||||
}
|
||||
{
|
||||
// Move between points 2 and 3.
|
||||
auto const pos = kTestGeometry[2] * 0.8 + kTestGeometry[3] * 0.2;
|
||||
route.MoveIterator(GetGps(pos.x, pos.y));
|
||||
|
||||
route.GetNearestTurn(distance, turn);
|
||||
size_t const currentTurnIndex = 3;
|
||||
TEST_ALMOST_EQUAL_ABS(distance, mercator::DistanceOnEarth(pos, kTestGeometry[currentTurnIndex]), 0.1, ());
|
||||
TEST_EQUAL(turn, kTestTurns[currentTurnIndex - 1], ());
|
||||
|
||||
double const timePassed = 0.8 * kTestTimes[2 - 1] + 0.2 * kTestTimes[3 - 1];
|
||||
|
||||
double time = route.GetCurrentTimeToEndSec();
|
||||
TEST_ALMOST_EQUAL_ABS(time, kTestTimes[4] - timePassed, 0.1, ());
|
||||
|
||||
time = route.GetCurrentTimeToNearestTurnSec();
|
||||
TEST_ALMOST_EQUAL_ABS(time, kTestTimes[currentTurnIndex - 1] - timePassed, 0.1, ());
|
||||
}
|
||||
{
|
||||
// Move between points 3 and 4.
|
||||
auto const pos = kTestGeometry[3] * 0.3 + kTestGeometry[4] * 0.7;
|
||||
route.MoveIterator(GetGps(pos.x, pos.y));
|
||||
|
||||
route.GetNearestTurn(distance, turn);
|
||||
size_t const currentTurnIndex = 5; // Turn with m_index == 4 is None.
|
||||
TEST_ALMOST_EQUAL_ABS(distance, mercator::DistanceOnEarth(pos, kTestGeometry[currentTurnIndex]), 0.1, ());
|
||||
TEST_EQUAL(turn, kTestTurns[currentTurnIndex - 1], ());
|
||||
|
||||
double const timePassed = 0.3 * kTestTimes[3 - 1] + 0.7 * kTestTimes[4 - 1];
|
||||
|
||||
double time = route.GetCurrentTimeToEndSec();
|
||||
TEST_ALMOST_EQUAL_ABS(time, kTestTimes[4] - timePassed, 0.1, ());
|
||||
|
||||
time = route.GetCurrentTimeToNearestTurnSec();
|
||||
TEST_ALMOST_EQUAL_ABS(time, kTestTimes[currentTurnIndex - 1] - timePassed, 0.1, ());
|
||||
}
|
||||
}
|
||||
|
||||
UNIT_TEST(NextTurnTest)
|
||||
{
|
||||
Route route("TestRouter", 0 /* route id */);
|
||||
vector<RouteSegment> routeSegments;
|
||||
GetTestRouteSegments(kTestGeometry, kTestTurns, {}, {}, routeSegments);
|
||||
route.SetRouteSegments(std::move(routeSegments));
|
||||
route.SetGeometry(kTestGeometry.begin(), kTestGeometry.end());
|
||||
|
||||
double distance, nextDistance;
|
||||
turns::TurnItem turn, nextTurn;
|
||||
|
||||
{
|
||||
// Initial point.
|
||||
size_t const currentTurnIndex = 2; // Turn with m_index == 1 is None.
|
||||
route.GetNearestTurn(distance, turn);
|
||||
TEST_EQUAL(turn, kTestTurns[currentTurnIndex - 1], ());
|
||||
|
||||
size_t const nextTurnIndex = 3;
|
||||
route.GetNextTurn(nextDistance, nextTurn);
|
||||
TEST_EQUAL(nextTurn, kTestTurns[nextTurnIndex - 1], ());
|
||||
}
|
||||
{
|
||||
// Move between points 1 and 2.
|
||||
auto const pos = (kTestGeometry[1] + kTestGeometry[2]) / 2;
|
||||
route.MoveIterator(GetGps(pos.x, pos.y));
|
||||
|
||||
size_t const currentTurnIndex = 2;
|
||||
route.GetNearestTurn(distance, turn);
|
||||
TEST_EQUAL(turn, kTestTurns[currentTurnIndex - 1], ());
|
||||
|
||||
size_t const nextTurnIndex = 3;
|
||||
route.GetNextTurn(nextDistance, nextTurn);
|
||||
TEST_EQUAL(nextTurn, kTestTurns[nextTurnIndex - 1], ());
|
||||
}
|
||||
{
|
||||
// Move between points 3 and 4.
|
||||
auto const pos = (kTestGeometry[3] + kTestGeometry[4]) / 2;
|
||||
route.MoveIterator(GetGps(pos.x, pos.y));
|
||||
|
||||
size_t const currentTurnIndex = 5; // Turn with m_index == 4 is None.
|
||||
route.GetNearestTurn(distance, turn);
|
||||
TEST_EQUAL(turn, kTestTurns[currentTurnIndex - 1], ());
|
||||
|
||||
// nextTurn is absent.
|
||||
route.GetNextTurn(nextDistance, nextTurn);
|
||||
TEST_EQUAL(nextTurn, turns::TurnItem(), ());
|
||||
}
|
||||
}
|
||||
|
||||
UNIT_TEST(NextTurnsTest)
|
||||
{
|
||||
Route route("TestRouter", 0 /* route id */);
|
||||
route.SetGeometry(kTestGeometry.begin(), kTestGeometry.end());
|
||||
vector<RouteSegment> routeSegments;
|
||||
GetTestRouteSegments(kTestGeometry, kTestTurns, {}, {}, routeSegments);
|
||||
route.SetRouteSegments(std::move(routeSegments));
|
||||
|
||||
vector<turns::TurnItem> turns(kTestTurns);
|
||||
vector<turns::TurnItemDist> turnsDist;
|
||||
|
||||
{
|
||||
// Initial point.
|
||||
auto const pos = kTestGeometry[0];
|
||||
|
||||
size_t const currentTurnIndex = 2; // Turn with m_index == 1 is None.
|
||||
size_t const nextTurnIndex = 3;
|
||||
TEST(route.GetNextTurns(turnsDist), ());
|
||||
TEST_EQUAL(turnsDist.size(), 2, ());
|
||||
double const firstSegLenM = mercator::DistanceOnEarth(pos, kTestGeometry[currentTurnIndex]);
|
||||
double const secondSegLenM =
|
||||
mercator::DistanceOnEarth(kTestGeometry[currentTurnIndex], kTestGeometry[nextTurnIndex]);
|
||||
TEST_EQUAL(turnsDist[0].m_turnItem, kTestTurns[currentTurnIndex - 1], ());
|
||||
TEST_EQUAL(turnsDist[1].m_turnItem, kTestTurns[nextTurnIndex - 1], ());
|
||||
TEST_ALMOST_EQUAL_ABS(turnsDist[0].m_distMeters, firstSegLenM, 0.1, ());
|
||||
TEST_ALMOST_EQUAL_ABS(turnsDist[1].m_distMeters, firstSegLenM + secondSegLenM, 0.1, ());
|
||||
}
|
||||
{
|
||||
// Move between points 1 and 2.
|
||||
auto const pos = (kTestGeometry[1] + kTestGeometry[2]) / 2;
|
||||
route.MoveIterator(GetGps(pos.x, pos.y));
|
||||
|
||||
size_t const currentTurnIndex = 2;
|
||||
size_t const nextTurnIndex = 3;
|
||||
TEST(route.GetNextTurns(turnsDist), ());
|
||||
TEST_EQUAL(turnsDist.size(), 2, ());
|
||||
double const firstSegLenM = mercator::DistanceOnEarth(pos, kTestGeometry[currentTurnIndex]);
|
||||
double const secondSegLenM =
|
||||
mercator::DistanceOnEarth(kTestGeometry[currentTurnIndex], kTestGeometry[nextTurnIndex]);
|
||||
TEST_EQUAL(turnsDist[0].m_turnItem, kTestTurns[currentTurnIndex - 1], ());
|
||||
TEST_EQUAL(turnsDist[1].m_turnItem, kTestTurns[nextTurnIndex - 1], ());
|
||||
TEST_ALMOST_EQUAL_ABS(turnsDist[0].m_distMeters, firstSegLenM, 0.1, ());
|
||||
TEST_ALMOST_EQUAL_ABS(turnsDist[1].m_distMeters, firstSegLenM + secondSegLenM, 0.1, ());
|
||||
}
|
||||
{
|
||||
// Move between points 2 and 3.
|
||||
auto const pos = (kTestGeometry[2] + kTestGeometry[3]) / 2;
|
||||
route.MoveIterator(GetGps(pos.x, pos.y));
|
||||
|
||||
size_t const currentTurnIndex = 3;
|
||||
size_t const nextTurnIndex = 5; // Turn with m_index == 4 is None.
|
||||
TEST(route.GetNextTurns(turnsDist), ());
|
||||
TEST_EQUAL(turnsDist.size(), 2, ());
|
||||
double const firstSegLenM = mercator::DistanceOnEarth(pos, kTestGeometry[currentTurnIndex]);
|
||||
double const secondSegLenM =
|
||||
mercator::DistanceOnEarth(kTestGeometry[currentTurnIndex], kTestGeometry[nextTurnIndex]);
|
||||
TEST_EQUAL(turnsDist[0].m_turnItem, kTestTurns[currentTurnIndex - 1], ());
|
||||
TEST_EQUAL(turnsDist[1].m_turnItem, kTestTurns[nextTurnIndex - 1], ());
|
||||
TEST_ALMOST_EQUAL_ABS(turnsDist[0].m_distMeters, firstSegLenM, 0.1, ());
|
||||
TEST_ALMOST_EQUAL_ABS(turnsDist[1].m_distMeters, firstSegLenM + secondSegLenM, 0.1, ());
|
||||
}
|
||||
{
|
||||
// Move between points 3 and 4.
|
||||
auto const pos = (kTestGeometry[3] + kTestGeometry[4]) / 2;
|
||||
route.MoveIterator(GetGps(pos.x, pos.y));
|
||||
|
||||
size_t const currentTurnIndex = 5; // Turn with m_index == 4 is None.
|
||||
// nextTurn is absent.
|
||||
TEST(route.GetNextTurns(turnsDist), ());
|
||||
double const firstSegLenM = mercator::DistanceOnEarth(pos, kTestGeometry[currentTurnIndex]);
|
||||
TEST_EQUAL(turnsDist[0].m_turnItem, kTestTurns[currentTurnIndex - 1], ());
|
||||
TEST_ALMOST_EQUAL_ABS(turnsDist[0].m_distMeters, firstSegLenM, 0.1, ());
|
||||
}
|
||||
}
|
||||
|
||||
// 0.0002 *--------*
|
||||
// | |
|
||||
// | |
|
||||
// Finish | |
|
||||
// 0.0001 *----------------*
|
||||
// |
|
||||
// |
|
||||
// |
|
||||
// 0 * Start
|
||||
// 0 0.0001 0.0002
|
||||
//
|
||||
UNIT_TEST(SelfIntersectedRouteMatchingTest)
|
||||
{
|
||||
vector<m2::PointD> const kRouteGeometry = {{0.0001, 0.0}, {0.0001, 0.0}, {0.0001, 0.0002},
|
||||
{0.0002, 0.0002}, {0.0002, 0.0001}, {0.0, 0.0001}};
|
||||
double constexpr kRoundingErrorMeters = 0.001;
|
||||
|
||||
Route route("TestRouter", 0 /* route id */);
|
||||
route.SetGeometry(kRouteGeometry.begin(), kRouteGeometry.end());
|
||||
|
||||
vector<RouteSegment> routeSegments;
|
||||
GetTestRouteSegments(kRouteGeometry, {}, {}, {}, routeSegments);
|
||||
route.SetRouteSegments(std::move(routeSegments));
|
||||
|
||||
auto const testMachedPos =
|
||||
[&](location::GpsInfo const & pos, location::GpsInfo const & expectedMatchingPos, size_t expectedIndexInRoute)
|
||||
{
|
||||
location::RouteMatchingInfo routeMatchingInfo;
|
||||
route.MoveIterator(pos);
|
||||
location::GpsInfo matchedPos = pos;
|
||||
route.MatchLocationToRoute(matchedPos, routeMatchingInfo);
|
||||
TEST_LESS(mercator::DistanceOnEarth(m2::PointD(matchedPos.m_latitude, matchedPos.m_longitude),
|
||||
m2::PointD(expectedMatchingPos.m_latitude, expectedMatchingPos.m_longitude)),
|
||||
kRoundingErrorMeters, ());
|
||||
TEST_EQUAL(max(size_t(1), routeMatchingInfo.GetIndexInRoute()), expectedIndexInRoute, ());
|
||||
};
|
||||
|
||||
// Moving along the route from start point.
|
||||
location::GpsInfo const pos1(GetGps(0.0001, 0.0));
|
||||
testMachedPos(pos1, pos1, 1 /* expectedIndexInRoute */);
|
||||
location::GpsInfo const pos2(GetGps(0.0001, 0.00005));
|
||||
testMachedPos(pos2, pos2, 1 /* expectedIndexInRoute */);
|
||||
|
||||
// Moving around the self intersection and checking that position is matched to the first segment of the route.
|
||||
location::GpsInfo const selfIntersectionPos(GetGps(0.0001, 0.0001));
|
||||
location::GpsInfo const pos3(GetGps(0.00005, 0.0001));
|
||||
testMachedPos(pos3, selfIntersectionPos, 1 /* expectedIndexInRoute */);
|
||||
location::GpsInfo const pos4(GetGps(0.00015, 0.0001));
|
||||
testMachedPos(pos4, selfIntersectionPos, 1 /* expectedIndexInRoute */);
|
||||
|
||||
// Continue moving along the route.
|
||||
location::GpsInfo const pos5(GetGps(0.00011, 0.0002));
|
||||
testMachedPos(pos5, pos5, 2 /* expectedIndexInRoute */);
|
||||
location::GpsInfo const pos6(GetGps(0.0002, 0.00019));
|
||||
testMachedPos(pos6, pos6, 3 /* expectedIndexInRoute */);
|
||||
location::GpsInfo const pos7(GetGps(0.00019, 0.0001));
|
||||
testMachedPos(pos7, pos7, 4 /* expectedIndexInRoute */);
|
||||
|
||||
// Moving around the self intersection and checking that position is matched to the last segment of the route.
|
||||
location::GpsInfo const pos8(GetGps(0.0001, 0.00005));
|
||||
testMachedPos(pos8, selfIntersectionPos, 4 /* expectedIndexInRoute */);
|
||||
location::GpsInfo const pos9(GetGps(0.0001, 0.00015));
|
||||
testMachedPos(pos9, selfIntersectionPos, 4 /* expectedIndexInRoute */);
|
||||
}
|
||||
|
||||
UNIT_TEST(RouteNameTest)
|
||||
{
|
||||
Route route("TestRouter", 0 /* route id */);
|
||||
|
||||
route.SetGeometry(kTestGeometry.begin(), kTestGeometry.end());
|
||||
vector<RouteSegment> routeSegments;
|
||||
GetTestRouteSegments(kTestGeometry, kTestTurns, kTestNames, {}, routeSegments);
|
||||
route.SetRouteSegments(std::move(routeSegments));
|
||||
|
||||
RouteSegment::RoadNameInfo roadNameInfo;
|
||||
route.GetCurrentStreetName(roadNameInfo);
|
||||
TEST_EQUAL(roadNameInfo.m_name, "Street0", (roadNameInfo.m_name));
|
||||
|
||||
route.GetClosestStreetNameAfterIdx(1, roadNameInfo);
|
||||
TEST_EQUAL(roadNameInfo.m_name, "Street1", (roadNameInfo.m_name));
|
||||
|
||||
route.GetClosestStreetNameAfterIdx(2, roadNameInfo);
|
||||
TEST_EQUAL(roadNameInfo.m_name, "Street2", (roadNameInfo.m_name));
|
||||
|
||||
route.GetClosestStreetNameAfterIdx(3, roadNameInfo);
|
||||
TEST_EQUAL(roadNameInfo.m_name, "Street3", (roadNameInfo.m_name));
|
||||
|
||||
route.GetClosestStreetNameAfterIdx(4, roadNameInfo);
|
||||
TEST_EQUAL(roadNameInfo.m_name, "Street3", (roadNameInfo.m_name));
|
||||
|
||||
location::GpsInfo const pos(GetGps(1.0, 2.0));
|
||||
route.MoveIterator(pos);
|
||||
route.GetCurrentStreetName(roadNameInfo);
|
||||
TEST_EQUAL(roadNameInfo.m_name, "Street2", (roadNameInfo.m_name));
|
||||
}
|
||||
} // namespace route_tests
|
||||
196
libs/routing/routing_tests/routing_algorithm.cpp
Normal file
196
libs/routing/routing_tests/routing_algorithm.cpp
Normal file
|
|
@ -0,0 +1,196 @@
|
|||
#include "routing/routing_tests/routing_algorithm.hpp"
|
||||
|
||||
#include "routing/base/astar_algorithm.hpp"
|
||||
#include "routing/base/astar_graph.hpp"
|
||||
|
||||
#include "routing/maxspeeds.hpp"
|
||||
#include "routing/routing_helpers.hpp"
|
||||
|
||||
#include "geometry/mercator.hpp"
|
||||
|
||||
#include "base/assert.hpp"
|
||||
|
||||
#include <cmath>
|
||||
#include <cstdint>
|
||||
#include <vector>
|
||||
|
||||
namespace routing_test
|
||||
{
|
||||
void UndirectedGraph::AddEdge(Vertex u, Vertex v, Weight w)
|
||||
{
|
||||
m_adjs[u].emplace_back(v, w);
|
||||
m_adjs[v].emplace_back(u, w);
|
||||
}
|
||||
|
||||
size_t UndirectedGraph::GetNodesNumber() const
|
||||
{
|
||||
return m_adjs.size();
|
||||
}
|
||||
|
||||
void UndirectedGraph::GetEdgesList(Vertex const & vertex, bool /* isOutgoing */, EdgeListT & adj)
|
||||
{
|
||||
GetAdjacencyList(vertex, adj);
|
||||
}
|
||||
|
||||
void UndirectedGraph::GetIngoingEdgesList(astar::VertexData<Vertex, Weight> const & vertexData, EdgeListT & adj)
|
||||
{
|
||||
GetEdgesList(vertexData.m_vertex, false /* isOutgoing */, adj);
|
||||
}
|
||||
|
||||
void UndirectedGraph::GetOutgoingEdgesList(astar::VertexData<Vertex, Weight> const & vertexData, EdgeListT & adj)
|
||||
{
|
||||
GetEdgesList(vertexData.m_vertex, true /* isOutgoing */, adj);
|
||||
}
|
||||
|
||||
double UndirectedGraph::HeuristicCostEstimate(Vertex const & v, Vertex const & w)
|
||||
{
|
||||
return 0.0;
|
||||
}
|
||||
|
||||
void UndirectedGraph::GetAdjacencyList(Vertex v, EdgeListT & adj) const
|
||||
{
|
||||
adj.clear();
|
||||
auto const it = m_adjs.find(v);
|
||||
if (it != m_adjs.cend())
|
||||
adj = it->second;
|
||||
}
|
||||
|
||||
void DirectedGraph::AddEdge(Vertex from, Vertex to, Weight w)
|
||||
{
|
||||
m_outgoing[from].emplace_back(to, w);
|
||||
m_ingoing[to].emplace_back(from, w);
|
||||
}
|
||||
|
||||
void DirectedGraph::GetEdgesList(Vertex const & v, bool isOutgoing, EdgeListT & adj)
|
||||
{
|
||||
adj = isOutgoing ? m_outgoing[v] : m_ingoing[v];
|
||||
}
|
||||
|
||||
namespace
|
||||
{
|
||||
inline double TimeBetweenSec(geometry::PointWithAltitude const & j1, geometry::PointWithAltitude const & j2,
|
||||
double speedMPS)
|
||||
{
|
||||
ASSERT(speedMPS > 0.0, ());
|
||||
ASSERT_NOT_EQUAL(j1.GetAltitude(), geometry::kInvalidAltitude, ());
|
||||
ASSERT_NOT_EQUAL(j2.GetAltitude(), geometry::kInvalidAltitude, ());
|
||||
|
||||
double const distanceM = mercator::DistanceOnEarth(j1.GetPoint(), j2.GetPoint());
|
||||
double const altitudeDiffM = static_cast<double>(j2.GetAltitude()) - static_cast<double>(j1.GetAltitude());
|
||||
return std::sqrt(distanceM * distanceM + altitudeDiffM * altitudeDiffM) / speedMPS;
|
||||
}
|
||||
|
||||
/// A class which represents an weighted edge used by RoadGraph.
|
||||
class WeightedEdge
|
||||
{
|
||||
public:
|
||||
WeightedEdge() = default; // needed for buffer_vector only
|
||||
WeightedEdge(geometry::PointWithAltitude const & target, double weight) : target(target), weight(weight) {}
|
||||
|
||||
inline geometry::PointWithAltitude const & GetTarget() const { return target; }
|
||||
inline double GetWeight() const { return weight; }
|
||||
|
||||
private:
|
||||
geometry::PointWithAltitude target;
|
||||
double weight;
|
||||
};
|
||||
|
||||
using Algorithm = AStarAlgorithm<geometry::PointWithAltitude, WeightedEdge, double>;
|
||||
|
||||
/// A wrapper around IRoadGraph, which makes it possible to use IRoadGraph with astar algorithms.
|
||||
class RoadGraph : public Algorithm::Graph
|
||||
{
|
||||
public:
|
||||
explicit RoadGraph(RoadGraphIFace const & roadGraph)
|
||||
: m_roadGraph(roadGraph)
|
||||
, m_maxSpeedMPS(measurement_utils::KmphToMps(roadGraph.GetMaxSpeedKMpH()))
|
||||
{}
|
||||
|
||||
void GetOutgoingEdgesList(astar::VertexData<Vertex, Weight> const & vertexData, EdgeListT & adj) override
|
||||
{
|
||||
auto const & v = vertexData.m_vertex;
|
||||
IRoadGraph::EdgeListT edges;
|
||||
m_roadGraph.GetOutgoingEdges(v, edges);
|
||||
|
||||
adj.clear();
|
||||
adj.reserve(edges.size());
|
||||
|
||||
for (auto const & e : edges)
|
||||
{
|
||||
ASSERT_EQUAL(v, e.GetStartJunction(), ());
|
||||
|
||||
double const speedMPS = measurement_utils::KmphToMps(
|
||||
m_roadGraph.GetSpeedKMpH(e, {true /* forward */, false /* in city */, Maxspeed()}));
|
||||
adj.emplace_back(e.GetEndJunction(), TimeBetweenSec(e.GetStartJunction(), e.GetEndJunction(), speedMPS));
|
||||
}
|
||||
}
|
||||
|
||||
void GetIngoingEdgesList(astar::VertexData<Vertex, Weight> const & vertexData, EdgeListT & adj) override
|
||||
{
|
||||
auto const & v = vertexData.m_vertex;
|
||||
IRoadGraph::EdgeListT edges;
|
||||
m_roadGraph.GetIngoingEdges(v, edges);
|
||||
|
||||
adj.clear();
|
||||
adj.reserve(edges.size());
|
||||
|
||||
for (auto const & e : edges)
|
||||
{
|
||||
ASSERT_EQUAL(v, e.GetEndJunction(), ());
|
||||
|
||||
double const speedMPS = measurement_utils::KmphToMps(
|
||||
m_roadGraph.GetSpeedKMpH(e, {true /* forward */, false /* in city */, Maxspeed()}));
|
||||
adj.emplace_back(e.GetStartJunction(), TimeBetweenSec(e.GetStartJunction(), e.GetEndJunction(), speedMPS));
|
||||
}
|
||||
}
|
||||
|
||||
double HeuristicCostEstimate(Vertex const & v, Vertex const & w) override
|
||||
{
|
||||
return TimeBetweenSec(v, w, m_maxSpeedMPS);
|
||||
}
|
||||
|
||||
private:
|
||||
RoadGraphIFace const & m_roadGraph;
|
||||
double const m_maxSpeedMPS;
|
||||
};
|
||||
|
||||
TestAStarBidirectionalAlgo::Result Convert(Algorithm::Result value)
|
||||
{
|
||||
switch (value)
|
||||
{
|
||||
case Algorithm::Result::OK: return TestAStarBidirectionalAlgo::Result::OK;
|
||||
case Algorithm::Result::NoPath: return TestAStarBidirectionalAlgo::Result::NoPath;
|
||||
case Algorithm::Result::Cancelled: return TestAStarBidirectionalAlgo::Result::Cancelled;
|
||||
}
|
||||
|
||||
UNREACHABLE();
|
||||
return TestAStarBidirectionalAlgo::Result::NoPath;
|
||||
}
|
||||
} // namespace
|
||||
|
||||
std::string DebugPrint(TestAStarBidirectionalAlgo::Result const & value)
|
||||
{
|
||||
switch (value)
|
||||
{
|
||||
case TestAStarBidirectionalAlgo::Result::OK: return "OK";
|
||||
case TestAStarBidirectionalAlgo::Result::NoPath: return "NoPath";
|
||||
case TestAStarBidirectionalAlgo::Result::Cancelled: return "Cancelled";
|
||||
}
|
||||
|
||||
UNREACHABLE();
|
||||
return std::string();
|
||||
}
|
||||
|
||||
// *************************** AStar-bidirectional routing algorithm implementation ***********************
|
||||
TestAStarBidirectionalAlgo::Result TestAStarBidirectionalAlgo::CalculateRoute(
|
||||
RoadGraphIFace const & graph, geometry::PointWithAltitude const & startPos,
|
||||
geometry::PointWithAltitude const & finalPos, RoutingResult<IRoadGraph::Vertex, IRoadGraph::Weight> & path)
|
||||
{
|
||||
RoadGraph roadGraph(graph);
|
||||
base::Cancellable cancellable;
|
||||
Algorithm::Params<> params(roadGraph, startPos, finalPos, cancellable);
|
||||
|
||||
Algorithm::Result const res = Algorithm().FindPathBidirectional(params, path);
|
||||
return Convert(res);
|
||||
}
|
||||
} // namespace routing_test
|
||||
101
libs/routing/routing_tests/routing_algorithm.hpp
Normal file
101
libs/routing/routing_tests/routing_algorithm.hpp
Normal file
|
|
@ -0,0 +1,101 @@
|
|||
#pragma once
|
||||
|
||||
#include "routing/base/astar_graph.hpp"
|
||||
#include "routing/base/routing_result.hpp"
|
||||
|
||||
#include "routing/road_graph.hpp"
|
||||
|
||||
#include "routing_common/vehicle_model.hpp"
|
||||
|
||||
#include "geometry/point_with_altitude.hpp"
|
||||
|
||||
#include <map>
|
||||
#include <string>
|
||||
|
||||
namespace routing_test
|
||||
{
|
||||
using namespace routing;
|
||||
|
||||
struct SimpleEdge
|
||||
{
|
||||
SimpleEdge() = default; // needed for buffer_vector only
|
||||
SimpleEdge(uint32_t to, double weight) : m_to(to), m_weight(weight) {}
|
||||
|
||||
uint32_t GetTarget() const { return m_to; }
|
||||
double GetWeight() const { return m_weight; }
|
||||
|
||||
uint32_t m_to;
|
||||
double m_weight;
|
||||
};
|
||||
|
||||
class RoadGraphIFace : public IRoadGraph
|
||||
{
|
||||
public:
|
||||
virtual RoadInfo GetRoadInfo(FeatureID const & f, SpeedParams const & speedParams) const = 0;
|
||||
virtual double GetSpeedKMpH(FeatureID const & featureId, SpeedParams const & speedParams) const = 0;
|
||||
virtual double GetMaxSpeedKMpH() const = 0;
|
||||
|
||||
double GetSpeedKMpH(Edge const & edge, SpeedParams const & speedParams) const
|
||||
{
|
||||
double const speedKMpH = (edge.IsFake() ? GetMaxSpeedKMpH() : GetSpeedKMpH(edge.GetFeatureId(), speedParams));
|
||||
ASSERT_LESS_OR_EQUAL(speedKMpH, GetMaxSpeedKMpH(), ());
|
||||
return speedKMpH;
|
||||
}
|
||||
};
|
||||
|
||||
class UndirectedGraph : public AStarGraph<uint32_t, SimpleEdge, double>
|
||||
{
|
||||
public:
|
||||
void AddEdge(Vertex u, Vertex v, Weight w);
|
||||
size_t GetNodesNumber() const;
|
||||
|
||||
// AStarGraph overrides
|
||||
// @{
|
||||
void GetIngoingEdgesList(astar::VertexData<Vertex, Weight> const & vertexData, EdgeListT & adj) override;
|
||||
void GetOutgoingEdgesList(astar::VertexData<Vertex, Weight> const & vertexData, EdgeListT & adj) override;
|
||||
double HeuristicCostEstimate(Vertex const & v, Vertex const & w) override;
|
||||
// @}
|
||||
|
||||
void GetEdgesList(Vertex const & vertex, bool /* isOutgoing */, EdgeListT & adj);
|
||||
|
||||
private:
|
||||
void GetAdjacencyList(Vertex v, EdgeListT & adj) const;
|
||||
|
||||
std::map<uint32_t, EdgeListT> m_adjs;
|
||||
};
|
||||
|
||||
class DirectedGraph
|
||||
{
|
||||
public:
|
||||
using Vertex = uint32_t;
|
||||
using Edge = SimpleEdge;
|
||||
using Weight = double;
|
||||
|
||||
using EdgeListT = SmallList<SimpleEdge>;
|
||||
|
||||
void AddEdge(Vertex from, Vertex to, Weight w);
|
||||
|
||||
void GetEdgesList(Vertex const & v, bool isOutgoing, EdgeListT & adj);
|
||||
|
||||
private:
|
||||
std::map<uint32_t, EdgeListT> m_outgoing;
|
||||
std::map<uint32_t, EdgeListT> m_ingoing;
|
||||
};
|
||||
|
||||
class TestAStarBidirectionalAlgo
|
||||
{
|
||||
public:
|
||||
enum class Result
|
||||
{
|
||||
OK,
|
||||
NoPath,
|
||||
Cancelled
|
||||
};
|
||||
|
||||
Result CalculateRoute(RoadGraphIFace const & graph, geometry::PointWithAltitude const & startPos,
|
||||
geometry::PointWithAltitude const & finalPos,
|
||||
RoutingResult<IRoadGraph::Vertex, IRoadGraph::Weight> & path);
|
||||
};
|
||||
|
||||
std::string DebugPrint(TestAStarBidirectionalAlgo::Result const & result);
|
||||
} // namespace routing_test
|
||||
137
libs/routing/routing_tests/routing_helpers_tests.cpp
Normal file
137
libs/routing/routing_tests/routing_helpers_tests.cpp
Normal file
|
|
@ -0,0 +1,137 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/road_graph.hpp"
|
||||
#include "routing/route.hpp"
|
||||
#include "routing/routing_helpers.hpp"
|
||||
#include "routing/segment.hpp"
|
||||
#include "routing/turns.hpp"
|
||||
|
||||
#include "routing/routing_tests/tools.hpp"
|
||||
|
||||
#include "indexer/feature_altitude.hpp"
|
||||
|
||||
#include "geometry/point2d.hpp"
|
||||
#include "geometry/point_with_altitude.hpp"
|
||||
#include "geometry/rect2d.hpp"
|
||||
|
||||
#include <vector>
|
||||
|
||||
namespace routing_test
|
||||
{
|
||||
using namespace routing::turns;
|
||||
using namespace routing;
|
||||
using namespace std;
|
||||
|
||||
UNIT_TEST(FillSegmentInfoSmokeTest)
|
||||
{
|
||||
vector<Segment> const segments = {{0 /* mwmId */, 1 /* featureId */, 0 /* segmentIdx */, true /* forward */}};
|
||||
vector<m2::PointD> const junctions = {m2::PointD(0.0 /* x */, 0.0 /* y */), m2::PointD(0.0 /* x */, 0.0 /* y */)};
|
||||
vector<turns::TurnItem> const & turnDirs = {{1 /* point index */, CarDirection::ReachedYourDestination}};
|
||||
vector<double> const times = {1.0};
|
||||
|
||||
vector<RouteSegment> routeSegments;
|
||||
RouteSegmentsFrom(segments, junctions, turnDirs, {}, routeSegments);
|
||||
FillSegmentInfo(times, routeSegments);
|
||||
|
||||
TEST_EQUAL(routeSegments.size(), 1, ());
|
||||
TEST_EQUAL(routeSegments[0].GetTurn().m_turn, CarDirection::ReachedYourDestination, ());
|
||||
TEST(routeSegments[0].GetRoadNameInfo().m_name.empty(), ());
|
||||
}
|
||||
|
||||
UNIT_TEST(FillSegmentInfoTest)
|
||||
{
|
||||
vector<Segment> const segments = {
|
||||
{0 /* mwmId */, 1 /* featureId */, 0 /* segmentIdx */, true /* forward */}, {0, 2, 0, true}, {0, 3, 0, true}};
|
||||
vector<m2::PointD> const junctions = {m2::PointD(0.0 /* x */, 0.0 /* y */), m2::PointD(0.0 /* x */, 0.0 /* y */),
|
||||
m2::PointD(0.1 /* x */, 0.0 /* y */), m2::PointD(0.2 /* x */, 0.0 /* y */)};
|
||||
vector<turns::TurnItem> const & turnDirs = {{1 /* point index */, CarDirection::None},
|
||||
{2 /* point index */, CarDirection::TurnRight},
|
||||
{3 /* point index */, CarDirection::ReachedYourDestination}};
|
||||
vector<RouteSegment::RoadNameInfo> const streets = {
|
||||
{"zero", "", "", "", "", false}, {"first", "", "", "", "", false}, {"second", "", "", "", "", false}};
|
||||
vector<double> const times = {1.0, 2.0, 3.0};
|
||||
|
||||
vector<RouteSegment> segmentInfo;
|
||||
RouteSegmentsFrom(segments, junctions, turnDirs, streets, segmentInfo);
|
||||
FillSegmentInfo(times, segmentInfo);
|
||||
|
||||
TEST_EQUAL(segmentInfo.size(), 3, ());
|
||||
TEST_EQUAL(segmentInfo[1].GetTurn().m_turn, CarDirection::TurnRight, ());
|
||||
TEST_EQUAL(segmentInfo[1].GetRoadNameInfo().m_name, string("first"), ());
|
||||
TEST_EQUAL(segmentInfo[0].GetSegment(), segments[0], ());
|
||||
|
||||
TEST_EQUAL(segmentInfo[2].GetTurn().m_turn, CarDirection::ReachedYourDestination, ());
|
||||
TEST_EQUAL(segmentInfo[2].GetRoadNameInfo().m_name, string("second"), ());
|
||||
TEST_EQUAL(segmentInfo[1].GetSegment(), segments[1], ());
|
||||
}
|
||||
|
||||
UNIT_TEST(PolylineInRectTest)
|
||||
{
|
||||
// Empty polyline.
|
||||
TEST(!RectCoversPolyline({}, m2::RectD()), ());
|
||||
TEST(!RectCoversPolyline({}, m2::RectD(0.0, 0.0, 2.0, 2.0)), ());
|
||||
|
||||
// One point polyline outside the rect.
|
||||
{
|
||||
auto const junctions = IRoadGraph::PointWithAltitudeVec({{m2::PointD(3.0, 3.0), 0 /* altitude */}});
|
||||
TEST(!RectCoversPolyline(junctions, m2::RectD(0.0, 0.0, 2.0, 2.0)), ());
|
||||
}
|
||||
|
||||
// One point polyline inside the rect.
|
||||
{
|
||||
auto const junctions = IRoadGraph::PointWithAltitudeVec({{m2::PointD(1.0, 1.0), 0 /* altitude */}});
|
||||
TEST(RectCoversPolyline(junctions, m2::RectD(0.0, 0.0, 2.0, 2.0)), ());
|
||||
}
|
||||
|
||||
// One point polyline on the rect border.
|
||||
{
|
||||
auto const junctions = IRoadGraph::PointWithAltitudeVec({{m2::PointD(0.0, 0.0), 0 /* altitude */}});
|
||||
TEST(RectCoversPolyline(junctions, m2::RectD(0.0, 0.0, 2.0, 2.0)), ());
|
||||
}
|
||||
|
||||
// Two point polyline touching the rect border.
|
||||
{
|
||||
auto const junctions = IRoadGraph::PointWithAltitudeVec({
|
||||
{m2::PointD(-1.0, -1.0), 0 /* altitude */},
|
||||
{m2::PointD(0.0, 0.0), 0 /* altitude */},
|
||||
});
|
||||
TEST(RectCoversPolyline(junctions, m2::RectD(0.0, 0.0, 2.0, 2.0)), ());
|
||||
}
|
||||
|
||||
// Crossing rect by a segment but no polyline points inside the rect.
|
||||
{
|
||||
auto const junctions = IRoadGraph::PointWithAltitudeVec({
|
||||
{m2::PointD(-1.0, -1.0), 0 /* altitude */},
|
||||
{m2::PointD(5.0, 5.0), 0 /* altitude */},
|
||||
});
|
||||
TEST(RectCoversPolyline(junctions, m2::RectD(0.0, 0.0, 2.0, 2.0)), ());
|
||||
}
|
||||
|
||||
{
|
||||
auto const junctions = IRoadGraph::PointWithAltitudeVec({
|
||||
{m2::PointD(0.0, 1.0), 0 /* altitude */},
|
||||
{m2::PointD(100.0, 2.0), 0 /* altitude */},
|
||||
});
|
||||
TEST(RectCoversPolyline(junctions, m2::RectD(0.0, 0.0, 100.0, 1.0)), ());
|
||||
}
|
||||
|
||||
// Crossing a rect very close to a corner.
|
||||
{
|
||||
auto const junctions = IRoadGraph::PointWithAltitudeVec({
|
||||
{m2::PointD(-1.0, 0.0), 0 /* altitude */},
|
||||
{m2::PointD(1.0, 1.9), 0 /* altitude */},
|
||||
});
|
||||
TEST(RectCoversPolyline(junctions, m2::RectD(0.0, 0.0, 1.0, 1.0)), ());
|
||||
}
|
||||
|
||||
// Three point polyline crossing the rect.
|
||||
{
|
||||
auto const junctions = IRoadGraph::PointWithAltitudeVec({
|
||||
{m2::PointD(0.0, -1.0), 0 /* altitude */},
|
||||
{m2::PointD(1.0, 0.01), 0 /* altitude */},
|
||||
{m2::PointD(2.0, -1.0), 0 /* altitude */},
|
||||
});
|
||||
TEST(RectCoversPolyline(junctions, m2::RectD(0.0, 0.0, 1.0, 1.0)), ());
|
||||
}
|
||||
}
|
||||
} // namespace routing_test
|
||||
78
libs/routing/routing_tests/routing_options_tests.cpp
Normal file
78
libs/routing/routing_tests/routing_options_tests.cpp
Normal file
|
|
@ -0,0 +1,78 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/routing_options.hpp"
|
||||
|
||||
#include <cstdint>
|
||||
#include <vector>
|
||||
|
||||
using namespace routing;
|
||||
|
||||
namespace
|
||||
{
|
||||
using RoadType = RoutingOptions::RoadType;
|
||||
|
||||
class RoutingOptionsTests
|
||||
{
|
||||
public:
|
||||
RoutingOptionsTests() { m_savedOptions = RoutingOptions::LoadCarOptionsFromSettings(); }
|
||||
|
||||
~RoutingOptionsTests() { RoutingOptions::SaveCarOptionsToSettings(m_savedOptions); }
|
||||
|
||||
private:
|
||||
RoutingOptions m_savedOptions;
|
||||
};
|
||||
|
||||
RoutingOptions CreateOptions(std::vector<RoutingOptions::Road> const & include)
|
||||
{
|
||||
RoutingOptions options;
|
||||
|
||||
for (auto type : include)
|
||||
options.Add(type);
|
||||
|
||||
return options;
|
||||
}
|
||||
|
||||
void Checker(std::vector<RoutingOptions::Road> const & include)
|
||||
{
|
||||
RoutingOptions options = CreateOptions(include);
|
||||
|
||||
for (auto type : include)
|
||||
TEST(options.Has(type), ());
|
||||
|
||||
auto max = static_cast<RoadType>(RoutingOptions::Road::Max);
|
||||
for (uint8_t i = 1; i < max; i <<= 1)
|
||||
{
|
||||
bool hasInclude = false;
|
||||
auto type = static_cast<RoutingOptions::Road>(i);
|
||||
for (auto has : include)
|
||||
hasInclude |= (type == has);
|
||||
|
||||
if (!hasInclude)
|
||||
TEST(!options.Has(static_cast<RoutingOptions::Road>(i)), ());
|
||||
}
|
||||
}
|
||||
|
||||
UNIT_TEST(RoutingOptionTest)
|
||||
{
|
||||
Checker({RoutingOptions::Road::Toll, RoutingOptions::Road::Motorway, RoutingOptions::Road::Dirty});
|
||||
Checker({RoutingOptions::Road::Toll, RoutingOptions::Road::Dirty});
|
||||
|
||||
Checker({RoutingOptions::Road::Toll, RoutingOptions::Road::Ferry, RoutingOptions::Road::Dirty});
|
||||
|
||||
Checker({RoutingOptions::Road::Dirty});
|
||||
Checker({RoutingOptions::Road::Toll});
|
||||
Checker({RoutingOptions::Road::Dirty, RoutingOptions::Road::Motorway});
|
||||
Checker({});
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(RoutingOptionsTests, GetSetTest)
|
||||
{
|
||||
RoutingOptions options =
|
||||
CreateOptions({RoutingOptions::Road::Toll, RoutingOptions::Road::Motorway, RoutingOptions::Road::Dirty});
|
||||
|
||||
RoutingOptions::SaveCarOptionsToSettings(options);
|
||||
RoutingOptions fromSettings = RoutingOptions::LoadCarOptionsFromSettings();
|
||||
|
||||
TEST_EQUAL(options.GetOptions(), fromSettings.GetOptions(), ());
|
||||
}
|
||||
} // namespace
|
||||
611
libs/routing/routing_tests/routing_session_test.cpp
Normal file
611
libs/routing/routing_tests/routing_session_test.cpp
Normal file
|
|
@ -0,0 +1,611 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/routing_tests/tools.hpp"
|
||||
|
||||
#include "routing/route.hpp"
|
||||
#include "routing/router.hpp"
|
||||
#include "routing/routing_callbacks.hpp"
|
||||
#include "routing/routing_helpers.hpp"
|
||||
#include "routing/routing_session.hpp"
|
||||
|
||||
#include "geometry/point2d.hpp"
|
||||
#include "geometry/point_with_altitude.hpp"
|
||||
|
||||
#include "base/logging.hpp"
|
||||
|
||||
#include <chrono>
|
||||
#include <initializer_list>
|
||||
#include <memory>
|
||||
#include <mutex>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
namespace routing_session_test
|
||||
{
|
||||
using namespace routing;
|
||||
using namespace std;
|
||||
|
||||
using chrono::seconds;
|
||||
using chrono::steady_clock;
|
||||
|
||||
vector<m2::PointD> kTestRoute = {{0., 1.}, {0., 1.}, {0., 3.}, {0., 4.}};
|
||||
vector<Segment> const kTestSegments = {{0, 0, 0, true}, {0, 0, 1, true}, {0, 0, 2, true}};
|
||||
vector<turns::TurnItem> const kTestTurnsReachOnly = {turns::TurnItem(1, turns::CarDirection::None),
|
||||
turns::TurnItem(2, turns::CarDirection::None),
|
||||
turns::TurnItem(3, turns::CarDirection::ReachedYourDestination)};
|
||||
vector<turns::TurnItem> const kTestTurns = {turns::TurnItem(1, turns::CarDirection::None),
|
||||
turns::TurnItem(2, turns::CarDirection::TurnLeft),
|
||||
turns::TurnItem(3, turns::CarDirection::ReachedYourDestination)};
|
||||
vector<double> const kTestTimes = {5.0, 10.0, 15.0};
|
||||
auto const kRouteBuildingMaxDuration = seconds(30);
|
||||
|
||||
void FillSubroutesInfo(Route & route, vector<turns::TurnItem> const & turns = kTestTurnsReachOnly);
|
||||
|
||||
// Simple router. It returns route given to him on creation.
|
||||
class DummyRouter : public IRouter
|
||||
{
|
||||
private:
|
||||
Route m_route;
|
||||
RouterResultCode m_code;
|
||||
size_t & m_buildCount;
|
||||
|
||||
public:
|
||||
DummyRouter(Route & route, RouterResultCode code, size_t & buildCounter)
|
||||
: m_route(route)
|
||||
, m_code(code)
|
||||
, m_buildCount(buildCounter)
|
||||
{}
|
||||
|
||||
string GetName() const override { return "dummy"; }
|
||||
void ClearState() override {}
|
||||
void SetGuides(GuidesTracks && /* guides */) override {}
|
||||
|
||||
RouterResultCode CalculateRoute(Checkpoints const & /* checkpoints */, m2::PointD const & /* startDirection */,
|
||||
bool /* adjust */, RouterDelegate const & /* delegate */, Route & route) override
|
||||
{
|
||||
++m_buildCount;
|
||||
route = m_route;
|
||||
return m_code;
|
||||
}
|
||||
|
||||
bool FindClosestProjectionToRoad(m2::PointD const & point, m2::PointD const & direction, double radius,
|
||||
EdgeProj & proj) override
|
||||
{
|
||||
return false;
|
||||
}
|
||||
};
|
||||
|
||||
// Router which every next call of CalculateRoute() method return different return codes.
|
||||
class ReturnCodesRouter : public IRouter
|
||||
{
|
||||
public:
|
||||
ReturnCodesRouter(initializer_list<RouterResultCode> const & returnCodes, vector<m2::PointD> const & route)
|
||||
: m_returnCodes(returnCodes)
|
||||
, m_route(route)
|
||||
{}
|
||||
|
||||
// IRouter overrides:
|
||||
string GetName() const override { return "return codes router"; }
|
||||
void ClearState() override {}
|
||||
void SetGuides(GuidesTracks && /* guides */) override {}
|
||||
|
||||
RouterResultCode CalculateRoute(Checkpoints const & /* checkpoints */, m2::PointD const & /* startDirection */,
|
||||
bool /* adjust */, RouterDelegate const & /* delegate */, Route & route) override
|
||||
{
|
||||
TEST_LESS(m_returnCodesIdx, m_returnCodes.size(), ());
|
||||
route = Route(GetName(), m_route.begin(), m_route.end(), 0 /* route id */);
|
||||
FillSubroutesInfo(route);
|
||||
return m_returnCodes[m_returnCodesIdx++];
|
||||
}
|
||||
|
||||
bool FindClosestProjectionToRoad(m2::PointD const & point, m2::PointD const & direction, double radius,
|
||||
EdgeProj & proj) override
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
private:
|
||||
vector<RouterResultCode> m_returnCodes;
|
||||
vector<m2::PointD> m_route;
|
||||
size_t m_returnCodesIdx = 0;
|
||||
};
|
||||
|
||||
class TimedSignal
|
||||
{
|
||||
public:
|
||||
TimedSignal() : m_flag(false) {}
|
||||
void Signal()
|
||||
{
|
||||
lock_guard<mutex> guard(m_waitingMutex);
|
||||
m_flag = true;
|
||||
m_cv.notify_one();
|
||||
}
|
||||
|
||||
bool WaitUntil(steady_clock::time_point const & time)
|
||||
{
|
||||
unique_lock<mutex> lock(m_waitingMutex);
|
||||
m_cv.wait_until(lock, time, [this, &time] { return m_flag || steady_clock::now() > time; });
|
||||
return m_flag;
|
||||
}
|
||||
|
||||
private:
|
||||
mutex m_waitingMutex;
|
||||
condition_variable m_cv;
|
||||
bool m_flag;
|
||||
};
|
||||
|
||||
/// \brief This class is developed to test callback on RoutingSession::m_state changing.
|
||||
/// An new instance of the class should be constructed for every new test.
|
||||
class SessionStateTest
|
||||
{
|
||||
public:
|
||||
SessionStateTest(initializer_list<SessionState> expectedStates, RoutingSession & routingSession)
|
||||
: m_expectedStates(expectedStates)
|
||||
, m_session(routingSession)
|
||||
{
|
||||
for (size_t i = 1; i < expectedStates.size(); ++i)
|
||||
{
|
||||
// Note. Change session state callback is called only if the state is change.
|
||||
if (m_expectedStates[i - 1] != m_expectedStates[i])
|
||||
++m_expectedNumberOfStateChanging;
|
||||
}
|
||||
|
||||
TimedSignal timedSignal;
|
||||
GetPlatform().RunTask(Platform::Thread::Gui, [this, &timedSignal]()
|
||||
{
|
||||
m_session.SetChangeSessionStateCallback([this](SessionState previous, SessionState current)
|
||||
{ TestChangeSessionStateCallbackCall(previous, current); });
|
||||
timedSignal.Signal();
|
||||
});
|
||||
TEST(timedSignal.WaitUntil(steady_clock::now() + kRouteBuildingMaxDuration), ("Callback is not set."));
|
||||
}
|
||||
|
||||
~SessionStateTest()
|
||||
{
|
||||
TEST_EQUAL(m_numberOfTestCalls, m_expectedNumberOfStateChanging,
|
||||
("Wrong number of calls of SetState() callback.", m_expectedStates));
|
||||
TimedSignal timedSignal;
|
||||
GetPlatform().RunTask(Platform::Thread::Gui, [this, &timedSignal]()
|
||||
{
|
||||
m_session.SetChangeSessionStateCallback(nullptr);
|
||||
timedSignal.Signal();
|
||||
});
|
||||
TEST(timedSignal.WaitUntil(steady_clock::now() + kRouteBuildingMaxDuration), ("Callback is not set."));
|
||||
}
|
||||
|
||||
private:
|
||||
void TestChangeSessionStateCallbackCall(SessionState previous, SessionState current)
|
||||
{
|
||||
TEST_LESS(m_numberOfTestCalls + 1, m_expectedStates.size(),
|
||||
("Too many calls of the method. previous:", previous, ", current:", current));
|
||||
TEST_EQUAL(previous, m_expectedStates[m_numberOfTestCalls], (previous, current));
|
||||
TEST_EQUAL(current, m_expectedStates[m_numberOfTestCalls + 1], (previous, current));
|
||||
|
||||
++m_numberOfTestCalls;
|
||||
}
|
||||
|
||||
size_t m_numberOfTestCalls = 0;
|
||||
vector<SessionState> const m_expectedStates;
|
||||
size_t m_expectedNumberOfStateChanging = 0;
|
||||
RoutingSession & m_session;
|
||||
};
|
||||
|
||||
void FillSubroutesInfo(Route & route, vector<turns::TurnItem> const & turns /* = kTestTurnsReachOnly */)
|
||||
{
|
||||
vector<geometry::PointWithAltitude> junctions;
|
||||
for (auto const & point : kTestRoute)
|
||||
junctions.emplace_back(point, geometry::kDefaultAltitudeMeters);
|
||||
|
||||
vector<RouteSegment> segmentInfo;
|
||||
RouteSegmentsFrom(kTestSegments, kTestRoute, turns, {}, segmentInfo);
|
||||
FillSegmentInfo(kTestTimes, segmentInfo);
|
||||
route.SetRouteSegments(std::move(segmentInfo));
|
||||
route.SetSubroteAttrs(vector<Route::SubrouteAttrs>(
|
||||
{Route::SubrouteAttrs(junctions.front(), junctions.back(), 0, kTestSegments.size())}));
|
||||
}
|
||||
|
||||
void TestMovingByUpdatingLat(SessionStateTest const & sessionState, vector<double> const & lats,
|
||||
location::GpsInfo const & info, RoutingSession & session)
|
||||
{
|
||||
location::GpsInfo uptInfo(info);
|
||||
TimedSignal signal;
|
||||
GetPlatform().RunTask(Platform::Thread::Gui, [&session, &signal, &lats, &uptInfo]()
|
||||
{
|
||||
for (auto const lat : lats)
|
||||
{
|
||||
uptInfo.m_latitude = lat;
|
||||
session.OnLocationPositionChanged(uptInfo);
|
||||
}
|
||||
|
||||
signal.Signal();
|
||||
});
|
||||
TEST(signal.WaitUntil(steady_clock::now() + kRouteBuildingMaxDuration), ("Along route moving timeout."));
|
||||
}
|
||||
|
||||
void TestLeavingRoute(RoutingSession & session, location::GpsInfo const & info)
|
||||
{
|
||||
vector<double> const latitudes = {0.0, -0.001, -0.002, -0.003, -0.004, -0.005,
|
||||
-0.006, -0.007, -0.008, -0.009, -0.01, -0.011};
|
||||
SessionStateTest sessionStateTest({SessionState::OnRoute, SessionState::RouteNeedRebuild}, session);
|
||||
TestMovingByUpdatingLat(sessionStateTest, latitudes, info, session);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(AsyncGuiThreadTestWithRoutingSession, TestRouteBuilding)
|
||||
{
|
||||
// Multithreading synchronization note. |counter| and |session| are constructed on the main thread,
|
||||
// then used on gui thread and then if timeout in timedSignal.WaitUntil() is not reached,
|
||||
// |counter| is used again.
|
||||
TimedSignal timedSignal;
|
||||
size_t counter = 0;
|
||||
|
||||
GetPlatform().RunTask(Platform::Thread::Gui, [&timedSignal, &counter, this]()
|
||||
{
|
||||
InitRoutingSession();
|
||||
Route masterRoute("dummy", kTestRoute.begin(), kTestRoute.end(), 0 /* route id */);
|
||||
|
||||
unique_ptr<DummyRouter> router = make_unique<DummyRouter>(masterRoute, RouterResultCode::NoError, counter);
|
||||
m_session->SetRouter(std::move(router), nullptr);
|
||||
m_session->SetRoutingCallbacks([&timedSignal](Route const &, RouterResultCode)
|
||||
{
|
||||
LOG(LINFO, ("Ready"));
|
||||
timedSignal.Signal();
|
||||
}, nullptr /* rebuildReadyCallback */, nullptr /* needMoreMapsCallback */, nullptr /* removeRouteCallback */);
|
||||
m_session->BuildRoute(Checkpoints(kTestRoute.front(), kTestRoute.back()), RouterDelegate::kNoTimeout);
|
||||
});
|
||||
|
||||
// Manual check of the routeBuilding mutex to avoid spurious results.
|
||||
TEST(timedSignal.WaitUntil(steady_clock::now() + kRouteBuildingMaxDuration), ("Route was not built."));
|
||||
TEST_EQUAL(counter, 1, ());
|
||||
}
|
||||
|
||||
// Test on route rebuilding when current position moving from the route. Each next position
|
||||
// is farther from the route then previous one.
|
||||
UNIT_CLASS_TEST(AsyncGuiThreadTestWithRoutingSession, TestRouteRebuildingMovingAway)
|
||||
{
|
||||
location::GpsInfo info;
|
||||
size_t counter = 0;
|
||||
|
||||
TimedSignal alongTimedSignal;
|
||||
GetPlatform().RunTask(Platform::Thread::Gui, [&alongTimedSignal, this, &counter]()
|
||||
{
|
||||
InitRoutingSession();
|
||||
Route masterRoute("dummy", kTestRoute.begin(), kTestRoute.end(), 0 /* route id */);
|
||||
FillSubroutesInfo(masterRoute);
|
||||
|
||||
unique_ptr<DummyRouter> router = make_unique<DummyRouter>(masterRoute, RouterResultCode::NoError, counter);
|
||||
m_session->SetRouter(std::move(router), nullptr);
|
||||
|
||||
// Go along the route.
|
||||
m_session->SetRoutingCallbacks([&alongTimedSignal](Route const &, RouterResultCode) { alongTimedSignal.Signal(); },
|
||||
nullptr /* rebuildReadyCallback */, nullptr /* needMoreMapsCallback */,
|
||||
nullptr /* removeRouteCallback */);
|
||||
m_session->BuildRoute(Checkpoints(kTestRoute.front(), kTestRoute.back()),
|
||||
RouterDelegate::RouterDelegate::kNoTimeout);
|
||||
});
|
||||
TEST(alongTimedSignal.WaitUntil(steady_clock::now() + kRouteBuildingMaxDuration), ("Route was not built."));
|
||||
TEST_EQUAL(counter, 1, ());
|
||||
|
||||
{
|
||||
SessionStateTest sessionStateTest({SessionState::RouteNotStarted, SessionState::OnRoute,
|
||||
SessionState::RouteBuilding, SessionState::RouteNotStarted},
|
||||
*m_session);
|
||||
TimedSignal oppositeTimedSignal;
|
||||
GetPlatform().RunTask(Platform::Thread::Gui, [&oppositeTimedSignal, &info, this]()
|
||||
{
|
||||
info.m_horizontalAccuracy = 0.01;
|
||||
info.m_verticalAccuracy = 0.01;
|
||||
info.m_longitude = 0.;
|
||||
info.m_latitude = 1.;
|
||||
SessionState code = SessionState::NoValidRoute;
|
||||
|
||||
{
|
||||
while (info.m_latitude < kTestRoute.back().y)
|
||||
{
|
||||
code = m_session->OnLocationPositionChanged(info);
|
||||
TEST_EQUAL(code, SessionState::OnRoute, ());
|
||||
info.m_latitude += 0.01;
|
||||
}
|
||||
}
|
||||
|
||||
// Rebuild route and go in opposite direction. So initiate a route rebuilding flag.
|
||||
m_session->SetRoutingCallbacks([&oppositeTimedSignal](Route const &, RouterResultCode)
|
||||
{ oppositeTimedSignal.Signal(); }, nullptr /* rebuildReadyCallback */, nullptr /* needMoreMapsCallback */,
|
||||
nullptr /* removeRouteCallback */);
|
||||
{
|
||||
m_session->BuildRoute(Checkpoints(kTestRoute.front(), kTestRoute.back()), RouterDelegate::kNoTimeout);
|
||||
}
|
||||
});
|
||||
TEST(oppositeTimedSignal.WaitUntil(steady_clock::now() + kRouteBuildingMaxDuration), ("Route was not built."));
|
||||
}
|
||||
|
||||
// Going away from route to set rebuilding flag.
|
||||
TimedSignal checkTimedSignal;
|
||||
GetPlatform().RunTask(Platform::Thread::Gui, [&checkTimedSignal, &info, this]()
|
||||
{
|
||||
info.m_longitude = 0.;
|
||||
info.m_latitude = 1.;
|
||||
info.m_speed = measurement_utils::KmphToMps(60);
|
||||
SessionState code = SessionState::NoValidRoute;
|
||||
for (size_t i = 0; i < 10; ++i)
|
||||
{
|
||||
code = m_session->OnLocationPositionChanged(info);
|
||||
info.m_latitude -= 0.1;
|
||||
}
|
||||
TEST_EQUAL(code, SessionState::RouteNeedRebuild, ());
|
||||
checkTimedSignal.Signal();
|
||||
});
|
||||
TEST(checkTimedSignal.WaitUntil(steady_clock::now() + kRouteBuildingMaxDuration), ("Route was not rebuilt."));
|
||||
}
|
||||
|
||||
// Test on route rebuilding when current position moving to the route starting far from the route.
|
||||
// Each next position is closer to the route then previous one but is not covered by route matching passage.
|
||||
UNIT_CLASS_TEST(AsyncGuiThreadTestWithRoutingSession, TestRouteRebuildingMovingToRoute)
|
||||
{
|
||||
location::GpsInfo info;
|
||||
size_t counter = 0;
|
||||
|
||||
TimedSignal alongTimedSignal;
|
||||
GetPlatform().RunTask(Platform::Thread::Gui, [&alongTimedSignal, this, &counter]()
|
||||
{
|
||||
InitRoutingSession();
|
||||
Route masterRoute("dummy", kTestRoute.begin(), kTestRoute.end(), 0 /* route id */);
|
||||
FillSubroutesInfo(masterRoute);
|
||||
|
||||
unique_ptr<DummyRouter> router = make_unique<DummyRouter>(masterRoute, RouterResultCode::NoError, counter);
|
||||
m_session->SetRouter(std::move(router), nullptr);
|
||||
|
||||
m_session->SetRoutingCallbacks([&alongTimedSignal](Route const &, RouterResultCode) { alongTimedSignal.Signal(); },
|
||||
nullptr /* rebuildReadyCallback */, nullptr /* needMoreMapsCallback */,
|
||||
nullptr /* removeRouteCallback */);
|
||||
m_session->BuildRoute(Checkpoints(kTestRoute.front(), kTestRoute.back()), RouterDelegate::kNoTimeout);
|
||||
});
|
||||
TEST(alongTimedSignal.WaitUntil(steady_clock::now() + kRouteBuildingMaxDuration), ("Route was not built."));
|
||||
TEST_EQUAL(counter, 1, ());
|
||||
|
||||
// Going starting far from the route and moving to the route but rebuild flag still is set.
|
||||
{
|
||||
SessionStateTest sessionStateTest({SessionState::RouteNotStarted, SessionState::RouteNeedRebuild}, *m_session);
|
||||
TimedSignal checkTimedSignalAway;
|
||||
GetPlatform().RunTask(Platform::Thread::Gui, [&checkTimedSignalAway, &info, this]()
|
||||
{
|
||||
info.m_longitude = 0.0;
|
||||
info.m_latitude = 0.0;
|
||||
info.m_speed = measurement_utils::KmphToMps(60);
|
||||
SessionState code = SessionState::NoValidRoute;
|
||||
{
|
||||
for (size_t i = 0; i < 8; ++i)
|
||||
{
|
||||
code = m_session->OnLocationPositionChanged(info);
|
||||
info.m_latitude += 0.1;
|
||||
}
|
||||
}
|
||||
TEST_EQUAL(code, SessionState::RouteNeedRebuild, ());
|
||||
checkTimedSignalAway.Signal();
|
||||
});
|
||||
TEST(checkTimedSignalAway.WaitUntil(steady_clock::now() + kRouteBuildingMaxDuration), ("Route was not rebuilt."));
|
||||
}
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(AsyncGuiThreadTestWithRoutingSession, TestFollowRouteFlagPersistence)
|
||||
{
|
||||
location::GpsInfo info;
|
||||
size_t counter = 0;
|
||||
|
||||
TimedSignal alongTimedSignal;
|
||||
GetPlatform().RunTask(Platform::Thread::Gui, [&alongTimedSignal, this, &counter]()
|
||||
{
|
||||
InitRoutingSession();
|
||||
Route masterRoute("dummy", kTestRoute.begin(), kTestRoute.end(), 0 /* route id */);
|
||||
FillSubroutesInfo(masterRoute, kTestTurns);
|
||||
unique_ptr<DummyRouter> router = make_unique<DummyRouter>(masterRoute, RouterResultCode::NoError, counter);
|
||||
m_session->SetRouter(std::move(router), nullptr);
|
||||
|
||||
// Go along the route.
|
||||
m_session->SetRoutingCallbacks([&alongTimedSignal](Route const &, RouterResultCode) { alongTimedSignal.Signal(); },
|
||||
nullptr /* rebuildReadyCallback */, nullptr /* needMoreMapsCallback */,
|
||||
nullptr /* removeRouteCallback */);
|
||||
m_session->BuildRoute(Checkpoints(kTestRoute.front(), kTestRoute.back()), RouterDelegate::kNoTimeout);
|
||||
});
|
||||
TEST(alongTimedSignal.WaitUntil(steady_clock::now() + kRouteBuildingMaxDuration), ("Route was not built."));
|
||||
TEST_EQUAL(m_onNewTurnCallbackCounter, 0, ());
|
||||
|
||||
TimedSignal oppositeTimedSignal;
|
||||
GetPlatform().RunTask(Platform::Thread::Gui, [&oppositeTimedSignal, &info, this, &counter]()
|
||||
{
|
||||
TEST(!m_session->IsFollowing(), ());
|
||||
m_session->EnableFollowMode();
|
||||
TEST(m_session->IsFollowing(), ());
|
||||
|
||||
info.m_horizontalAccuracy = 0.01;
|
||||
info.m_verticalAccuracy = 0.01;
|
||||
info.m_longitude = 0.;
|
||||
info.m_latitude = 1.;
|
||||
while (info.m_latitude < kTestRoute.back().y)
|
||||
{
|
||||
m_session->OnLocationPositionChanged(info);
|
||||
TEST(m_session->IsOnRoute(), ());
|
||||
TEST(m_session->IsFollowing(), ());
|
||||
info.m_latitude += 0.01;
|
||||
}
|
||||
TEST_EQUAL(counter, 1, ());
|
||||
|
||||
// Rebuild route and go in opposite direction. So initiate a route rebuilding flag.
|
||||
m_session->SetRoutingCallbacks([&oppositeTimedSignal](Route const &, RouterResultCode)
|
||||
{ oppositeTimedSignal.Signal(); }, nullptr /* rebuildReadyCallback */, nullptr /* needMoreMapsCallback */,
|
||||
nullptr /* removeRouteCallback */);
|
||||
m_session->BuildRoute(Checkpoints(kTestRoute.front(), kTestRoute.back()), RouterDelegate::kNoTimeout);
|
||||
});
|
||||
TEST(oppositeTimedSignal.WaitUntil(steady_clock::now() + kRouteBuildingMaxDuration), ("Route was not built."));
|
||||
TEST_EQUAL(m_onNewTurnCallbackCounter, 1, ());
|
||||
|
||||
TimedSignal rebuildTimedSignal;
|
||||
GetPlatform().RunTask(Platform::Thread::Gui, [&rebuildTimedSignal, &info, this]
|
||||
{
|
||||
// Manual route building resets the following flag.
|
||||
TEST(!m_session->IsFollowing(), ());
|
||||
m_session->EnableFollowMode();
|
||||
TEST(m_session->IsFollowing(), ());
|
||||
info.m_longitude = 0.;
|
||||
info.m_latitude = 1.;
|
||||
info.m_speed = measurement_utils::KmphToMps(60);
|
||||
SessionState code = SessionState::NoValidRoute;
|
||||
for (size_t i = 0; i < 10; ++i)
|
||||
{
|
||||
code = m_session->OnLocationPositionChanged(info);
|
||||
info.m_latitude -= 0.1;
|
||||
}
|
||||
TEST_EQUAL(code, SessionState::RouteNeedRebuild, ());
|
||||
TEST(m_session->IsFollowing(), ());
|
||||
|
||||
m_session->RebuildRoute(kTestRoute.front(), [&rebuildTimedSignal](Route const &, RouterResultCode)
|
||||
{ rebuildTimedSignal.Signal(); }, nullptr /* needMoreMapsCallback */, nullptr /* removeRouteCallback */,
|
||||
RouterDelegate::kNoTimeout, SessionState::RouteBuilding, false /* adjust */);
|
||||
});
|
||||
TEST(rebuildTimedSignal.WaitUntil(steady_clock::now() + kRouteBuildingMaxDuration), ("Route was not built."));
|
||||
TEST_EQUAL(m_onNewTurnCallbackCounter, 1, ());
|
||||
|
||||
TimedSignal checkTimedSignal;
|
||||
GetPlatform().RunTask(Platform::Thread::Gui, [&checkTimedSignal, this]
|
||||
{
|
||||
TEST(m_session->IsFollowing(), ());
|
||||
checkTimedSignal.Signal();
|
||||
});
|
||||
TEST(checkTimedSignal.WaitUntil(steady_clock::now() + kRouteBuildingMaxDuration), ("Route checking timeout."));
|
||||
TEST_EQUAL(m_onNewTurnCallbackCounter, 1, ());
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(AsyncGuiThreadTestWithRoutingSession, TestFollowRoutePercentTest)
|
||||
{
|
||||
TimedSignal alongTimedSignal;
|
||||
GetPlatform().RunTask(Platform::Thread::Gui, [&alongTimedSignal, this]()
|
||||
{
|
||||
InitRoutingSession();
|
||||
Route masterRoute("dummy", kTestRoute.begin(), kTestRoute.end(), 0 /* route id */);
|
||||
FillSubroutesInfo(masterRoute);
|
||||
|
||||
size_t counter = 0;
|
||||
unique_ptr<DummyRouter> router = make_unique<DummyRouter>(masterRoute, RouterResultCode::NoError, counter);
|
||||
m_session->SetRouter(std::move(router), nullptr);
|
||||
|
||||
// Get completion percent of unexisted route.
|
||||
TEST_EQUAL(m_session->GetCompletionPercent(), 0, (m_session->GetCompletionPercent()));
|
||||
// Go along the route.
|
||||
m_session->SetRoutingCallbacks([&alongTimedSignal](Route const &, RouterResultCode) { alongTimedSignal.Signal(); },
|
||||
nullptr /* rebuildReadyCallback */, nullptr /* needMoreMapsCallback */,
|
||||
nullptr /* removeRouteCallback */);
|
||||
m_session->BuildRoute(Checkpoints(kTestRoute.front(), kTestRoute.back()), RouterDelegate::kNoTimeout);
|
||||
});
|
||||
TEST(alongTimedSignal.WaitUntil(steady_clock::now() + kRouteBuildingMaxDuration), ("Route was not built."));
|
||||
|
||||
TimedSignal checkTimedSignal;
|
||||
GetPlatform().RunTask(Platform::Thread::Gui, [&checkTimedSignal, this]
|
||||
{
|
||||
// Get completion percent of unstarted route.
|
||||
TEST_EQUAL(m_session->GetCompletionPercent(), 0, (m_session->GetCompletionPercent()));
|
||||
|
||||
location::GpsInfo info;
|
||||
info.m_horizontalAccuracy = 0.01;
|
||||
info.m_verticalAccuracy = 0.01;
|
||||
|
||||
// Go through the route.
|
||||
info.m_longitude = 0.;
|
||||
info.m_latitude = 1.;
|
||||
m_session->OnLocationPositionChanged(info);
|
||||
TEST(AlmostEqualAbs(m_session->GetCompletionPercent(), 0., 0.5), (m_session->GetCompletionPercent()));
|
||||
|
||||
info.m_longitude = 0.;
|
||||
info.m_latitude = 2.;
|
||||
m_session->OnLocationPositionChanged(info);
|
||||
TEST(AlmostEqualAbs(m_session->GetCompletionPercent(), 33.3, 0.5), (m_session->GetCompletionPercent()));
|
||||
|
||||
info.m_longitude = 0.;
|
||||
info.m_latitude = 3.;
|
||||
m_session->OnLocationPositionChanged(info);
|
||||
TEST(AlmostEqualAbs(m_session->GetCompletionPercent(), 66.6, 0.5), (m_session->GetCompletionPercent()));
|
||||
|
||||
info.m_longitude = 0.;
|
||||
info.m_latitude = 3.99;
|
||||
m_session->OnLocationPositionChanged(info);
|
||||
TEST(AlmostEqualAbs(m_session->GetCompletionPercent(), 100., 0.5), (m_session->GetCompletionPercent()));
|
||||
checkTimedSignal.Signal();
|
||||
});
|
||||
TEST(checkTimedSignal.WaitUntil(steady_clock::now() + kRouteBuildingMaxDuration), ("Route checking timeout."));
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(AsyncGuiThreadTestWithRoutingSession, TestRouteRebuildingError)
|
||||
{
|
||||
vector<m2::PointD> const kRoute = {{0.0, 0.001}, {0.0, 0.002}, {0.0, 0.003}, {0.0, 0.004}};
|
||||
// Creation RoutingSession.
|
||||
TimedSignal createTimedSignal;
|
||||
GetPlatform().RunTask(Platform::Thread::Gui, [this, &kRoute, &createTimedSignal]()
|
||||
{
|
||||
InitRoutingSession();
|
||||
unique_ptr<ReturnCodesRouter> router = make_unique<ReturnCodesRouter>(
|
||||
initializer_list<RouterResultCode>{RouterResultCode::NoError, RouterResultCode::InternalError}, kRoute);
|
||||
m_session->SetRouter(std::move(router), nullptr);
|
||||
createTimedSignal.Signal();
|
||||
});
|
||||
TEST(createTimedSignal.WaitUntil(steady_clock::now() + kRouteBuildingMaxDuration), ("RouteSession was not created."));
|
||||
|
||||
// Building a route.
|
||||
{
|
||||
SessionStateTest sessionStateTest(
|
||||
{SessionState::NoValidRoute, SessionState::RouteBuilding, SessionState::RouteNotStarted}, *m_session);
|
||||
TimedSignal buildTimedSignal;
|
||||
GetPlatform().RunTask(Platform::Thread::Gui, [this, &kRoute, &buildTimedSignal]()
|
||||
{
|
||||
m_session->SetRoutingCallbacks([&buildTimedSignal](Route const &, RouterResultCode)
|
||||
{ buildTimedSignal.Signal(); }, nullptr /* rebuildReadyCallback */, nullptr /* needMoreMapsCallback */,
|
||||
nullptr /* removeRouteCallback */);
|
||||
|
||||
m_session->BuildRoute(Checkpoints(kRoute.front(), kRoute.back()), RouterDelegate::kNoTimeout);
|
||||
});
|
||||
TEST(buildTimedSignal.WaitUntil(steady_clock::now() + kRouteBuildingMaxDuration), ("Route was not built."));
|
||||
}
|
||||
|
||||
location::GpsInfo info;
|
||||
info.m_horizontalAccuracy = 5.0; // meters
|
||||
info.m_verticalAccuracy = 5.0; // meters
|
||||
info.m_longitude = 0.0;
|
||||
|
||||
// Moving along route.
|
||||
{
|
||||
SessionStateTest sessionStateTest({SessionState::RouteNotStarted, SessionState::OnRoute}, *m_session);
|
||||
vector<double> const latitudes = {0.001, 0.0015, 0.002};
|
||||
TestMovingByUpdatingLat(sessionStateTest, latitudes, info, *m_session);
|
||||
}
|
||||
|
||||
// Test 1. Leaving the route and returning to the route when state is |SessionState::RouteNeedRebuil|.
|
||||
TestLeavingRoute(*m_session, info);
|
||||
|
||||
// Continue moving along the route.
|
||||
{
|
||||
SessionStateTest sessionStateTest({SessionState::RouteNeedRebuild, SessionState::OnRoute}, *m_session);
|
||||
vector<double> const latitudes = {0.002, 0.0025, 0.003};
|
||||
TestMovingByUpdatingLat(sessionStateTest, latitudes, info, *m_session);
|
||||
}
|
||||
|
||||
// Test 2. Leaving the route until, can not rebuilding it, and going along an old route.
|
||||
// It happens we the route is left and it's impossible to build a new route.
|
||||
// In this case the navigation is continued based on the former route.
|
||||
TestLeavingRoute(*m_session, info);
|
||||
{
|
||||
SessionStateTest sessionStateTest({SessionState::RouteNeedRebuild, SessionState::RouteRebuilding}, *m_session);
|
||||
TimedSignal signal;
|
||||
GetPlatform().RunTask(Platform::Thread::Gui, [this, &signal]()
|
||||
{
|
||||
m_session->SetState(SessionState::RouteRebuilding);
|
||||
signal.Signal();
|
||||
});
|
||||
TEST(signal.WaitUntil(steady_clock::now() + kRouteBuildingMaxDuration), ("State was not set."));
|
||||
}
|
||||
|
||||
// Continue moving along the route again.
|
||||
{
|
||||
// Test on state is not changed.
|
||||
SessionStateTest sessionStateTest({SessionState::RouteRebuilding, SessionState::OnRoute}, *m_session);
|
||||
vector<double> const latitudes = {0.003, 0.0035, 0.004};
|
||||
TestMovingByUpdatingLat(sessionStateTest, latitudes, info, *m_session);
|
||||
}
|
||||
}
|
||||
} // namespace routing_session_test
|
||||
172
libs/routing/routing_tests/speed_cameras_tests.cpp
Normal file
172
libs/routing/routing_tests/speed_cameras_tests.cpp
Normal file
|
|
@ -0,0 +1,172 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/speed_camera_ser_des.hpp"
|
||||
|
||||
#include "platform/platform_tests_support/scoped_dir.hpp"
|
||||
#include "platform/platform_tests_support/scoped_file.hpp"
|
||||
|
||||
#include "coding/file_reader.hpp"
|
||||
#include "coding/file_writer.hpp"
|
||||
#include "coding/files_container.hpp"
|
||||
|
||||
#include "base/assert.hpp"
|
||||
#include "base/file_name_utils.hpp"
|
||||
#include "base/math.hpp"
|
||||
|
||||
#include <vector>
|
||||
|
||||
using namespace platform::tests_support;
|
||||
using namespace platform;
|
||||
using namespace routing;
|
||||
|
||||
namespace
|
||||
{
|
||||
static auto const kTestDir = "ser_des_test_camera";
|
||||
static auto const kTestFileForCamera = "ser_des_test_camera.bin";
|
||||
static auto const kErrorMessageOneWay = "Serialize method works only with cameras with one way";
|
||||
|
||||
UNIT_TEST(SegmentCoord_LessOperator)
|
||||
{
|
||||
{
|
||||
SegmentCoord a(10, 5);
|
||||
SegmentCoord b(11, 0);
|
||||
|
||||
TEST_LESS(a, b, ());
|
||||
}
|
||||
|
||||
{
|
||||
SegmentCoord a(10, 0);
|
||||
SegmentCoord b(11, 5);
|
||||
|
||||
TEST_LESS(a, b, ());
|
||||
}
|
||||
|
||||
{
|
||||
SegmentCoord a(5, 0);
|
||||
SegmentCoord b(11, 5);
|
||||
|
||||
TEST_LESS(a, b, ());
|
||||
}
|
||||
|
||||
{
|
||||
SegmentCoord a(5, 0);
|
||||
SegmentCoord b(0, 5);
|
||||
|
||||
TEST_LESS(b, a, ());
|
||||
}
|
||||
|
||||
{
|
||||
SegmentCoord a(5, 0);
|
||||
SegmentCoord b(5, 5);
|
||||
|
||||
TEST_LESS(a, b, ());
|
||||
}
|
||||
|
||||
{
|
||||
SegmentCoord a(5, 6);
|
||||
SegmentCoord b(5, 5);
|
||||
|
||||
TEST_LESS(b, a, ());
|
||||
}
|
||||
|
||||
{
|
||||
SegmentCoord a(4, 6);
|
||||
SegmentCoord b(5, 6);
|
||||
|
||||
TEST_LESS(a, b, ());
|
||||
}
|
||||
}
|
||||
|
||||
// Test for serialize/deserialize of speed cameras.
|
||||
|
||||
bool TestSerDesSpeedCamera(std::vector<SpeedCameraMetadata> const & speedCamerasMetadata)
|
||||
{
|
||||
if (speedCamerasMetadata.empty())
|
||||
return true;
|
||||
|
||||
CHECK_EQUAL(speedCamerasMetadata[0].m_ways.size(), 1, (kErrorMessageOneWay));
|
||||
for (size_t i = 1; i < speedCamerasMetadata.size(); ++i)
|
||||
{
|
||||
CHECK_EQUAL(speedCamerasMetadata[i].m_ways.size(), 1, (kErrorMessageOneWay));
|
||||
CHECK_LESS_OR_EQUAL(speedCamerasMetadata[i - 1].m_ways.back().m_featureId,
|
||||
speedCamerasMetadata[i].m_ways.back().m_featureId,
|
||||
("Ways of cameras should be sorted by featureId for delta coding"));
|
||||
}
|
||||
|
||||
ScopedDir scopedDir(kTestDir);
|
||||
auto const testFile = base::JoinPath(kTestDir, kTestFileForCamera);
|
||||
ScopedFile scopedFile(testFile, "");
|
||||
auto const & writableDir = GetPlatform().WritableDir();
|
||||
auto const & filePath = base::JoinPath(writableDir, testFile);
|
||||
|
||||
{
|
||||
FileWriter writer(filePath);
|
||||
uint32_t prevFeatureId = 0;
|
||||
for (auto const & metadata : speedCamerasMetadata)
|
||||
SerializeSpeedCamera(writer, metadata, prevFeatureId);
|
||||
}
|
||||
|
||||
{
|
||||
FileReader reader(filePath);
|
||||
ReaderSource<FileReader> src(reader);
|
||||
uint32_t prevFeatureId = 0;
|
||||
for (auto const & metadata : speedCamerasMetadata)
|
||||
{
|
||||
auto const & way = metadata.m_ways.back();
|
||||
auto const res = DeserializeSpeedCamera(src, prevFeatureId);
|
||||
TEST_EQUAL(res.first, SegmentCoord(way.m_featureId, way.m_segmentId), ());
|
||||
TEST(AlmostEqualAbs(res.second.m_coef, way.m_coef, 1e-5), ());
|
||||
TEST_EQUAL(res.second.m_maxSpeedKmPH, metadata.m_maxSpeedKmPH, ());
|
||||
}
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
UNIT_TEST(SpeedCamera_SerDes_1)
|
||||
{
|
||||
std::vector<routing::SpeedCameraMwmPosition> ways = {{1 /* featureId */, 1 /* segmentId */, 0 /* coef */}};
|
||||
SpeedCameraMetadata metadata({10, 10} /* m_center */, 60 /* m_maxSpeedKmPH */, std::move(ways));
|
||||
|
||||
TEST(TestSerDesSpeedCamera({metadata}), ());
|
||||
}
|
||||
|
||||
UNIT_TEST(SpeedCamera_SerDes_2)
|
||||
{
|
||||
std::vector<SpeedCameraMetadata> speedCamerasMetadata;
|
||||
{
|
||||
std::vector<routing::SpeedCameraMwmPosition> ways = {{1 /* featureId */, 1 /* segmentId */, 0 /* coef */}};
|
||||
SpeedCameraMetadata metadata({10, 10} /* m_center */, 60 /* m_maxSpeedKmPH */, std::move(ways));
|
||||
speedCamerasMetadata.emplace_back(metadata);
|
||||
}
|
||||
{
|
||||
std::vector<routing::SpeedCameraMwmPosition> ways = {{2 /* featureId */, 1 /* segmentId */, 0.5 /* coef */}};
|
||||
SpeedCameraMetadata metadata({15, 10} /* m_center */, 90 /* m_maxSpeedKmPH */, std::move(ways));
|
||||
speedCamerasMetadata.emplace_back(metadata);
|
||||
}
|
||||
|
||||
TEST(TestSerDesSpeedCamera(speedCamerasMetadata), ());
|
||||
}
|
||||
|
||||
UNIT_TEST(SpeedCamera_SerDes_3)
|
||||
{
|
||||
std::vector<SpeedCameraMetadata> speedCamerasMetadata;
|
||||
{
|
||||
std::vector<routing::SpeedCameraMwmPosition> ways = {{1 /* featureId */, 1 /* segmentId */, 0 /* coef */}};
|
||||
SpeedCameraMetadata metadata({10, 10} /* m_center */, 60 /* m_maxSpeedKmPH */, std::move(ways));
|
||||
speedCamerasMetadata.emplace_back(metadata);
|
||||
}
|
||||
{
|
||||
std::vector<routing::SpeedCameraMwmPosition> ways = {{1 /* featureId */, 1 /* segmentId */, 0.5 /* coef */}};
|
||||
SpeedCameraMetadata metadata({10, 10} /* m_center */, 90 /* m_maxSpeedKmPH */, std::move(ways));
|
||||
speedCamerasMetadata.emplace_back(metadata);
|
||||
}
|
||||
{
|
||||
std::vector<routing::SpeedCameraMwmPosition> ways = {{10 /* featureId */, 1 /* segmentId */, 1 /* coef */}};
|
||||
SpeedCameraMetadata metadata({20, 20} /* m_center */, 40 /* m_maxSpeedKmPH */, std::move(ways));
|
||||
speedCamerasMetadata.emplace_back(metadata);
|
||||
}
|
||||
|
||||
TEST(TestSerDesSpeedCamera(speedCamerasMetadata), ());
|
||||
}
|
||||
} // namespace
|
||||
50
libs/routing/routing_tests/tools.cpp
Normal file
50
libs/routing/routing_tests/tools.cpp
Normal file
|
|
@ -0,0 +1,50 @@
|
|||
#include "routing/routing_tests/tools.hpp"
|
||||
|
||||
namespace routing
|
||||
{
|
||||
void AsyncGuiThreadTestWithRoutingSession::InitRoutingSession()
|
||||
{
|
||||
m_session = std::make_unique<routing::RoutingSession>();
|
||||
m_session->Init(nullptr /* pointCheckCallback */);
|
||||
m_session->SetRoutingSettings(routing::GetRoutingSettings(routing::VehicleType::Car));
|
||||
m_session->SetOnNewTurnCallback([this]() { ++m_onNewTurnCallbackCounter; });
|
||||
}
|
||||
|
||||
void RouteSegmentsFrom(std::vector<Segment> const & segments, std::vector<m2::PointD> const & path,
|
||||
std::vector<turns::TurnItem> const & turns,
|
||||
std::vector<RouteSegment::RoadNameInfo> const & names, std::vector<RouteSegment> & routeSegments)
|
||||
{
|
||||
size_t size = segments.size();
|
||||
if (size == 0)
|
||||
size = turns.size();
|
||||
if (size == 0)
|
||||
size = names.size();
|
||||
if (size == 0)
|
||||
size = path.size() - 1;
|
||||
|
||||
ASSERT(segments.empty() || segments.size() == size, ());
|
||||
ASSERT(turns.empty() || turns.size() == size, ());
|
||||
ASSERT(names.empty() || names.size() == size, ());
|
||||
ASSERT(path.empty() || path.size() - 1 == size, ());
|
||||
|
||||
for (size_t i = 0; i < size; ++i)
|
||||
{
|
||||
geometry::PointWithAltitude point;
|
||||
if (path.size() > 0)
|
||||
point = geometry::PointWithAltitude(path[i + 1], geometry::kDefaultAltitudeMeters);
|
||||
Segment segment({0, 0, 0, true});
|
||||
if (segments.size() > 0)
|
||||
segment = segments[i];
|
||||
turns::TurnItem turn;
|
||||
if (turns.size() > 0)
|
||||
{
|
||||
turn = turns[i];
|
||||
ASSERT(turn.m_index == i + 1, ());
|
||||
}
|
||||
RouteSegment::RoadNameInfo name;
|
||||
if (names.size() > 0)
|
||||
name = names[i];
|
||||
routeSegments.emplace_back(segment, turn, point, name);
|
||||
}
|
||||
}
|
||||
} // namespace routing
|
||||
29
libs/routing/routing_tests/tools.hpp
Normal file
29
libs/routing/routing_tests/tools.hpp
Normal file
|
|
@ -0,0 +1,29 @@
|
|||
#pragma once
|
||||
|
||||
#include "platform/platform_tests_support/async_gui_thread.hpp"
|
||||
|
||||
#include "routing/routing_session.hpp"
|
||||
|
||||
#include <memory>
|
||||
|
||||
namespace routing
|
||||
{
|
||||
class AsyncGuiThreadTest
|
||||
{
|
||||
platform::tests_support::AsyncGuiThread m_asyncGuiThread;
|
||||
};
|
||||
|
||||
class AsyncGuiThreadTestWithRoutingSession : public AsyncGuiThreadTest
|
||||
{
|
||||
public:
|
||||
void InitRoutingSession();
|
||||
|
||||
std::unique_ptr<RoutingSession> m_session;
|
||||
size_t m_onNewTurnCallbackCounter = 0;
|
||||
};
|
||||
|
||||
void RouteSegmentsFrom(std::vector<Segment> const & segments, std::vector<m2::PointD> const & path,
|
||||
std::vector<turns::TurnItem> const & turns,
|
||||
std::vector<RouteSegment::RoadNameInfo> const & names,
|
||||
std::vector<RouteSegment> & routeSegments);
|
||||
} // namespace routing
|
||||
286
libs/routing/routing_tests/turns_generator_test.cpp
Normal file
286
libs/routing/routing_tests/turns_generator_test.cpp
Normal file
|
|
@ -0,0 +1,286 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/routing_tests/tools.hpp"
|
||||
|
||||
#include "routing/car_directions.hpp"
|
||||
#include "routing/loaded_path_segment.hpp"
|
||||
#include "routing/route.hpp"
|
||||
#include "routing/routing_result_graph.hpp"
|
||||
#include "routing/turns.hpp"
|
||||
#include "routing/turns_generator.hpp"
|
||||
#include "routing/turns_generator_utils.hpp"
|
||||
|
||||
#include "indexer/ftypes_matcher.hpp"
|
||||
|
||||
#include "geometry/mercator.hpp"
|
||||
#include "geometry/point2d.hpp"
|
||||
#include "geometry/point_with_altitude.hpp"
|
||||
|
||||
#include "base/macros.hpp"
|
||||
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
namespace turn_generator_test
|
||||
{
|
||||
using namespace routing;
|
||||
using namespace std;
|
||||
using namespace turns;
|
||||
|
||||
// It's a dummy class to wrap |segments| for tests.
|
||||
class RoutingResultTest : public IRoutingResult
|
||||
{
|
||||
public:
|
||||
explicit RoutingResultTest(TUnpackedPathSegments const & segments) : m_segments(segments) {}
|
||||
|
||||
TUnpackedPathSegments const & GetSegments() const override { return m_segments; }
|
||||
|
||||
void GetPossibleTurns(SegmentRange const & segmentRange, m2::PointD const & junctionPoint, size_t & ingoingCount,
|
||||
TurnCandidates & outgoingTurns) const override
|
||||
{
|
||||
outgoingTurns.candidates.emplace_back(0.0, Segment(), ftypes::HighwayClass::Tertiary, false);
|
||||
outgoingTurns.isCandidatesAngleValid = false;
|
||||
}
|
||||
|
||||
double GetPathLength() const override
|
||||
{
|
||||
NOTIMPLEMENTED();
|
||||
return 0.0;
|
||||
}
|
||||
|
||||
geometry::PointWithAltitude GetStartPoint() const override
|
||||
{
|
||||
NOTIMPLEMENTED();
|
||||
return geometry::PointWithAltitude();
|
||||
}
|
||||
|
||||
geometry::PointWithAltitude GetEndPoint() const override
|
||||
{
|
||||
NOTIMPLEMENTED();
|
||||
return geometry::PointWithAltitude();
|
||||
}
|
||||
|
||||
private:
|
||||
TUnpackedPathSegments m_segments;
|
||||
};
|
||||
|
||||
UNIT_TEST(TestFixupTurns)
|
||||
{
|
||||
double const kHalfSquareSideMeters = 10.;
|
||||
m2::PointD const kSquareCenterLonLat = {0., 0.};
|
||||
m2::RectD const kSquareNearZero =
|
||||
mercator::MetersToXY(kSquareCenterLonLat.x, kSquareCenterLonLat.y, kHalfSquareSideMeters);
|
||||
{
|
||||
// Removing a turn in case staying on a roundabout.
|
||||
vector<m2::PointD> const pointsMerc1 = {{kSquareNearZero.minX(), kSquareNearZero.minY()},
|
||||
{kSquareNearZero.minX(), kSquareNearZero.minY()},
|
||||
{kSquareNearZero.maxX(), kSquareNearZero.maxY()},
|
||||
{kSquareNearZero.maxX(), kSquareNearZero.minY()}};
|
||||
// The constructor TurnItem(uint32_t idx, CarDirection t, uint32_t exitNum = 0)
|
||||
// is used for initialization of vector<TurnItem> below.
|
||||
vector<turns::TurnItem> turnsDir1 = {
|
||||
{1, CarDirection::EnterRoundAbout}, {2, CarDirection::StayOnRoundAbout}, {3, CarDirection::LeaveRoundAbout}};
|
||||
vector<RouteSegment> routeSegments;
|
||||
RouteSegmentsFrom({}, pointsMerc1, turnsDir1, {}, routeSegments);
|
||||
FixupCarTurns(routeSegments);
|
||||
vector<turns::TurnItem> const expectedTurnDir1 = {
|
||||
{1, CarDirection::EnterRoundAbout, 2}, {2, CarDirection::None, 0}, {3, CarDirection::LeaveRoundAbout, 2}};
|
||||
TEST_EQUAL(routeSegments[0].GetTurn(), expectedTurnDir1[0], ());
|
||||
TEST_EQUAL(routeSegments[1].GetTurn(), expectedTurnDir1[1], ());
|
||||
TEST_EQUAL(routeSegments[2].GetTurn(), expectedTurnDir1[2], ());
|
||||
}
|
||||
{
|
||||
// Merging turns which are close to each other.
|
||||
vector<m2::PointD> const pointsMerc2 = {{kSquareNearZero.minX(), kSquareNearZero.minY()},
|
||||
{kSquareNearZero.minX(), kSquareNearZero.minY()},
|
||||
{kSquareCenterLonLat.x, kSquareCenterLonLat.y},
|
||||
{kSquareNearZero.maxX(), kSquareNearZero.maxY()}};
|
||||
vector<turns::TurnItem> turnsDir2 = {
|
||||
{1, CarDirection::None}, {2, CarDirection::GoStraight}, {3, CarDirection::TurnLeft}};
|
||||
vector<RouteSegment> routeSegments2;
|
||||
RouteSegmentsFrom({}, pointsMerc2, turnsDir2, {}, routeSegments2);
|
||||
FixupCarTurns(routeSegments2);
|
||||
vector<turns::TurnItem> const expectedTurnDir2 = {
|
||||
{1, CarDirection::None}, {2, CarDirection::None}, {3, CarDirection::TurnLeft}};
|
||||
TEST_EQUAL(routeSegments2[0].GetTurn(), expectedTurnDir2[0], ());
|
||||
TEST_EQUAL(routeSegments2[1].GetTurn(), expectedTurnDir2[1], ());
|
||||
TEST_EQUAL(routeSegments2[2].GetTurn(), expectedTurnDir2[2], ());
|
||||
}
|
||||
{
|
||||
// No turn is removed.
|
||||
vector<m2::PointD> const pointsMerc3 = {
|
||||
{kSquareNearZero.minX(), kSquareNearZero.minY()},
|
||||
{kSquareNearZero.minX(), kSquareNearZero.maxY()},
|
||||
{kSquareNearZero.maxX(), kSquareNearZero.maxY()},
|
||||
};
|
||||
vector<turns::TurnItem> turnsDir3 = {{1, CarDirection::None}, {2, CarDirection::TurnRight}};
|
||||
|
||||
vector<RouteSegment> routeSegments3;
|
||||
RouteSegmentsFrom({}, {}, turnsDir3, {}, routeSegments3);
|
||||
FixupCarTurns(routeSegments3);
|
||||
vector<turns::TurnItem> const expectedTurnDir3 = {{1, CarDirection::None}, {2, CarDirection::TurnRight}};
|
||||
|
||||
TEST_EQUAL(routeSegments3[0].GetTurn(), expectedTurnDir3[0], ());
|
||||
TEST_EQUAL(routeSegments3[1].GetTurn(), expectedTurnDir3[1], ());
|
||||
}
|
||||
}
|
||||
|
||||
UNIT_TEST(TestGetRoundaboutDirection)
|
||||
{
|
||||
// The signature of GetRoundaboutDirection function is
|
||||
// GetRoundaboutDirection(bool isIngoingEdgeRoundabout, bool isOutgoingEdgeRoundabout,
|
||||
// bool isMultiTurnJunction, bool keepTurnByHighwayClass)
|
||||
TEST_EQUAL(GetRoundaboutDirectionBasic(true, true, true, true), CarDirection::StayOnRoundAbout, ());
|
||||
TEST_EQUAL(GetRoundaboutDirectionBasic(true, true, true, false), CarDirection::None, ());
|
||||
TEST_EQUAL(GetRoundaboutDirectionBasic(true, true, false, true), CarDirection::None, ());
|
||||
TEST_EQUAL(GetRoundaboutDirectionBasic(true, true, false, false), CarDirection::None, ());
|
||||
TEST_EQUAL(GetRoundaboutDirectionBasic(false, true, false, true), CarDirection::EnterRoundAbout, ());
|
||||
TEST_EQUAL(GetRoundaboutDirectionBasic(true, false, false, false), CarDirection::LeaveRoundAbout, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(TestInvertDirection)
|
||||
{
|
||||
TEST_EQUAL(InvertDirection(CarDirection::TurnSlightRight), CarDirection::TurnSlightLeft, ());
|
||||
TEST_EQUAL(InvertDirection(CarDirection::TurnRight), CarDirection::TurnLeft, ());
|
||||
TEST_EQUAL(InvertDirection(CarDirection::TurnSharpRight), CarDirection::TurnSharpLeft, ());
|
||||
TEST_EQUAL(InvertDirection(CarDirection::TurnSlightLeft), CarDirection::TurnSlightRight, ());
|
||||
TEST_EQUAL(InvertDirection(CarDirection::TurnSlightRight), CarDirection::TurnSlightLeft, ());
|
||||
TEST_EQUAL(InvertDirection(CarDirection::TurnLeft), CarDirection::TurnRight, ());
|
||||
TEST_EQUAL(InvertDirection(CarDirection::TurnSharpLeft), CarDirection::TurnSharpRight, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(TestRightmostDirection)
|
||||
{
|
||||
TEST_EQUAL(RightmostDirection(180.), CarDirection::TurnSharpRight, ());
|
||||
TEST_EQUAL(RightmostDirection(170.), CarDirection::TurnSharpRight, ());
|
||||
TEST_EQUAL(RightmostDirection(90.), CarDirection::TurnRight, ());
|
||||
TEST_EQUAL(RightmostDirection(45.), CarDirection::TurnSlightRight, ());
|
||||
TEST_EQUAL(RightmostDirection(0.), CarDirection::GoStraight, ());
|
||||
TEST_EQUAL(RightmostDirection(-20.), CarDirection::GoStraight, ());
|
||||
TEST_EQUAL(RightmostDirection(-90.), CarDirection::GoStraight, ());
|
||||
TEST_EQUAL(RightmostDirection(-170.), CarDirection::GoStraight, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(TestLeftmostDirection)
|
||||
{
|
||||
TEST_EQUAL(LeftmostDirection(180.), CarDirection::GoStraight, ());
|
||||
TEST_EQUAL(LeftmostDirection(170.), CarDirection::GoStraight, ());
|
||||
TEST_EQUAL(LeftmostDirection(90.), CarDirection::GoStraight, ());
|
||||
TEST_EQUAL(LeftmostDirection(45.), CarDirection::GoStraight, ());
|
||||
TEST_EQUAL(LeftmostDirection(0.), CarDirection::GoStraight, ());
|
||||
TEST_EQUAL(LeftmostDirection(-20.), CarDirection::TurnSlightLeft, ());
|
||||
TEST_EQUAL(LeftmostDirection(-90.), CarDirection::TurnLeft, ());
|
||||
TEST_EQUAL(LeftmostDirection(-170.), CarDirection::TurnSharpLeft, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(TestIntermediateDirection)
|
||||
{
|
||||
TEST_EQUAL(IntermediateDirection(180.), CarDirection::TurnSharpRight, ());
|
||||
TEST_EQUAL(IntermediateDirection(170.), CarDirection::TurnSharpRight, ());
|
||||
TEST_EQUAL(IntermediateDirection(90.), CarDirection::TurnRight, ());
|
||||
TEST_EQUAL(IntermediateDirection(45.), CarDirection::TurnSlightRight, ());
|
||||
TEST_EQUAL(IntermediateDirection(0.), CarDirection::GoStraight, ());
|
||||
TEST_EQUAL(IntermediateDirection(-20.), CarDirection::TurnSlightLeft, ());
|
||||
TEST_EQUAL(IntermediateDirection(-90.), CarDirection::TurnLeft, ());
|
||||
TEST_EQUAL(IntermediateDirection(-170.), CarDirection::TurnSharpLeft, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(TestCheckUTurnOnRoute)
|
||||
{
|
||||
TUnpackedPathSegments pathSegments(4, LoadedPathSegment());
|
||||
pathSegments[0].m_roadNameInfo = {"A road", "", "", "", "", false};
|
||||
pathSegments[0].m_highwayClass = ftypes::HighwayClass::Trunk;
|
||||
pathSegments[0].m_onRoundabout = false;
|
||||
pathSegments[0].m_isLink = false;
|
||||
pathSegments[0].m_path = {{{0, 0}, 0}, {{0, 1}, 0}};
|
||||
pathSegments[0].m_segmentRange =
|
||||
SegmentRange(FeatureID(), 0 /* start seg id */, 1 /* end seg id */, true /* forward */,
|
||||
pathSegments[0].m_path.front().GetPoint(), pathSegments[0].m_path.back().GetPoint());
|
||||
|
||||
pathSegments[1] = pathSegments[0];
|
||||
pathSegments[1].m_segmentRange =
|
||||
SegmentRange(FeatureID(), 1 /* start seg id */, 2 /* end seg id */, true /* forward */,
|
||||
pathSegments[1].m_path.front().GetPoint(), pathSegments[1].m_path.back().GetPoint());
|
||||
pathSegments[1].m_path = {{{0, 1}, 0}, {{0, 0}, 0}};
|
||||
|
||||
pathSegments[2] = pathSegments[0];
|
||||
pathSegments[2].m_segmentRange =
|
||||
SegmentRange(FeatureID(), 2 /* start seg id */, 3 /* end seg id */, true /* forward */,
|
||||
pathSegments[2].m_path.front().GetPoint(), pathSegments[2].m_path.back().GetPoint());
|
||||
pathSegments[2].m_path = {{{0, 0}, 0}, {{0, 1}, 0}};
|
||||
|
||||
pathSegments[3] = pathSegments[0];
|
||||
pathSegments[3].m_segmentRange =
|
||||
SegmentRange(FeatureID(), 3 /* start seg id */, 4 /* end seg id */, true /* forward */,
|
||||
pathSegments[3].m_path.front().GetPoint(), pathSegments[3].m_path.back().GetPoint());
|
||||
pathSegments[3].m_path.clear();
|
||||
|
||||
RoutingResultTest resultTest(pathSegments);
|
||||
RoutingSettings const vehicleSettings = GetRoutingSettings(VehicleType::Car);
|
||||
// Zigzag test.
|
||||
TurnItem turn1;
|
||||
TEST_EQUAL(CheckUTurnOnRoute(resultTest, 1 /* outgoingSegmentIndex */, NumMwmIds(), vehicleSettings, turn1), 1, ());
|
||||
TEST_EQUAL(turn1.m_turn, CarDirection::UTurnLeft, ());
|
||||
TurnItem turn2;
|
||||
TEST_EQUAL(CheckUTurnOnRoute(resultTest, 2 /* outgoingSegmentIndex */, NumMwmIds(), vehicleSettings, turn2), 1, ());
|
||||
TEST_EQUAL(turn2.m_turn, CarDirection::UTurnLeft, ());
|
||||
|
||||
// Empty path test.
|
||||
TurnItem turn3;
|
||||
TEST_EQUAL(CheckUTurnOnRoute(resultTest, 3 /* outgoingSegmentIndex */, NumMwmIds(), vehicleSettings, turn3), 0, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(GetNextRoutePointIndex)
|
||||
{
|
||||
TUnpackedPathSegments pathSegments(2, LoadedPathSegment());
|
||||
pathSegments[0].m_path = {{{0, 0}, 0}, {{0, 1}, 0}, {{0, 2}, 0}};
|
||||
pathSegments[1].m_path = {{{0, 2}, 0}, {{1, 2}, 0}};
|
||||
|
||||
RoutingResultTest resultTest(pathSegments);
|
||||
RoutePointIndex nextIndex;
|
||||
|
||||
// Forward direction.
|
||||
TEST(GetNextRoutePointIndex(resultTest, RoutePointIndex({0 /* m_segmentIndex */, 0 /* m_pathIndex */}), NumMwmIds(),
|
||||
true /* forward */, nextIndex),
|
||||
());
|
||||
TEST_EQUAL(nextIndex, RoutePointIndex({0 /* m_segmentIndex */, 1 /* m_pathIndex */}), ());
|
||||
|
||||
TEST(GetNextRoutePointIndex(resultTest, RoutePointIndex({0 /* m_segmentIndex */, 1 /* m_pathIndex */}), NumMwmIds(),
|
||||
true /* forward */, nextIndex),
|
||||
());
|
||||
TEST_EQUAL(nextIndex, RoutePointIndex({0 /* m_segmentIndex */, 2 /* m_pathIndex */}), ());
|
||||
|
||||
// Trying to get next item after the last item of the first segment.
|
||||
// False because of too sharp turn angle.
|
||||
TEST(!GetNextRoutePointIndex(resultTest, RoutePointIndex({0 /* m_segmentIndex */, 2 /* m_pathIndex */}), NumMwmIds(),
|
||||
true /* forward */, nextIndex),
|
||||
());
|
||||
|
||||
// Trying to get point about the end of the route.
|
||||
TEST(!GetNextRoutePointIndex(resultTest, RoutePointIndex({1 /* m_segmentIndex */, 1 /* m_pathIndex */}), NumMwmIds(),
|
||||
true /* forward */, nextIndex),
|
||||
());
|
||||
|
||||
// Backward direction.
|
||||
// Moving in backward direction it's possible to get index of the first item of a segment.
|
||||
TEST(GetNextRoutePointIndex(resultTest, RoutePointIndex({1 /* m_segmentIndex */, 1 /* m_pathIndex */}), NumMwmIds(),
|
||||
false /* forward */, nextIndex),
|
||||
());
|
||||
TEST_EQUAL(nextIndex, RoutePointIndex({1 /* m_segmentIndex */, 0 /* m_pathIndex */}), ());
|
||||
|
||||
TEST(GetNextRoutePointIndex(resultTest, RoutePointIndex({0 /* m_segmentIndex */, 2 /* m_pathIndex */}), NumMwmIds(),
|
||||
false /* forward */, nextIndex),
|
||||
());
|
||||
TEST_EQUAL(nextIndex, RoutePointIndex({0 /* m_segmentIndex */, 1 /* m_pathIndex */}), ());
|
||||
|
||||
TEST(GetNextRoutePointIndex(resultTest, RoutePointIndex({0 /* m_segmentIndex */, 1 /* m_pathIndex */}), NumMwmIds(),
|
||||
false /* forward */, nextIndex),
|
||||
());
|
||||
TEST_EQUAL(nextIndex, RoutePointIndex({0 /* m_segmentIndex */, 0 /* m_pathIndex */}), ());
|
||||
|
||||
// Trying to get point before the beginning.
|
||||
TEST(!GetNextRoutePointIndex(resultTest, RoutePointIndex({0 /* m_segmentIndex */, 0 /* m_pathIndex */}), NumMwmIds(),
|
||||
false /* forward */, nextIndex),
|
||||
());
|
||||
}
|
||||
} // namespace turn_generator_test
|
||||
511
libs/routing/routing_tests/turns_sound_test.cpp
Normal file
511
libs/routing/routing_tests/turns_sound_test.cpp
Normal file
|
|
@ -0,0 +1,511 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/turns_notification_manager.hpp"
|
||||
#include "routing/turns_sound_settings.hpp"
|
||||
|
||||
#include <vector>
|
||||
|
||||
namespace turns_sound_test
|
||||
{
|
||||
using namespace std;
|
||||
using routing::turns::CarDirection;
|
||||
using routing::turns::TurnItemDist;
|
||||
using routing::turns::sound::NotificationManager;
|
||||
using routing::turns::sound::Settings;
|
||||
|
||||
// An error to compare two double after conversion feet to meters.
|
||||
double const kEps = 1.;
|
||||
|
||||
UNIT_TEST(TurnNotificationSettings_MetersTest)
|
||||
{
|
||||
Settings const settings(
|
||||
20 /* notificationTimeSeconds */, 200 /* minNotificationDistanceUnits */, 700 /* maxNotificationDistanceUnits */,
|
||||
5 /* m_startBeforeSeconds */, 25 /* m_minStartBeforeMeters */, 150 /* m_maxStartBeforeMeters */,
|
||||
170 /* m_minDistToSayNotificationMeters */, {100, 200, 300, 400, 500, 600, 700} /* soundedDistancesUnits */,
|
||||
measurement_utils::Units::Metric /* lengthUnits */);
|
||||
|
||||
TEST(settings.IsValid(), ());
|
||||
TEST(AlmostEqualAbs(settings.ConvertMetersPerSecondToUnitsPerSecond(20.), 20., kEps), ());
|
||||
TEST(AlmostEqualAbs(settings.ConvertMetersPerSecondToUnitsPerSecond(0.), 0., kEps), ());
|
||||
TEST(AlmostEqualAbs(settings.ConvertUnitsToMeters(300. /* distanceInUnits */), 300., kEps), ());
|
||||
TEST_EQUAL(settings.RoundByPresetSoundedDistancesUnits(300 /* distanceInUnits */), 300, ());
|
||||
TEST_EQUAL(settings.RoundByPresetSoundedDistancesUnits(0 /* distanceInUnits */), 100, ());
|
||||
|
||||
TEST_EQUAL(settings.ComputeTurnDistanceM(0. /* speedMetersPerSecond */), 200., ());
|
||||
TEST_EQUAL(settings.ComputeTurnDistanceM(10. /* speedMetersPerSecond */), 200., ());
|
||||
TEST_EQUAL(settings.ComputeTurnDistanceM(20. /* speedMetersPerSecond */), 400., ());
|
||||
TEST_EQUAL(settings.ComputeTurnDistanceM(35. /* speedMetersPerSecond */), 700., ());
|
||||
TEST_EQUAL(settings.ComputeTurnDistanceM(200. /* speedMetersPerSecond */), 700., ());
|
||||
|
||||
TEST_EQUAL(settings.ComputeDistToPronounceDistM(0. /* speedMetersPerSecond */), 25., ());
|
||||
TEST_EQUAL(settings.ComputeDistToPronounceDistM(10. /* speedMetersPerSecond */), 50., ());
|
||||
TEST_EQUAL(settings.ComputeDistToPronounceDistM(20. /* speedMetersPerSecond */), 100., ());
|
||||
TEST_EQUAL(settings.ComputeDistToPronounceDistM(35. /* speedMetersPerSecond */), 150., ());
|
||||
TEST_EQUAL(settings.ComputeDistToPronounceDistM(200. /* speedMetersPerSecond */), 150., ());
|
||||
}
|
||||
|
||||
UNIT_TEST(TurnNotificationSettings_FeetTest)
|
||||
{
|
||||
Settings const settings(
|
||||
20 /* notificationTimeSeconds */, 500 /* minNotificationDistanceUnits */, 2000 /* maxNotificationDistanceUnits */,
|
||||
5 /* m_startBeforeSeconds */, 25 /* m_minStartBeforeMeters */, 150 /* m_maxStartBeforeMeters */,
|
||||
170 /* m_minDistToSayNotificationMeters */, {200, 400, 600, 800, 1000, 1500, 2000} /* soundedDistancesUnits */,
|
||||
measurement_utils::Units::Imperial /* lengthUnits */);
|
||||
|
||||
TEST(settings.IsValid(), ());
|
||||
TEST(AlmostEqualAbs(settings.ConvertMetersPerSecondToUnitsPerSecond(20.), 65., kEps), ());
|
||||
TEST(AlmostEqualAbs(settings.ConvertMetersPerSecondToUnitsPerSecond(0.), 0., kEps), ());
|
||||
TEST(AlmostEqualAbs(settings.ConvertUnitsToMeters(300. /* distanceInUnits */), 91., kEps), ());
|
||||
TEST_EQUAL(settings.RoundByPresetSoundedDistancesUnits(500 /* distanceInUnits */), 600, ());
|
||||
TEST_EQUAL(settings.RoundByPresetSoundedDistancesUnits(0 /* distanceInUnits */), 200, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(TurnNotificationSettings_NotValidTest)
|
||||
{
|
||||
Settings settings1(
|
||||
20 /* notificationTimeSeconds */, 500 /* minNotificationDistanceUnits */, 2000 /* maxNotificationDistanceUnits */,
|
||||
5 /* m_startBeforeSeconds */, 25 /* m_minStartBeforeMeters */, 150 /* m_maxStartBeforeMeters */,
|
||||
170 /* m_minDistToSayNotificationMeters */, {200, 400, 800, 600, 1000, 1500, 2000} /* soundedDistancesUnits */,
|
||||
measurement_utils::Units::Imperial /* lengthUnits */);
|
||||
TEST(!settings1.IsValid(), ());
|
||||
|
||||
Settings settings2(20 /* notificationTimeSeconds */, 5000 /* minNotificationDistanceUnits */,
|
||||
2000 /* maxNotificationDistanceUnits */, 5 /* m_startBeforeSeconds */,
|
||||
25 /* m_minStartBeforeMeters */, 150 /* m_maxStartBeforeMeters */,
|
||||
170 /* m_minDistToSayNotificationMeters */,
|
||||
{200, 400, 600, 800, 1000, 1500, 2000} /* soundedDistancesUnits */,
|
||||
measurement_utils::Units::Metric /* lengthUnits */);
|
||||
TEST(!settings2.IsValid(), ());
|
||||
}
|
||||
|
||||
UNIT_TEST(TurnsSound_MetersTest)
|
||||
{
|
||||
string const engShortJson =
|
||||
"\
|
||||
{\
|
||||
\"in_600_meters\":\"In 600 meters.\",\
|
||||
\"make_a_right_turn\":\"Make a right turn.\"\
|
||||
}";
|
||||
auto notificationManager = NotificationManager::CreateNotificationManagerForTesting(
|
||||
5 /* startBeforeSeconds */, 10 /* minStartBeforeMeters */, 100 /* maxStartBeforeMeters */,
|
||||
100 /* minDistToSayNotificationMeters */, measurement_utils::Units::Metric, engShortJson,
|
||||
20 /* notificationTimeSecond */, 30.0 /* speedMeterPerSecond */);
|
||||
|
||||
vector<TurnItemDist> turns = {{{5 /* idx */, CarDirection::TurnRight}, 1000.}};
|
||||
vector<string> turnNotifications;
|
||||
|
||||
// Starting nearing the turnItem.
|
||||
// 1000 meters till the turn. No sound notifications is required.
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::None, ());
|
||||
|
||||
// 700 meters till the turn. No sound notifications is required.
|
||||
turns.front().m_distMeters = 700.;
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::None, ());
|
||||
|
||||
// 699 meters till the turn. It's time to pronounce the first voice notification.
|
||||
// Why? The current speed is 30 meters per seconds. According to correctSettingsMeters
|
||||
// we need to play the first voice notification 20 seconds before the turn.
|
||||
// Besides that we need 5 seconds (but 100 meters maximum) for playing the notification.
|
||||
// So we start playing the first notification when the distance till the turn is less
|
||||
// then 20 seconds * 30 meters per seconds + 100 meters = 700 meters.
|
||||
turns.front().m_distMeters = 699.;
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
vector<string> const expectedNotification1 = {{"In 600 meters. Make a right turn."}};
|
||||
TEST_EQUAL(turnNotifications, expectedNotification1, ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::None, ());
|
||||
|
||||
// 650 meters till the turn. No sound notifications is required.
|
||||
turns.front().m_distMeters = 650.;
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::None, ());
|
||||
|
||||
notificationManager.SetSpeedMetersPerSecond(32.);
|
||||
|
||||
// 150 meters till the turn. No sound notifications is required.
|
||||
turns.front().m_distMeters = 150.;
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::None, ());
|
||||
|
||||
// 100 meters till the turn. No sound notifications is required.
|
||||
turns.front().m_distMeters = 100.;
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::None, ());
|
||||
|
||||
// 99 meters till the turn. It's time to pronounce the second voice notification.
|
||||
turns.front().m_distMeters = 99.;
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
vector<string> const expectedNotification2 = {{"Make a right turn."}};
|
||||
TEST_EQUAL(turnNotifications, expectedNotification2, ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::None, ());
|
||||
|
||||
// 99 meters till the turn again. No sound notifications is required.
|
||||
turns.front().m_distMeters = 99.;
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::None, ());
|
||||
|
||||
// 50 meters till the turn. No sound notifications is required.
|
||||
turns.front().m_distMeters = 50.;
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::None, ());
|
||||
|
||||
// 0 meters till the turn. No sound notifications is required.
|
||||
turns.front().m_distMeters = 0.;
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::None, ());
|
||||
|
||||
TEST(notificationManager.IsEnabled(), ());
|
||||
}
|
||||
|
||||
// Test case:
|
||||
// - Two turns;
|
||||
// - They are close to each other;
|
||||
// So the first notification of the second turn shall be skipped.
|
||||
UNIT_TEST(TurnsSound_MetersTwoTurnsTest)
|
||||
{
|
||||
string const engShortJson =
|
||||
"\
|
||||
{\
|
||||
\"in_600_meters\":\"In 600 meters.\",\
|
||||
\"make_a_sharp_right_turn\":\"Make a sharp right turn.\",\
|
||||
\"enter_the_roundabout\":\"Enter the roundabout.\"\
|
||||
}";
|
||||
auto notificationManager = NotificationManager::CreateNotificationManagerForTesting(
|
||||
5 /* startBeforeSeconds */, 10 /* minStartBeforeMeters */, 100 /* maxStartBeforeMeters */,
|
||||
100 /* minDistToSayNotificationMeters */, measurement_utils::Units::Metric, engShortJson,
|
||||
20 /* notificationTimeSecond */, 35.0 /* speedMeterPerSecond */);
|
||||
|
||||
vector<TurnItemDist> turns = {{{5 /* idx */, CarDirection::TurnSharpRight}, 800.}};
|
||||
vector<string> turnNotifications;
|
||||
|
||||
// Starting nearing the first turn.
|
||||
// 800 meters till the turn. No sound notifications is required.
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
|
||||
// 700 meters till the turn. It's time to pronounce the first voice notification.
|
||||
// The speed is high.
|
||||
// The compensation of
|
||||
// NotificationManager::m_startBeforeSeconds/NotificationManager::m_minStartBeforeMeters/
|
||||
// NotificationManager::m_maxStartBeforeMeters is not enough.
|
||||
// The user will be closer to the turn while pronouncing despite the compensation.
|
||||
// So it should be pronounced "In 600 meters."
|
||||
turns.front().m_distMeters = 700.;
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
vector<string> const expectedNotification1 = {{"In 600 meters. Make a sharp right turn."}};
|
||||
TEST_EQUAL(turnNotifications, expectedNotification1, ());
|
||||
|
||||
notificationManager.SetSpeedMetersPerSecond(32.);
|
||||
|
||||
// 150 meters till the turn. No sound notifications is required.
|
||||
turns.front().m_distMeters = 150.;
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
|
||||
// 99 meters till the turn. It's time to pronounce the second voice notification.
|
||||
turns.front().m_distMeters = 99.;
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
vector<string> const expectedNotification2 = {{"Make a sharp right turn."}};
|
||||
TEST_EQUAL(turnNotifications, expectedNotification2, ());
|
||||
|
||||
notificationManager.SetSpeedMetersPerSecond(10.);
|
||||
|
||||
// 0 meters till the turn. No sound notifications is required.
|
||||
turns.front().m_distMeters = 0.;
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
|
||||
vector<TurnItemDist> turns2 = {{{11 /* idx */, CarDirection::EnterRoundAbout, 2 /* exitNum */}, 60.}};
|
||||
|
||||
// Starting nearing the second turn.
|
||||
notificationManager.GenerateTurnNotifications(turns2, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
|
||||
// 40 meters till the second turn. It's time to pronounce the second voice notification
|
||||
// without the first one.
|
||||
turns2.front().m_distMeters = 40.;
|
||||
notificationManager.GenerateTurnNotifications(turns2, turnNotifications);
|
||||
vector<string> const expectedNotification3 = {{"Enter the roundabout."}};
|
||||
TEST_EQUAL(turnNotifications, expectedNotification3, ());
|
||||
|
||||
TEST(notificationManager.IsEnabled(), ());
|
||||
}
|
||||
|
||||
UNIT_TEST(TurnsSound_FeetTest)
|
||||
{
|
||||
string const engShortJson =
|
||||
"\
|
||||
{\
|
||||
\"in_2000_feet\":\"In 2000 feet.\",\
|
||||
\"enter_the_roundabout\":\"Enter the roundabout.\"\
|
||||
}";
|
||||
auto notificationManager = NotificationManager::CreateNotificationManagerForTesting(
|
||||
5 /* startBeforeSeconds */, 10 /* minStartBeforeMeters */, 100 /* maxStartBeforeMeters */,
|
||||
100 /* minDistToSayNotificationMeters */, measurement_utils::Units::Imperial, engShortJson,
|
||||
20 /* notificationTimeSecond */, 30.0 /* speedMeterPerSecond */);
|
||||
|
||||
vector<TurnItemDist> turns = {{{7 /* idx */, CarDirection::EnterRoundAbout, 3 /* exitNum */}, 1000.}};
|
||||
vector<string> turnNotifications;
|
||||
|
||||
// Starting nearing the turnItem.
|
||||
// 1000 meters till the turn. No sound notifications is required.
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
|
||||
// 700 meters till the turn. No sound notifications is required.
|
||||
turns.front().m_distMeters = 700.;
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
|
||||
// 699 meters till the turn. It's time to pronounce the first voice notification.
|
||||
// Why? The current speed is 30 meters per seconds. According to correctSettingsMeters
|
||||
// we need to play the first voice notification 20 seconds before the turn.
|
||||
// Besides that we need 5 seconds (but 100 meters maximum) for playing the notification.
|
||||
// So we start playing the first notification when the distance till the turn is less
|
||||
// then 20 seconds * 30 meters per seconds + 100 meters = 700 meters.
|
||||
turns.front().m_distMeters = 699.;
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
vector<string> const expectedNotification1 = {{"In 2000 feet. Enter the roundabout."}};
|
||||
TEST_EQUAL(turnNotifications, expectedNotification1, ());
|
||||
|
||||
// 650 meters till the turn. No sound notifications is required.
|
||||
turns.front().m_distMeters = 650.;
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
|
||||
// 150 meters till the turn. No sound notifications is required.
|
||||
turns.front().m_distMeters = 150.;
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
|
||||
// 100 meters till the turn. No sound notifications is required.
|
||||
turns.front().m_distMeters = 100.;
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
|
||||
// 99 meters till the turn. It's time to pronounce the second voice notification.
|
||||
turns.front().m_distMeters = 99.;
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
vector<string> const expectedNotification2 = {{"Enter the roundabout."}};
|
||||
TEST_EQUAL(turnNotifications, expectedNotification2, ());
|
||||
|
||||
// 99 meters till the turn again. No sound notifications is required.
|
||||
turns.front().m_distMeters = 99.;
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
|
||||
// 50 meters till the turn. No sound notifications is required.
|
||||
turns.front().m_distMeters = 50.;
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
|
||||
// 0 meters till the turn. No sound notifications is required.
|
||||
turns.front().m_distMeters = 0.;
|
||||
notificationManager.GenerateTurnNotifications(turns, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
|
||||
TEST(notificationManager.IsEnabled(), ());
|
||||
}
|
||||
|
||||
UNIT_TEST(TurnsSound_ComposedTurnTest)
|
||||
{
|
||||
string const engShortJson =
|
||||
"\
|
||||
{\
|
||||
\"in_600_meters\":\"In 600 meters.\",\
|
||||
\"in_200_meters\":\"In 200 meters.\",\
|
||||
\"make_a_right_turn\":\"Turn right.\",\
|
||||
\"enter_the_roundabout\":\"Enter the roundabout.\",\
|
||||
\"then\":\"Then.\",\
|
||||
\"you_have_reached_the_destination\":\"You have reached the destination.\"\
|
||||
}";
|
||||
auto notificationManager = NotificationManager::CreateNotificationManagerForTesting(
|
||||
5 /* startBeforeSeconds */, 10 /* minStartBeforeMeters */, 100 /* maxStartBeforeMeters */,
|
||||
100 /* minDistToSayNotificationMeters */, measurement_utils::Units::Metric, engShortJson,
|
||||
30.0 /* notificationTimeSecond */, 20.0 /* speedMeterPerSecond */);
|
||||
|
||||
vector<string> turnNotifications;
|
||||
|
||||
// Starting nearing the first turn.
|
||||
// 800 meters till the first turn.
|
||||
vector<TurnItemDist> const turns1 = {{{5 /* idx */, CarDirection::TurnRight}, 800. /* m_distMeters */},
|
||||
{{10 /* idx */, CarDirection::EnterRoundAbout}, 1000. /* m_distMeters */}};
|
||||
notificationManager.GenerateTurnNotifications(turns1, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::None, ());
|
||||
|
||||
// 620 meters till the first turn.
|
||||
turnNotifications.clear();
|
||||
vector<TurnItemDist> const turns2 = {{{5 /* idx */, CarDirection::TurnRight}, 620. /* m_distMeters */},
|
||||
{{10 /* idx */, CarDirection::EnterRoundAbout}, 665. /* m_distMeters */}};
|
||||
vector<string> const expectedNotification2 = {{"In 600 meters. Turn right."}, {"Then. Enter the roundabout."}};
|
||||
notificationManager.GenerateTurnNotifications(turns2, turnNotifications);
|
||||
TEST_EQUAL(turnNotifications, expectedNotification2, ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::EnterRoundAbout, ());
|
||||
|
||||
// 300 meters till the first turn.
|
||||
turnNotifications.clear();
|
||||
vector<TurnItemDist> const turns3 = {{{5 /* idx */, CarDirection::TurnRight}, 300. /* m_distMeters */},
|
||||
{{10 /* idx */, CarDirection::EnterRoundAbout}, 500. /* m_distMeters */}};
|
||||
notificationManager.GenerateTurnNotifications(turns3, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::EnterRoundAbout, ());
|
||||
|
||||
// 20 meters till the first turn.
|
||||
turnNotifications.clear();
|
||||
vector<TurnItemDist> const turns4 = {{{5 /* idx */, CarDirection::TurnRight}, 20. /* m_distMeters */},
|
||||
{{10 /* idx */, CarDirection::EnterRoundAbout}, 220. /* m_distMeters */}};
|
||||
vector<string> const expectedNotification4 = {{"Turn right."}, {"Then. In 200 meters. Enter the roundabout."}};
|
||||
notificationManager.GenerateTurnNotifications(turns4, turnNotifications);
|
||||
TEST_EQUAL(turnNotifications, expectedNotification4, ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::EnterRoundAbout, ());
|
||||
|
||||
// After the first turn.
|
||||
turnNotifications.clear();
|
||||
vector<TurnItemDist> const turns5 = {
|
||||
{{10 /* idx */, CarDirection::EnterRoundAbout}, 180. /* m_distMeters */},
|
||||
{{15 /* idx */, CarDirection::ReachedYourDestination}, 1180. /* m_distMeters */}};
|
||||
notificationManager.GenerateTurnNotifications(turns5, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::None, ());
|
||||
|
||||
// Just before the second turn.
|
||||
turnNotifications.clear();
|
||||
vector<TurnItemDist> const turns6 = {
|
||||
{{10 /* idx */, CarDirection::EnterRoundAbout}, 10. /* m_distMeters */},
|
||||
{{15 /* idx */, CarDirection::ReachedYourDestination}, 1010. /* m_distMeters */}};
|
||||
vector<string> const expectedNotification6 = {{"Enter the roundabout."}};
|
||||
notificationManager.GenerateTurnNotifications(turns6, turnNotifications);
|
||||
TEST_EQUAL(turnNotifications, expectedNotification6, ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::None, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(TurnsSound_RoundaboutTurnTest)
|
||||
{
|
||||
string const engShortJson =
|
||||
"\
|
||||
{\
|
||||
\"enter_the_roundabout\":\"Enter the roundabout.\",\
|
||||
\"leave_the_roundabout\":\"Leave the roundabout.\",\
|
||||
\"take_the_1_exit\":\"Take the first exit.\",\
|
||||
\"take_the_2_exit\":\"Take the second exit.\",\
|
||||
\"take_the_4_exit\":\"Take the fourth exit.\",\
|
||||
\"in_600_meters\":\"In 600 meters.\",\
|
||||
\"in_1_kilometer\":\"In 1 kilometer.\",\
|
||||
\"then\":\"Then.\"\
|
||||
}";
|
||||
auto notificationManager = NotificationManager::CreateNotificationManagerForTesting(
|
||||
5 /* startBeforeSeconds */, 10 /* minStartBeforeMeters */, 100 /* maxStartBeforeMeters */,
|
||||
100 /* minDistToSayNotificationMeters */, measurement_utils::Units::Metric, engShortJson,
|
||||
30 /* notificationTimeSecond */, 20.0 /* speedMeterPerSecond */);
|
||||
|
||||
vector<string> turnNotifications;
|
||||
|
||||
// Starting nearing the first turn.
|
||||
// 1000 meters till the first turn.
|
||||
vector<TurnItemDist> const turns1 = {
|
||||
{{5 /* idx */, CarDirection::EnterRoundAbout, 2 /* m_exitNum */}, 1000. /* m_distMeters */},
|
||||
{{10 /* idx */, CarDirection::LeaveRoundAbout, 2 /* m_exitNum */}, 2000. /* m_distMeters */}};
|
||||
notificationManager.GenerateTurnNotifications(turns1, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::None, ());
|
||||
|
||||
// 620 meters till the first turn.
|
||||
vector<TurnItemDist> const turns2 = {
|
||||
{{5 /* idx */, CarDirection::EnterRoundAbout, 2 /* m_exitNum */}, 620. /* m_distMeters */},
|
||||
{{10 /* idx */, CarDirection::LeaveRoundAbout, 2 /* m_exitNum */}, 1620. /* m_distMeters */}};
|
||||
vector<string> const expectedNotification2 = {{"In 600 meters. Enter the roundabout."},
|
||||
{"Then. In 1 kilometer. Take the second exit."}};
|
||||
notificationManager.GenerateTurnNotifications(turns2, turnNotifications);
|
||||
TEST_EQUAL(turnNotifications, expectedNotification2, ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::None, ());
|
||||
|
||||
// 3 meters till the first turn.
|
||||
vector<TurnItemDist> const turns3 = {
|
||||
{{5 /* idx */, CarDirection::EnterRoundAbout, 2 /* m_exitNum */}, 3. /* m_distMeters */},
|
||||
{{10 /* idx */, CarDirection::LeaveRoundAbout, 2 /* m_exitNum */}, 1003. /* m_distMeters */}};
|
||||
vector<string> const expectedNotification3 = {{"Enter the roundabout."},
|
||||
{"Then. In 1 kilometer. Take the second exit."}};
|
||||
notificationManager.GenerateTurnNotifications(turns3, turnNotifications);
|
||||
TEST_EQUAL(turnNotifications, expectedNotification3, ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::None, ());
|
||||
|
||||
// 900 meters till the second turn.
|
||||
vector<TurnItemDist> const turns4 = {
|
||||
{{10 /* idx */, CarDirection::LeaveRoundAbout, 2 /* m_exitNum */}, 900. /* m_distMeters */},
|
||||
{{15 /* idx */, CarDirection::EnterRoundAbout, 1 /* m_exitNum */}, 1900. /* m_distMeters */}};
|
||||
notificationManager.GenerateTurnNotifications(turns4, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::None, ());
|
||||
|
||||
// 300 meters till the second turn.
|
||||
vector<TurnItemDist> const turns5 = {
|
||||
{{10 /* idx */, CarDirection::LeaveRoundAbout, 2 /* m_exitNum */}, 300. /* m_distMeters */},
|
||||
{{15 /* idx */, CarDirection::EnterRoundAbout, 1 /* m_exitNum */}, 1300. /* m_distMeters */}};
|
||||
notificationManager.GenerateTurnNotifications(turns5, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::None, ());
|
||||
|
||||
// 3 meters till the second turn.
|
||||
vector<TurnItemDist> const turns6 = {
|
||||
{{10 /* idx */, CarDirection::LeaveRoundAbout, 2 /* m_exitNum */}, 3. /* m_distMeters */},
|
||||
{{15 /* idx */, CarDirection::EnterRoundAbout, 1 /* m_exitNum */}, 1003. /* m_distMeters */}};
|
||||
vector<string> const expectedNotification6 = {{"Leave the roundabout."}};
|
||||
notificationManager.GenerateTurnNotifications(turns6, turnNotifications);
|
||||
TEST_EQUAL(turnNotifications, expectedNotification6, ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::None, ());
|
||||
|
||||
// 5 meters till the third turn.
|
||||
vector<TurnItemDist> const turns7 = {
|
||||
{{15 /* idx */, CarDirection::EnterRoundAbout, 1 /* m_exitNum */}, 5. /* m_distMeters */},
|
||||
{{20 /* idx */, CarDirection::LeaveRoundAbout, 1 /* m_exitNum */}, 1005. /* m_distMeters */}};
|
||||
vector<string> const expectedNotification7 = {{"Enter the roundabout."},
|
||||
{"Then. In 1 kilometer. Take the first exit."}};
|
||||
notificationManager.GenerateTurnNotifications(turns7, turnNotifications); // The first notification fast forwarding.
|
||||
notificationManager.GenerateTurnNotifications(turns7, turnNotifications);
|
||||
TEST_EQUAL(turnNotifications, expectedNotification7, ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::None, ());
|
||||
|
||||
// 900 meters till the 4th turn.
|
||||
notificationManager.Reset();
|
||||
vector<TurnItemDist> const turns8 = {
|
||||
{{25 /* idx */, CarDirection::EnterRoundAbout, 4 /* m_exitNum */}, 900. /* m_distMeters */},
|
||||
{{30 /* idx */, CarDirection::LeaveRoundAbout, 4 /* m_exitNum */}, 1200. /* m_distMeters */}};
|
||||
notificationManager.GenerateTurnNotifications(turns8, turnNotifications);
|
||||
TEST(turnNotifications.empty(), ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::None, ());
|
||||
|
||||
// 620 meters till the 4th turn.
|
||||
vector<TurnItemDist> const turns9 = {
|
||||
{{25 /* idx */, CarDirection::EnterRoundAbout, 4 /* m_exitNum */}, 620. /* m_distMeters */},
|
||||
{{30 /* idx */, CarDirection::LeaveRoundAbout, 4 /* m_exitNum */}, 1000. /* m_distMeters */}};
|
||||
vector<string> const expectedNotification9 = {{"In 600 meters. Enter the roundabout."},
|
||||
{"Then. Take the fourth exit."}};
|
||||
notificationManager.GenerateTurnNotifications(turns9, turnNotifications,
|
||||
routing::RouteSegment::RoadNameInfo("Main street"));
|
||||
TEST_EQUAL(turnNotifications, expectedNotification9, ());
|
||||
TEST_EQUAL(notificationManager.GetSecondTurnNotification(), CarDirection::LeaveRoundAbout, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(GetJsonBufferTest)
|
||||
{
|
||||
string const localeNameEn = "en";
|
||||
string jsonBuffer;
|
||||
TEST(GetJsonBuffer(platform::TextSource::TtsSound, localeNameEn, jsonBuffer), ());
|
||||
TEST(!jsonBuffer.empty(), ());
|
||||
|
||||
string const localeNameRu = "ru";
|
||||
jsonBuffer.clear();
|
||||
TEST(GetJsonBuffer(platform::TextSource::TtsSound, localeNameRu, jsonBuffer), ());
|
||||
TEST(!jsonBuffer.empty(), ());
|
||||
}
|
||||
} // namespace turns_sound_test
|
||||
467
libs/routing/routing_tests/turns_tts_text_tests.cpp
Normal file
467
libs/routing/routing_tests/turns_tts_text_tests.cpp
Normal file
|
|
@ -0,0 +1,467 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/route.hpp"
|
||||
#include "routing/turns_sound_settings.hpp"
|
||||
#include "routing/turns_tts_text.hpp"
|
||||
#include "routing/turns_tts_text_i18n.hpp"
|
||||
|
||||
#include "base/string_utils.hpp"
|
||||
|
||||
#include <cstring>
|
||||
#include <string>
|
||||
|
||||
namespace turns_tts_text_tests
|
||||
{
|
||||
using namespace routing::turns;
|
||||
using namespace routing::turns::sound;
|
||||
using namespace std;
|
||||
using namespace strings;
|
||||
|
||||
using measurement_utils::Units;
|
||||
|
||||
bool PairDistEquals(PairDist const & lhs, PairDist const & rhs)
|
||||
{
|
||||
return lhs.first == rhs.first && strcmp(lhs.second, rhs.second) == 0;
|
||||
}
|
||||
|
||||
UNIT_TEST(GetDistanceTextIdMetersTest)
|
||||
{
|
||||
TEST_EQUAL(GetDistanceTextId({500, 0, false, CarDirection::TurnRight, Units::Metric}), "in_500_meters", ());
|
||||
|
||||
// Notification const notification2(500, 0, true, CarDirection::TurnRight, Units::Metric);
|
||||
// TEST_EQUAL(GetDistanceTextId(notification2), "then", ());
|
||||
|
||||
TEST_EQUAL(GetDistanceTextId({200, 0, false, CarDirection::TurnRight, Units::Metric}), "in_200_meters", ());
|
||||
TEST_EQUAL(GetDistanceTextId({2000, 0, false, CarDirection::TurnRight, Units::Metric}), "in_2_kilometers", ());
|
||||
|
||||
/// @see DistToTextId.
|
||||
TEST_EQUAL(GetDistanceTextId({130, 0, false, CarDirection::TurnRight, Units::Metric}), "in_100_meters", ());
|
||||
TEST_EQUAL(GetDistanceTextId({135, 0, false, CarDirection::TurnRight, Units::Metric}), "in_200_meters", ());
|
||||
}
|
||||
|
||||
UNIT_TEST(GetDistanceTextIdFeetTest)
|
||||
{
|
||||
TEST_EQUAL(GetDistanceTextId({500, 0, false, CarDirection::TurnRight, Units::Imperial}), "in_500_feet", ());
|
||||
|
||||
// Notification const notification2(500, 0, true, CarDirection::TurnRight, Units::Imperial);
|
||||
// TEST_EQUAL(GetDistanceTextId(notification2), "then", ());
|
||||
|
||||
TEST_EQUAL(GetDistanceTextId({800, 0, false, CarDirection::TurnRight, Units::Imperial}), "in_800_feet", ());
|
||||
TEST_EQUAL(GetDistanceTextId({5000, 0, false, CarDirection::TurnRight, Units::Imperial}), "in_5000_feet", ());
|
||||
}
|
||||
|
||||
UNIT_TEST(GetRoundaboutTextIdTest)
|
||||
{
|
||||
// Notification(uint32_t distanceUnits, uint8_t exitNum, bool useThenInsteadOfDistance,
|
||||
// CarDirection turnDir, ::Settings::Units lengthUnits)
|
||||
Notification const notification1(500, 0, false, CarDirection::LeaveRoundAbout, Units::Imperial);
|
||||
TEST_EQUAL(GetRoundaboutTextId(notification1), "leave_the_roundabout", ());
|
||||
Notification const notification2(0, 3, true, CarDirection::LeaveRoundAbout, Units::Imperial);
|
||||
TEST_EQUAL(GetRoundaboutTextId(notification2), "take_the_3_exit", ());
|
||||
Notification const notification3(0, 7, true, CarDirection::LeaveRoundAbout, Units::Metric);
|
||||
TEST_EQUAL(GetRoundaboutTextId(notification3), "take_the_7_exit", ());
|
||||
Notification const notification4(0, 15, true, CarDirection::LeaveRoundAbout, Units::Metric);
|
||||
TEST_EQUAL(GetRoundaboutTextId(notification4), "leave_the_roundabout", ());
|
||||
}
|
||||
|
||||
UNIT_TEST(GetYouArriveTextIdTest)
|
||||
{
|
||||
// Notification(uint32_t distanceUnits, uint8_t exitNum, bool useThenInsteadOfDistance,
|
||||
// CarDirection turnDir, ::Settings::Units lengthUnits)
|
||||
Notification const notification1(500, 0, false, CarDirection::ReachedYourDestination, Units::Imperial);
|
||||
TEST_EQUAL(GetYouArriveTextId(notification1), "destination", ());
|
||||
Notification const notification2(0, 0, false, CarDirection::ReachedYourDestination, Units::Metric);
|
||||
TEST_EQUAL(GetYouArriveTextId(notification2), "you_have_reached_the_destination", ());
|
||||
Notification const notification3(0, 0, true, CarDirection::ReachedYourDestination, Units::Metric);
|
||||
TEST_EQUAL(GetYouArriveTextId(notification3), "destination", ());
|
||||
}
|
||||
|
||||
UNIT_TEST(GetDirectionTextIdTest)
|
||||
{
|
||||
// Notification(uint32_t distanceUnits, uint8_t exitNum, bool useThenInsteadOfDistance,
|
||||
// CarDirection turnDir, ::Settings::Units lengthUnits)
|
||||
Notification const notification1(500, 0, false, CarDirection::TurnRight, Units::Imperial);
|
||||
TEST_EQUAL(GetDirectionTextId(notification1), "make_a_right_turn", ());
|
||||
Notification const notification2(1000, 0, false, CarDirection::GoStraight, Units::Metric);
|
||||
TEST_EQUAL(GetDirectionTextId(notification2), "go_straight", ());
|
||||
Notification const notification3(700, 0, false, CarDirection::UTurnLeft, Units::Metric);
|
||||
TEST_EQUAL(GetDirectionTextId(notification3), "make_a_u_turn", ());
|
||||
Notification const notification4(200, 0, false, CarDirection::ReachedYourDestination, Units::Metric);
|
||||
TEST_EQUAL(GetDirectionTextId(notification4), "destination", ());
|
||||
Notification const notification5(0, 0, false, CarDirection::ReachedYourDestination, Units::Metric);
|
||||
TEST_EQUAL(GetDirectionTextId(notification5), "you_have_reached_the_destination", ());
|
||||
}
|
||||
|
||||
UNIT_TEST(GetTtsTextTest)
|
||||
{
|
||||
string const engShortJson =
|
||||
R"({
|
||||
"in_300_meters":"In 300 meters.",
|
||||
"in_500_meters":"In 500 meters.",
|
||||
"then":"Then.",
|
||||
"make_a_right_turn":"Make a right turn.",
|
||||
"make_a_left_turn":"Make a left turn.",
|
||||
"you_have_reached_the_destination":"You have reached the destination."
|
||||
})";
|
||||
|
||||
string const rusShortJson =
|
||||
R"({
|
||||
"in_300_meters":"Через 300 метров.",
|
||||
"in_500_meters":"Через 500 метров.",
|
||||
"then":"Затем.",
|
||||
"make_a_right_turn":"Поворот направо.",
|
||||
"make_a_left_turn":"Поворот налево.",
|
||||
"you_have_reached_the_destination":"Вы достигли конца маршрута."
|
||||
})";
|
||||
|
||||
GetTtsText getTtsText;
|
||||
// Notification(uint32_t distanceUnits, uint8_t exitNum, bool useThenInsteadOfDistance,
|
||||
// CarDirection turnDir, Settings::Units lengthUnits)
|
||||
Notification const notification1(500, 0, false, CarDirection::TurnRight, Units::Metric);
|
||||
Notification const notification2(300, 0, false, CarDirection::TurnLeft, Units::Metric);
|
||||
Notification const notification3(0, 0, false, CarDirection::ReachedYourDestination, Units::Metric);
|
||||
Notification const notification4(0, 0, true, CarDirection::TurnLeft, Units::Metric);
|
||||
|
||||
getTtsText.ForTestingSetLocaleWithJson(engShortJson, "en");
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification1), "In 500 meters. Make a right turn.", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification2), "In 300 meters. Make a left turn.", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification3), "You have reached the destination.", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification4), "Then. Make a left turn.", ());
|
||||
|
||||
getTtsText.ForTestingSetLocaleWithJson(rusShortJson, "ru");
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification1), "Через 500 метров. Поворот направо.", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification2), "Через 300 метров. Поворот налево.", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification3), "Вы достигли конца маршрута.", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification4), "Затем. Поворот налево.", ());
|
||||
}
|
||||
|
||||
UNIT_TEST(EndsInAcronymOrNumTest)
|
||||
{
|
||||
// actual JSON doesn't matter for this test
|
||||
string const huShortJson =
|
||||
R"({
|
||||
"in_300_meters":"Háromszáz méter után"
|
||||
})";
|
||||
|
||||
GetTtsText getTtsText;
|
||||
getTtsText.ForTestingSetLocaleWithJson(huShortJson, "hu");
|
||||
TEST_EQUAL(EndsInAcronymOrNum(strings::MakeUniString("Main Street")), false, ());
|
||||
TEST_EQUAL(EndsInAcronymOrNum(strings::MakeUniString("Main STREET")), true, ());
|
||||
TEST_EQUAL(EndsInAcronymOrNum(strings::MakeUniString("Highway A")), true, ());
|
||||
TEST_EQUAL(EndsInAcronymOrNum(strings::MakeUniString("Highway AA")), true, ());
|
||||
TEST_EQUAL(EndsInAcronymOrNum(strings::MakeUniString("Highway Aa")), false, ());
|
||||
TEST_EQUAL(EndsInAcronymOrNum(strings::MakeUniString("Highway aA")), false, ());
|
||||
TEST_EQUAL(EndsInAcronymOrNum(strings::MakeUniString("Highway 50")), true, ());
|
||||
TEST_EQUAL(EndsInAcronymOrNum(strings::MakeUniString("Highway 50A")), true, ());
|
||||
TEST_EQUAL(EndsInAcronymOrNum(strings::MakeUniString("Highway A50")), true, ());
|
||||
TEST_EQUAL(EndsInAcronymOrNum(strings::MakeUniString("Highway a50")), false, ());
|
||||
TEST_EQUAL(EndsInAcronymOrNum(strings::MakeUniString("Highway 50a")), false, ());
|
||||
TEST_EQUAL(EndsInAcronymOrNum(strings::MakeUniString("50 Highway")), false, ());
|
||||
TEST_EQUAL(EndsInAcronymOrNum(strings::MakeUniString("AA Highway")), false, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(GetTtsStreetTextTest)
|
||||
{
|
||||
// we can use "NULL" to indicate that the regular "_turn" string should be used and not "_turn_street"
|
||||
string const engShortJson =
|
||||
R"({
|
||||
"in_300_meters":"In 300 meters.",
|
||||
"in_500_meters":"In 500 meters.",
|
||||
"then":"Then.",
|
||||
"onto":"onto",
|
||||
"make_a_right_turn":"Make a right turn.",
|
||||
"make_a_left_turn":"Make a left turn.",
|
||||
"make_a_right_turn_street":"NULL",
|
||||
"make_a_left_turn_street":"NULL",
|
||||
"take_exit_number":"Take exit",
|
||||
"dist_direction_onto_street":"%1$s %2$s %3$s %4$s",
|
||||
"you_have_reached_the_destination":"You have reached the destination."
|
||||
})";
|
||||
|
||||
string const jaShortJson =
|
||||
R"({
|
||||
"in_300_meters":"三百メートル先",
|
||||
"in_500_meters":"五百メートル先",
|
||||
"then":"その先",
|
||||
"onto":"に入ります",
|
||||
"make_a_right_turn":"右折です。",
|
||||
"make_a_left_turn":"左折です。",
|
||||
"make_a_right_turn_street":"右折し",
|
||||
"make_a_left_turn_street":"左折し",
|
||||
"dist_direction_onto_street":"%1$s%2$s %4$s %3$s",
|
||||
"you_have_reached_the_destination":"到着。"
|
||||
})";
|
||||
|
||||
string const faShortJson =
|
||||
R"({
|
||||
"in_300_meters":"ﺩﺭ ﺲﯿﺻﺩ ﻢﺗﺮﯾ",
|
||||
"in_500_meters":"ﺩﺭ ﭖﺎﻨﺻﺩ ﻢﺗﺮﯾ",
|
||||
"then":"ﺲﭙﺳ",
|
||||
"onto":"ﺐﻫ",
|
||||
"make_a_right_turn":"ﺐﻫ ﺭﺎﺴﺗ ﺐﭙﯿﭽﯾﺩ.",
|
||||
"make_a_left_turn":"ﺐﻫ ﭻﭘ ﺐﭙﯿﭽﯾﺩ.",
|
||||
"dist_direction_onto_street":"%1$s %2$s %3$s %4$s",
|
||||
"you_have_reached_the_destination":"ﺶﻣﺍ ﺮﺴﯾﺪﻫ ﺎﯾﺩ."
|
||||
})";
|
||||
|
||||
string const arShortJson =
|
||||
R"({
|
||||
"in_300_meters":"ﺐﻋﺩ ﺙﻼﺜﻤﺋﺓ ﻢﺗﺭ",
|
||||
"in_500_meters":"ﺐﻋﺩ ﺦﻤﺴﻤﺋﺓ ﻢﺗﺭ",
|
||||
"then":"ﺚﻣ",
|
||||
"onto":"ﺈﻟﻯ",
|
||||
"make_a_right_turn":"ﺎﻨﻌﻄﻓ ﻲﻤﻴﻧﺍ.",
|
||||
"make_a_left_turn":"ﺎﻨﻌﻄﻓ ﻲﺳﺍﺭﺍ.",
|
||||
"dist_direction_onto_street":"%1$s %2$s %3$s %4$s",
|
||||
"you_have_reached_the_destination":"ﻞﻗﺩ ﻮﺼﻠﺗ."
|
||||
})";
|
||||
|
||||
string const huShortJson =
|
||||
R"({
|
||||
"in_300_meters":"Háromszáz méter után",
|
||||
"in_500_meters":"Ötszáz méter után",
|
||||
"go_straight":"Hajtson előre.",
|
||||
"then":"Majd",
|
||||
"onto":"a",
|
||||
"make_a_right_turn":"Forduljon jobbra.",
|
||||
"make_a_left_turn":"Forduljon balra.",
|
||||
"dist_direction_onto_street":"%1$s %2$s %3$s %4$s-re"
|
||||
})";
|
||||
|
||||
string const nlShortJson =
|
||||
R"({
|
||||
"in_300_meters":"Over driehonderd meter",
|
||||
"in_500_meters":"Over vijfhonderd meter",
|
||||
"go_straight":"Rij rechtdoor.",
|
||||
"then":"Daarna",
|
||||
"onto":"naar",
|
||||
"make_a_right_turn":"Sla rechtsaf.",
|
||||
"make_a_right_turn_street":"naar rechts afslaan",
|
||||
"make_a_left_turn":"Sla linksaf.",
|
||||
"make_a_left_turn_street":"naar links afslaan",
|
||||
"dist_direction_onto_street":"%5$s %1$s %2$s %3$s %4$s",
|
||||
"take_exit_number":"Verlaat naar",
|
||||
"take_exit_number_street_verb":"Neem"
|
||||
})";
|
||||
|
||||
GetTtsText getTtsText;
|
||||
// Notification(uint32_t distanceUnits, uint8_t exitNum, bool useThenInsteadOfDistance,
|
||||
// CarDirection turnDir, Settings::Units lengthUnits, routing::RouteSegment::RoadNameInfo nextStreetInfo)
|
||||
|
||||
Notification const notification1(500, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("Main Street"));
|
||||
Notification const notification2(300, 0, false, CarDirection::TurnLeft, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("Main Street"));
|
||||
Notification const notification3(300, 0, false, CarDirection::TurnLeft, measurement_utils::Units::Metric);
|
||||
Notification const notification4(0, 0, true, CarDirection::TurnLeft, measurement_utils::Units::Metric);
|
||||
Notification const notification5(300, 0, false, CarDirection::TurnLeft, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("Capital Parkway"));
|
||||
Notification const notification6(1000, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("Woodhaven Boulevard", "NY 25", "195"));
|
||||
Notification const notification7(1000, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("Woodhaven Boulevard", "NY 25", "1950"));
|
||||
|
||||
getTtsText.ForTestingSetLocaleWithJson(engShortJson, "en");
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification1), "In 500 meters Make a right turn onto Main Street", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification2), "In 300 meters Make a left turn onto Main Street", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification3), "In 300 meters. Make a left turn.", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification4), "Then. Make a left turn.", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification6), "Take exit 195; NY 25; Woodhaven Boulevard", ());
|
||||
|
||||
getTtsText.ForTestingSetLocaleWithJson(jaShortJson, "ja");
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification1), "五百メートル先右折し Main Street に入ります", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification2), "三百メートル先左折し Main Street に入ります", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification3), "三百メートル先左折です。", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification4), "その先左折です。", ());
|
||||
|
||||
getTtsText.ForTestingSetLocaleWithJson(faShortJson, "fa");
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification1), "ﺩﺭ ﭖﺎﻨﺻﺩ ﻢﺗﺮﯾ ﺐﻫ ﺭﺎﺴﺗ ﺐﭙﯿﭽﯾﺩ ﺐﻫ Main Street", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification2), "ﺩﺭ ﺲﯿﺻﺩ ﻢﺗﺮﯾ ﺐﻫ ﭻﭘ ﺐﭙﯿﭽﯾﺩ ﺐﻫ Main Street", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification3), "ﺩﺭ ﺲﯿﺻﺩ ﻢﺗﺮﯾ ﺐﻫ ﭻﭘ ﺐﭙﯿﭽﯾﺩ.", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification4), "ﺲﭙﺳ ﺐﻫ ﭻﭘ ﺐﭙﯿﭽﯾﺩ.", ());
|
||||
|
||||
getTtsText.ForTestingSetLocaleWithJson(arShortJson, "ar");
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification1), "ﺐﻋﺩ ﺦﻤﺴﻤﺋﺓ ﻢﺗﺭ ﺎﻨﻌﻄﻓ ﻲﻤﻴﻧﺍ ﺈﻟﻯ Main Street", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification2), "ﺐﻋﺩ ﺙﻼﺜﻤﺋﺓ ﻢﺗﺭ ﺎﻨﻌﻄﻓ ﻲﺳﺍﺭﺍ ﺈﻟﻯ Main Street", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification3), "ﺐﻋﺩ ﺙﻼﺜﻤﺋﺓ ﻢﺗﺭ ﺎﻨﻌﻄﻓ ﻲﺳﺍﺭﺍ.", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification4), "ﺚﻣ ﺎﻨﻌﻄﻓ ﻲﺳﺍﺭﺍ.", ());
|
||||
|
||||
getTtsText.ForTestingSetLocaleWithJson(huShortJson, "hu");
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification1), "Ötszáz méter után Forduljon jobbra a Main Streetre", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification2), "Háromszáz méter után Forduljon balra a Main Streetre", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification3), "Háromszáz méter után Forduljon balra.", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification4), "Majd Forduljon balra.", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification5), "Háromszáz méter után Forduljon balra a Capital Parkwayra",
|
||||
()); // -ra suffix for "back" vowel endings
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification6), "Forduljon jobbra a 195; NY 25; Woodhaven Boulevardra",
|
||||
()); // a for prefixing "hundred ninety five"
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification7), "Forduljon jobbra az 1950; NY 25; Woodhaven Boulevardra",
|
||||
()); // az for prefixing "thousand nine hundred fifty"
|
||||
Notification const notificationHuA(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("Woodhaven Boulevard", "NY 25", "19"));
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHuA),
|
||||
"Háromszáz méter után Forduljon jobbra a 19; NY 25; Woodhaven Boulevardra",
|
||||
()); // a for prefixing "ten nine"
|
||||
Notification const notificationHuB(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("Woodhaven Boulevard", "NY 25", "1"));
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHuB),
|
||||
"Háromszáz méter után Forduljon jobbra az 1; NY 25; Woodhaven Boulevardra", ()); // az for prefixing "one"
|
||||
|
||||
Notification const notificationHu1(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("puszta"));
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHu1), "Háromszáz méter után Forduljon jobbra a pusztára", ());
|
||||
Notification const notificationHu2(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("tanya"));
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHu2), "Háromszáz méter után Forduljon jobbra a tanyára", ());
|
||||
Notification const notificationHu3(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("utca"));
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHu3), "Háromszáz méter után Forduljon jobbra az utcára", ());
|
||||
Notification const notificationHu4(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("útja"));
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHu4), "Háromszáz méter után Forduljon jobbra az útjára", ());
|
||||
Notification const notificationHu5(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("allé"));
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHu5), "Háromszáz méter után Forduljon jobbra az allére",
|
||||
()); // Some speakers say allére but it's personal judgment
|
||||
Notification const notificationHu6(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("útgyűrű"));
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHu6), "Háromszáz méter után Forduljon jobbra az útgyűrűre", ());
|
||||
Notification const notificationHu7(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("csirke"));
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHu7), "Háromszáz méter után Forduljon jobbra a csirkére", ());
|
||||
Notification const notificationHu8(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("1"));
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHu8), "Háromszáz méter után Forduljon jobbra az 1re", ());
|
||||
Notification const notificationHu8a(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("10"));
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHu8a), "Háromszáz méter után Forduljon jobbra a 10re", ());
|
||||
Notification const notificationHu9(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("20"));
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHu9), "Háromszáz méter után Forduljon jobbra a 20ra", ());
|
||||
Notification const notificationHu10(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("7"));
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHu10), "Háromszáz méter után Forduljon jobbra a 7re",
|
||||
()); // 7 is re
|
||||
Notification const notificationHu11(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("71"));
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHu11), "Háromszáz méter után Forduljon jobbra a 71re",
|
||||
()); // 70 is re and 1 is re
|
||||
Notification const notificationHu12(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("50"));
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHu12), "Háromszáz méter után Forduljon jobbra az 50re",
|
||||
()); // 5* is az and 50 is re
|
||||
Notification const notificationHu13(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("Ybl utcá"));
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHu13), "Háromszáz méter után Forduljon jobbra az Ybl utcára",
|
||||
()); // leading Y is a vowel
|
||||
Notification const notificationHu14(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("puszta "));
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHu14), "Háromszáz méter után Forduljon jobbra a pusztára",
|
||||
()); // trailing space shouldn't matter
|
||||
Notification const notificationHu15(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo(" puszta"));
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHu15), "Háromszáz méter után Forduljon jobbra a pusztára",
|
||||
()); // leading space shouldn't matter
|
||||
Notification const notificationHu16(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo(" "));
|
||||
// only spaces shouldn't matter, but it counts as an empty street name, thus not part of new TTS / Street Name /
|
||||
// Hungarian logic, thus having a terminal period.
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHu16), "Háromszáz méter után Forduljon jobbra.", ());
|
||||
Notification const notificationHu17(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("puszta; "));
|
||||
// semicolon doesn't affect the suffix, but it does introduce punctuation that stops the a -> á replacement. Hopefully
|
||||
// this is acceptable for now (odd case.)
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHu17), "Háromszáz méter után Forduljon jobbra a puszta;ra", ());
|
||||
Notification const notificationHu18(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("10Á"));
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHu18), "Háromszáz méter után Forduljon jobbra a 10Ára",
|
||||
()); // 10* is a and Á is ra
|
||||
Notification const notificationHu19(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("5É"));
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHu19), "Háromszáz méter után Forduljon jobbra az 5Ére",
|
||||
()); // 5* is az and É is re
|
||||
Notification const notificationHu20(300, 0, false, CarDirection::TurnRight, measurement_utils::Units::Metric,
|
||||
routing::RouteSegment::RoadNameInfo("É100"));
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notificationHu20), "Háromszáz méter után Forduljon jobbra az É100ra",
|
||||
()); // É* is az and 100 is ra
|
||||
|
||||
getTtsText.ForTestingSetLocaleWithJson(nlShortJson, "nl");
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification1),
|
||||
"Over vijfhonderd meter naar rechts afslaan naar Main Street", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification2),
|
||||
"Over driehonderd meter naar links afslaan naar Main Street", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification3), "Over driehonderd meter Sla linksaf.", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification4), "Daarna Sla linksaf.", ());
|
||||
TEST_EQUAL(getTtsText.GetTurnNotification(notification6), "Verlaat naar 195; NY 25; Woodhaven Boulevard", ());
|
||||
}
|
||||
|
||||
UNIT_TEST(GetAllSoundedDistMetersTest)
|
||||
{
|
||||
VecPairDist const & allSoundedDistMeters = GetAllSoundedDistMeters();
|
||||
|
||||
TEST(is_sorted(allSoundedDistMeters.cbegin(), allSoundedDistMeters.cend(),
|
||||
[](PairDist const & p1, PairDist const & p2) { return p1.first < p2.first; }),
|
||||
());
|
||||
|
||||
TEST_EQUAL(allSoundedDistMeters.size(), 17, ());
|
||||
PairDist const expected1 = {50, "in_50_meters"};
|
||||
TEST(PairDistEquals(allSoundedDistMeters[0], expected1), (allSoundedDistMeters[0], expected1));
|
||||
PairDist const expected2 = {700, "in_700_meters"};
|
||||
TEST(PairDistEquals(allSoundedDistMeters[8], expected2), (allSoundedDistMeters[8], expected2));
|
||||
PairDist const expected3 = {3000, "in_3_kilometers"};
|
||||
TEST(PairDistEquals(allSoundedDistMeters[16], expected3), (allSoundedDistMeters[16], expected3));
|
||||
}
|
||||
|
||||
UNIT_TEST(GetAllSoundedDistFeet)
|
||||
{
|
||||
VecPairDist const & allSoundedDistFeet = GetAllSoundedDistFeet();
|
||||
|
||||
TEST(is_sorted(allSoundedDistFeet.cbegin(), allSoundedDistFeet.cend(),
|
||||
[](PairDist const & p1, PairDist const & p2) { return p1.first < p2.first; }),
|
||||
());
|
||||
|
||||
TEST_EQUAL(allSoundedDistFeet.size(), 22, ());
|
||||
PairDist const expected1 = {50, "in_50_feet"};
|
||||
TEST(PairDistEquals(allSoundedDistFeet[0], expected1), (allSoundedDistFeet[0], expected1));
|
||||
PairDist const expected2 = {700, "in_700_feet"};
|
||||
TEST(PairDistEquals(allSoundedDistFeet[7], expected2), (allSoundedDistFeet[7], expected2));
|
||||
PairDist const expected3 = {10560, "in_2_miles"};
|
||||
TEST(PairDistEquals(allSoundedDistFeet[21], expected3), (allSoundedDistFeet[21], expected3));
|
||||
}
|
||||
|
||||
UNIT_TEST(GetSoundedDistMeters)
|
||||
{
|
||||
vector<uint32_t> const & soundedDistMeters = GetSoundedDistMeters();
|
||||
VecPairDist const & allSoundedDistMeters = GetAllSoundedDistMeters();
|
||||
|
||||
TEST(is_sorted(soundedDistMeters.cbegin(), soundedDistMeters.cend()), ());
|
||||
// Checking that allSounded contains any element of inst.
|
||||
TEST(find_first_of(soundedDistMeters.cbegin(), soundedDistMeters.cend(), allSoundedDistMeters.cbegin(),
|
||||
allSoundedDistMeters.cend(),
|
||||
[](uint32_t p1, PairDist const & p2) { return p1 == p2.first; }) != soundedDistMeters.cend(),
|
||||
());
|
||||
|
||||
TEST_EQUAL(soundedDistMeters.size(), 11, ());
|
||||
TEST_EQUAL(soundedDistMeters[0], 200, ());
|
||||
TEST_EQUAL(soundedDistMeters[7], 900, ());
|
||||
TEST_EQUAL(soundedDistMeters[10], 2000, ());
|
||||
}
|
||||
|
||||
UNIT_TEST(GetSoundedDistFeet)
|
||||
{
|
||||
vector<uint32_t> soundedDistFeet = GetSoundedDistFeet();
|
||||
VecPairDist const & allSoundedDistFeet = GetAllSoundedDistFeet();
|
||||
|
||||
TEST(is_sorted(soundedDistFeet.cbegin(), soundedDistFeet.cend()), ());
|
||||
// Checking that allSounded contains any element of inst.
|
||||
TEST(find_first_of(soundedDistFeet.cbegin(), soundedDistFeet.cend(), allSoundedDistFeet.cbegin(),
|
||||
allSoundedDistFeet.cend(),
|
||||
[](uint32_t p1, PairDist const & p2) { return p1 == p2.first; }) != soundedDistFeet.cend(),
|
||||
());
|
||||
|
||||
TEST_EQUAL(soundedDistFeet.size(), 11, ());
|
||||
TEST_EQUAL(soundedDistFeet[0], 500, ());
|
||||
TEST_EQUAL(soundedDistFeet[7], 2000, ());
|
||||
TEST_EQUAL(soundedDistFeet[10], 5000, ());
|
||||
}
|
||||
} // namespace turns_tts_text_tests
|
||||
118
libs/routing/routing_tests/uturn_restriction_tests.cpp
Normal file
118
libs/routing/routing_tests/uturn_restriction_tests.cpp
Normal file
|
|
@ -0,0 +1,118 @@
|
|||
#include "testing/testing.hpp"
|
||||
|
||||
#include "routing/restriction_loader.hpp"
|
||||
|
||||
#include "routing/routing_tests/index_graph_tools.hpp"
|
||||
#include "routing/routing_tests/world_graph_builder.hpp"
|
||||
|
||||
namespace uturn_restriction_tests
|
||||
{
|
||||
using namespace routing;
|
||||
using namespace routing_test;
|
||||
|
||||
using Algorithm = AStarAlgorithm<Segment, SegmentEdge, RouteWeight>;
|
||||
|
||||
UNIT_CLASS_TEST(NoUTurnRestrictionTest, CheckNoUTurn_1)
|
||||
{
|
||||
Init(BuildCrossGraph());
|
||||
|
||||
Segment const start(kTestNumMwmId, 3 /* fId */, 0 /* segId */, true /* forward */);
|
||||
Segment const finish(kTestNumMwmId, 7 /* fId */, 0 /* segId */, true /* forward */);
|
||||
|
||||
std::vector<m2::PointD> const expectedGeom = {{3.0, 0.0}, {2.0, 0.0}, {1.0, 0.0}, {1.0, 1.0}, {1.0, 2.0}};
|
||||
|
||||
TestRouteGeom(start, finish, Algorithm::Result::OK, expectedGeom);
|
||||
|
||||
std::vector<RestrictionUTurn> noUTurnRestrictions = {{3 /* featureId */, false /* viaIsFirstPoint */}};
|
||||
|
||||
SetNoUTurnRestrictions(std::move(noUTurnRestrictions));
|
||||
TestRouteGeom(start, finish, Algorithm::Result::NoPath, {} /* expectedGeom */);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(NoUTurnRestrictionTest, CheckNoUTurn_2)
|
||||
{
|
||||
Init(BuildCrossGraph());
|
||||
|
||||
Segment const start(kTestNumMwmId, 2 /* fId */, 0 /* segId */, true /* forward */);
|
||||
Segment const finish(kTestNumMwmId, 7 /* fId */, 0 /* segId */, true /* forward */);
|
||||
|
||||
std::vector<m2::PointD> const expectedGeom = {{2.0, 0.0}, {1.0, 0.0}, {1.0, 1.0}, {1.0, 2.0}};
|
||||
|
||||
TestRouteGeom(start, finish, Algorithm::Result::OK, expectedGeom);
|
||||
|
||||
std::vector<RestrictionUTurn> noUTurnRestrictions = {{2 /* featureId */, false /* viaIsFirstPoint */}};
|
||||
|
||||
std::vector<m2::PointD> const expectedGeomAfterRestriction = {{2.0, 0.0}, {3.0, 0.0}, {2.0, 0.0},
|
||||
{1.0, 0.0}, {1.0, 1.0}, {1.0, 2.0}};
|
||||
|
||||
SetNoUTurnRestrictions(std::move(noUTurnRestrictions));
|
||||
TestRouteGeom(start, finish, Algorithm::Result::OK, expectedGeomAfterRestriction);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(NoUTurnRestrictionTest, CheckNoUTurn_3)
|
||||
{
|
||||
Init(BuildCrossGraph());
|
||||
|
||||
Segment const start(kTestNumMwmId, 2 /* fId */, 0 /* segId */, false /* forward */);
|
||||
Segment const finish(kTestNumMwmId, 3 /* fId */, 0 /* segId */, true /* forward */);
|
||||
|
||||
std::vector<m2::PointD> const expectedGeom = {{1.0, 0.0}, {2.0, 0.0}, {3.0, 0.0}};
|
||||
|
||||
TestRouteGeom(start, finish, Algorithm::Result::OK, expectedGeom);
|
||||
|
||||
std::vector<RestrictionUTurn> noUTurnRestrictions = {{2 /* featureId */, true /* viaIsFirstPoint */}};
|
||||
|
||||
std::vector<m2::PointD> const expectedGeomAfterRestriction = {
|
||||
{1.0, 0.0}, {1.0, -1.0}, {1.0, 0.0}, {2.0, 0.0}, {3.0, 0.0}};
|
||||
|
||||
SetNoUTurnRestrictions(std::move(noUTurnRestrictions));
|
||||
TestRouteGeom(start, finish, Algorithm::Result::OK, expectedGeomAfterRestriction);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(NoUTurnRestrictionTest, CheckOnlyUTurn_1)
|
||||
{
|
||||
Init(BuildCrossGraph());
|
||||
|
||||
Segment const start(kTestNumMwmId, 2 /* fId */, 0 /* segId */, true /* forward */);
|
||||
Segment const finish(kTestNumMwmId, 3 /* fId */, 0 /* segId */, true /* forward */);
|
||||
|
||||
std::vector<m2::PointD> const expectedGeom = {{2.0, 0.0}, {3.0, 0.0}};
|
||||
|
||||
TestRouteGeom(start, finish, Algorithm::Result::OK, expectedGeom);
|
||||
|
||||
std::vector<RestrictionUTurn> onlyUTurnRestrictions = {{2 /* featureId */, false /* viaIsFirstPoint */}};
|
||||
|
||||
RestrictionVec restrictionsNo;
|
||||
|
||||
auto & indexGraph = m_graph->GetWorldGraph().GetIndexGraph(kTestNumMwmId);
|
||||
ConvertRestrictionsOnlyUTurnToNo(indexGraph, onlyUTurnRestrictions, restrictionsNo);
|
||||
SetRestrictions(std::move(restrictionsNo));
|
||||
|
||||
TestRouteGeom(start, finish, Algorithm::Result::NoPath, {} /* expectedGeom */);
|
||||
}
|
||||
|
||||
UNIT_CLASS_TEST(NoUTurnRestrictionTest, CheckOnlyUTurn_2)
|
||||
{
|
||||
Init(BuildTestGraph());
|
||||
|
||||
Segment const start(kTestNumMwmId, 0 /* fId */, 0 /* segId */, false /* forward */);
|
||||
Segment const finish(kTestNumMwmId, 5 /* fId */, 0 /* segId */, true /* forward */);
|
||||
|
||||
std::vector<m2::PointD> const expectedGeom = {{0.0, 1.0}, {1.0, 1.0}, {2.0, 2.0}, {3.0, 2.0}};
|
||||
|
||||
TestRouteGeom(start, finish, Algorithm::Result::OK, expectedGeom);
|
||||
|
||||
std::vector<RestrictionUTurn> onlyUTurnRestrictions = {{1 /* featureId */, false /* viaIsFirstPoint */}};
|
||||
|
||||
RestrictionVec restrictionsNo;
|
||||
|
||||
auto & indexGraph = m_graph->GetWorldGraph().GetIndexGraph(kTestNumMwmId);
|
||||
ConvertRestrictionsOnlyUTurnToNo(indexGraph, onlyUTurnRestrictions, restrictionsNo);
|
||||
SetRestrictions(std::move(restrictionsNo));
|
||||
|
||||
std::vector<m2::PointD> const expectedGeomAfterRestriction = {{0.0, 1.0}, {-1.0, 1.0}, {-1.0, 2.0}, {0.0, 2.0},
|
||||
{1.0, 2.0}, {2.0, 2.0}, {3.0, 2.0}};
|
||||
|
||||
TestRouteGeom(start, finish, Algorithm::Result::OK, expectedGeomAfterRestriction);
|
||||
}
|
||||
} // namespace uturn_restriction_tests
|
||||
108
libs/routing/routing_tests/world_graph_builder.cpp
Normal file
108
libs/routing/routing_tests/world_graph_builder.cpp
Normal file
|
|
@ -0,0 +1,108 @@
|
|||
#include "routing/routing_tests/world_graph_builder.hpp"
|
||||
|
||||
#include "generator/generator_tests_support/routing_helpers.hpp"
|
||||
|
||||
#include "routing/routing_tests/index_graph_tools.hpp"
|
||||
|
||||
#include "routing/edge_estimator.hpp"
|
||||
#include "routing/geometry.hpp"
|
||||
#include "routing/joint.hpp"
|
||||
#include "routing/single_vehicle_world_graph.hpp"
|
||||
|
||||
#include "traffic/traffic_cache.hpp"
|
||||
|
||||
#include <utility>
|
||||
#include <vector>
|
||||
|
||||
namespace routing_test
|
||||
{
|
||||
using namespace routing;
|
||||
|
||||
// Finish
|
||||
// *
|
||||
// ^
|
||||
// |
|
||||
// F7
|
||||
// |
|
||||
// *
|
||||
// ^
|
||||
// |
|
||||
// F6
|
||||
// |
|
||||
// Start * -- F0 --> * -- F1 --> * <-- F2 --> * <-- F3 --> *
|
||||
// | ^
|
||||
// | |
|
||||
// F4 F5
|
||||
// | |
|
||||
// ⌄ |
|
||||
// *
|
||||
std::unique_ptr<SingleVehicleWorldGraph> BuildCrossGraph()
|
||||
{
|
||||
std::unique_ptr<TestGeometryLoader> loader = std::make_unique<TestGeometryLoader>();
|
||||
loader->AddRoad(0 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{-1.0, 0.0}, {0.0, 0.0}}));
|
||||
loader->AddRoad(1 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 0.0}, {1.0, 0.0}}));
|
||||
loader->AddRoad(2 /* featureId */, false /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 0.0}, {1.9999, 0.0}}));
|
||||
loader->AddRoad(3 /* featureId */, false /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.9999, 0.0}, {3.0, 0.0}}));
|
||||
loader->AddRoad(4 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 0.0}, {1.0, -1.0}}));
|
||||
loader->AddRoad(5 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, -1.0}, {1.0, 0.0}}));
|
||||
loader->AddRoad(6 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 0.0}, {1.0, 1.0}}));
|
||||
loader->AddRoad(7 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 1.0}, {1.0, 2.0}}));
|
||||
|
||||
std::vector<Joint> const joints = {MakeJoint({{0, 1}, {1, 0}}), MakeJoint({{1, 1}, {2, 0}, {4, 0}, {5, 1}, {6, 0}}),
|
||||
MakeJoint({{2, 1}, {3, 0}}), MakeJoint({{4, 1}, {5, 0}}),
|
||||
MakeJoint({{6, 1}, {7, 0}})};
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
std::shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
|
||||
return BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
}
|
||||
|
||||
//
|
||||
// 2 * -- F2 --> * -- F2 --> * -- F2 --> * -- F5 --> *
|
||||
// ↑ ↗
|
||||
// F2 F3
|
||||
// ↑ ↗
|
||||
// 1 * <-- F0 --> * <-- F1 --> *
|
||||
// ↘
|
||||
// F4
|
||||
// ↘
|
||||
// 0 *
|
||||
//
|
||||
// -1 0 1 2 3
|
||||
//
|
||||
std::unique_ptr<SingleVehicleWorldGraph> BuildTestGraph()
|
||||
{
|
||||
std::unique_ptr<TestGeometryLoader> loader = std::make_unique<TestGeometryLoader>();
|
||||
loader->AddRoad(0 /* featureId */, false /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 1.0}, {-1.0, 1.0}}));
|
||||
loader->AddRoad(1 /* featureId */, false /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{0.0, 1.0}, {1.0, 1.0}}));
|
||||
loader->AddRoad(2 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{-1.0, 1.0}, {-1.0, 2.0}, {0.0, 2.0}, {1.0, 2.0}, {2.0, 2.0}}));
|
||||
loader->AddRoad(3 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 1.0}, {2.0, 2.0}}));
|
||||
loader->AddRoad(4 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{1.0, 0.0}, {2.0, 0.0}}));
|
||||
loader->AddRoad(5 /* featureId */, true /* oneWay */, 1.0 /* speed */,
|
||||
RoadGeometry::Points({{2.0, 2.0}, {3.0, 2.0}}));
|
||||
|
||||
std::vector<Joint> const joints = {MakeJoint({{1, 0}, {0, 0}}), // (0, 1)
|
||||
MakeJoint({{0, 1}, {2, 0}}), // (-1, 1)
|
||||
MakeJoint({{3, 1}, {2, 4}, {5, 0}}), // (2, 2)
|
||||
MakeJoint({{1, 1}, {3, 0}, {4, 0}})}; // (1, 1)
|
||||
|
||||
traffic::TrafficCache const trafficCache;
|
||||
std::shared_ptr<EdgeEstimator> estimator = CreateEstimatorForCar(trafficCache);
|
||||
|
||||
return BuildWorldGraph(std::move(loader), estimator, joints);
|
||||
}
|
||||
} // namespace routing_test
|
||||
11
libs/routing/routing_tests/world_graph_builder.hpp
Normal file
11
libs/routing/routing_tests/world_graph_builder.hpp
Normal file
|
|
@ -0,0 +1,11 @@
|
|||
#pragma once
|
||||
|
||||
#include "routing/single_vehicle_world_graph.hpp"
|
||||
|
||||
#include <memory>
|
||||
|
||||
namespace routing_test
|
||||
{
|
||||
std::unique_ptr<routing::SingleVehicleWorldGraph> BuildCrossGraph();
|
||||
std::unique_ptr<routing::SingleVehicleWorldGraph> BuildTestGraph();
|
||||
} // namespace routing_test
|
||||
Loading…
Add table
Add a link
Reference in a new issue