[routing] New API for lanes

Signed-off-by: Andrei Shkrob <github@shkrob.dev>
This commit is contained in:
Andrei Shkrob
2025-07-29 22:54:24 +02:00
committed by x7z4w
parent 93293e7b31
commit c014e224b2
36 changed files with 1047 additions and 634 deletions

View File

@@ -1,6 +1,8 @@
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

View 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

View 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

View File

@@ -18,7 +18,6 @@
#include "base/macros.hpp"
#include <cmath>
#include <string>
#include <vector>
@@ -65,118 +64,6 @@ private:
TUnpackedPathSegments m_segments;
};
UNIT_TEST(TestSplitLanes)
{
vector<string> result;
SplitLanes("through|through|through|through;right", '|', result);
vector<string> const expected1 = {"through", "through", "through", "through;right"};
TEST_EQUAL(result, expected1, ());
SplitLanes("adsjkddfasui8747&sxdsdlad8\"\'", '|', result);
TEST_EQUAL(result, vector<string>({"adsjkddfasui8747&sxdsdlad8\"\'"}), ());
SplitLanes("|||||||", '|', result);
vector<string> expected2 = {"", "", "", "", "", "", ""};
TEST_EQUAL(result, expected2, ());
}
UNIT_TEST(TestParseSingleLane)
{
TSingleLane result;
TEST(ParseSingleLane("through;right", ';', result), ());
TSingleLane const expected1 = {LaneWay::Through, LaneWay::Right};
TEST_EQUAL(result, expected1, ());
TEST(!ParseSingleLane("through;Right", ';', result), ());
TEST(!ParseSingleLane("through ;right", ';', result), ());
TEST_EQUAL(result.size(), 0, ());
TEST(!ParseSingleLane("SD32kk*887;;", ';', result), ());
TEST_EQUAL(result.size(), 0, ());
TEST(!ParseSingleLane("Что-то на кириллице", ';', result), ());
TEST_EQUAL(result.size(), 0, ());
TEST(!ParseSingleLane("משהו בעברית", ';', result), ());
TEST_EQUAL(result.size(), 0, ());
TEST(ParseSingleLane("left;through", ';', result), ());
TSingleLane expected2 = {LaneWay::Left, LaneWay::Through};
TEST_EQUAL(result, expected2, ());
TEST(ParseSingleLane("left", ';', result), ());
TEST_EQUAL(result.size(), 1, ());
TEST_EQUAL(result[0], LaneWay::Left, ());
TEST(ParseSingleLane("left;", ';', result), ());
TSingleLane expected3 = {LaneWay::Left, LaneWay::None};
TEST_EQUAL(result, expected3, ());
TEST(ParseSingleLane(";", ';', result), ());
TSingleLane expected4 = {LaneWay::None, LaneWay::None};
TEST_EQUAL(result, expected4, ());
TEST(ParseSingleLane("", ';', result), ());
TSingleLane expected5 = {LaneWay::None};
TEST_EQUAL(result, expected5, ());
}
UNIT_TEST(TestParseLanes)
{
vector<SingleLaneInfo> result;
TEST(ParseLanes("through|through|through|through;right", result), ());
vector<SingleLaneInfo> const expected1 = {
{LaneWay::Through}, {LaneWay::Through}, {LaneWay::Through}, {LaneWay::Through, LaneWay::Right}};
TEST_EQUAL(result, expected1, ());
TEST(ParseLanes("left|left;through|through|through", result), ());
vector<SingleLaneInfo> const expected2 = {
{LaneWay::Left}, {LaneWay::Left, LaneWay::Through}, {LaneWay::Through}, {LaneWay::Through}};
TEST_EQUAL(result, expected2, ());
TEST(ParseLanes("left|through|through", result), ());
vector<SingleLaneInfo> const expected3 = {{LaneWay::Left}, {LaneWay::Through}, {LaneWay::Through}};
TEST_EQUAL(result, expected3, ());
TEST(ParseLanes("left|le ft| through|through | right", result), ());
vector<SingleLaneInfo> const expected4 = {
{LaneWay::Left}, {LaneWay::Left}, {LaneWay::Through}, {LaneWay::Through}, {LaneWay::Right}};
TEST_EQUAL(result, expected4, ());
TEST(ParseLanes("left|Left|through|througH|right", result), ());
vector<SingleLaneInfo> const expected5 = {
{LaneWay::Left}, {LaneWay::Left}, {LaneWay::Through}, {LaneWay::Through}, {LaneWay::Right}};
TEST_EQUAL(result, expected5, ());
TEST(ParseLanes("left|Left|through|througH|through;right;sharp_rIght", result), ());
vector<SingleLaneInfo> const expected6 = {{LaneWay::Left},
{LaneWay::Left},
{LaneWay::Through},
{LaneWay::Through},
{LaneWay::Through, LaneWay::Right, LaneWay::SharpRight}};
TEST_EQUAL(result, expected6, ());
TEST(!ParseLanes("left|Leftt|through|througH|right", result), ());
TEST_EQUAL(result.size(), 0, ());
TEST(!ParseLanes("Что-то на кириллице", result), ());
TEST_EQUAL(result.size(), 0, ());
TEST(!ParseLanes("משהו בעברית", result), ());
TEST_EQUAL(result.size(), 0, ());
TEST(ParseLanes("left |Left|through|througH|right", result), ());
vector<SingleLaneInfo> const expected7 = {
{LaneWay::Left}, {LaneWay::Left}, {LaneWay::Through}, {LaneWay::Through}, {LaneWay::Right}};
TEST_EQUAL(result, expected7, ());
TEST(ParseLanes("|||||slight_right", result), ());
vector<SingleLaneInfo> const expected8 = {{LaneWay::None}, {LaneWay::None}, {LaneWay::None},
{LaneWay::None}, {LaneWay::None}, {LaneWay::SlightRight}};
TEST_EQUAL(result, expected8, ());
}
UNIT_TEST(TestFixupTurns)
{
double const kHalfSquareSideMeters = 10.;
@@ -238,76 +125,6 @@ UNIT_TEST(TestFixupTurns)
}
}
UNIT_TEST(TestIsLaneWayConformedTurnDirection)
{
TEST(IsLaneWayConformedTurnDirection(LaneWay::Left, CarDirection::TurnLeft), ());
TEST(IsLaneWayConformedTurnDirection(LaneWay::Right, CarDirection::TurnRight), ());
TEST(IsLaneWayConformedTurnDirection(LaneWay::SlightLeft, CarDirection::TurnSlightLeft), ());
TEST(IsLaneWayConformedTurnDirection(LaneWay::SharpRight, CarDirection::TurnSharpRight), ());
TEST(IsLaneWayConformedTurnDirection(LaneWay::Reverse, CarDirection::UTurnLeft), ());
TEST(IsLaneWayConformedTurnDirection(LaneWay::Reverse, CarDirection::UTurnRight), ());
TEST(IsLaneWayConformedTurnDirection(LaneWay::Through, CarDirection::GoStraight), ());
TEST(!IsLaneWayConformedTurnDirection(LaneWay::Left, CarDirection::TurnSlightLeft), ());
TEST(!IsLaneWayConformedTurnDirection(LaneWay::Right, CarDirection::TurnSharpRight), ());
TEST(!IsLaneWayConformedTurnDirection(LaneWay::SlightLeft, CarDirection::GoStraight), ());
TEST(!IsLaneWayConformedTurnDirection(LaneWay::SharpRight, CarDirection::None), ());
TEST(!IsLaneWayConformedTurnDirection(LaneWay::Reverse, CarDirection::TurnLeft), ());
TEST(!IsLaneWayConformedTurnDirection(LaneWay::None, CarDirection::ReachedYourDestination), ());
}
UNIT_TEST(TestIsLaneWayConformedTurnDirectionApproximately)
{
TEST(IsLaneWayConformedTurnDirectionApproximately(LaneWay::Left, CarDirection::TurnSharpLeft), ());
TEST(IsLaneWayConformedTurnDirectionApproximately(LaneWay::Left, CarDirection::TurnSlightLeft), ());
TEST(IsLaneWayConformedTurnDirectionApproximately(LaneWay::Right, CarDirection::TurnSharpRight), ());
TEST(IsLaneWayConformedTurnDirectionApproximately(LaneWay::Right, CarDirection::TurnRight), ());
TEST(IsLaneWayConformedTurnDirectionApproximately(LaneWay::Reverse, CarDirection::UTurnLeft), ());
TEST(IsLaneWayConformedTurnDirectionApproximately(LaneWay::Reverse, CarDirection::UTurnRight), ());
TEST(IsLaneWayConformedTurnDirectionApproximately(LaneWay::SlightLeft, CarDirection::GoStraight), ());
TEST(IsLaneWayConformedTurnDirectionApproximately(LaneWay::SlightRight, CarDirection::GoStraight), ());
TEST(!IsLaneWayConformedTurnDirectionApproximately(LaneWay::SharpLeft, CarDirection::UTurnLeft), ());
TEST(!IsLaneWayConformedTurnDirectionApproximately(LaneWay::SharpLeft, CarDirection::UTurnRight), ());
TEST(!IsLaneWayConformedTurnDirectionApproximately(LaneWay::SharpRight, CarDirection::UTurnLeft), ());
TEST(!IsLaneWayConformedTurnDirectionApproximately(LaneWay::SharpRight, CarDirection::UTurnRight), ());
TEST(!IsLaneWayConformedTurnDirection(LaneWay::Through, CarDirection::ReachedYourDestination), ());
TEST(!IsLaneWayConformedTurnDirectionApproximately(LaneWay::Through, CarDirection::TurnRight), ());
TEST(!IsLaneWayConformedTurnDirectionApproximately(LaneWay::SlightRight, CarDirection::TurnSharpLeft), ());
}
UNIT_TEST(TestAddingActiveLaneInformation)
{
vector<turns::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});
vector<RouteSegment> routeSegments;
RouteSegmentsFrom({}, {}, turns, {}, routeSegments);
SelectRecommendedLanes(routeSegments);
TEST(routeSegments[0].GetTurn().m_lanes[0].m_isRecommended, ());
TEST(!routeSegments[0].GetTurn().m_lanes[1].m_isRecommended, ());
TEST(routeSegments[1].GetTurn().m_lanes[0].m_isRecommended, ());
TEST(!routeSegments[1].GetTurn().m_lanes[1].m_isRecommended, ());
TEST(!routeSegments[1].GetTurn().m_lanes[2].m_isRecommended, ());
TEST(!routeSegments[2].GetTurn().m_lanes[0].m_isRecommended, ());
TEST(routeSegments[2].GetTurn().m_lanes[1].m_isRecommended, ());
}
UNIT_TEST(TestGetRoundaboutDirection)
{
// The signature of GetRoundaboutDirection function is