test_route.cpp
Go to the documentation of this file.
1 #include <gtest/gtest.h>
2 
5 #include "test_routing_map.h"
6 
7 using namespace lanelet;
8 using namespace lanelet::routing;
9 using namespace lanelet::routing::tests;
10 
11 template <Id FromId, Id ToId, Id... ViaIds>
12 class TestRoute : public GermanVehicleGraph {
13  public:
14  explicit TestRoute(uint16_t routingCostId = 0, bool withLaneChanges = true) {
15  Ids viaIds{ViaIds...};
16  start = lanelets.at(From);
17  end = lanelets.at(To);
18  via = utils::transform(viaIds, [&](auto id) -> ConstLanelet { return lanelets.at(id); });
19  auto optRoute = via.empty() ? graph->getRoute(start, end, routingCostId, withLaneChanges)
20  : graph->getRouteVia(start, via, end, routingCostId, withLaneChanges);
21  EXPECT_TRUE(!!optRoute);
22  route = std::move(*optRoute);
23  }
28  // these would better be defined as static constexpr, but c++14 doesnt support it well
29  const Id From{FromId}; // NOLINT
30  const Id To{ToId}; // NOLINT
31 };
32 
33 class Route1 : public TestRoute<2001, 2014> {};
34 class Route1NoLc : public TestRoute<2001, 2014> {
35  public:
36  Route1NoLc() : TestRoute(0, false) {}
37 };
38 class Route2 : public TestRoute<2001, 2004> {};
39 class Route3 : public TestRoute<2003, 2002> {};
40 class Route4 : public TestRoute<2003, 2013> {};
41 class Route5 : public TestRoute<2066, 2064> {};
42 class RouteMaxHoseLeftRight : public TestRoute<2017, 2024> {};
43 class RouteMaxHoseRightLeft : public TestRoute<2023, 2016> {};
44 class RouteMaxHoseLeftRightDashedSolid : public TestRoute<2017, 2025> {};
45 class RouteMaxHoseLeftRightDashedSolidFurther : public TestRoute<2017, 2027> {};
46 class RouteSolidDashed : public TestRoute<2024, 2026> {};
47 class RouteSolidDashedWithAdjacent : public TestRoute<2024, 2029> {};
48 class RouteSplittedDiverging : public TestRoute<2029, 2038> {};
49 class RouteSplittedDivergingAndMerging : public TestRoute<2041, 2049> {};
50 class RouteViaSimple : public TestRoute<2003, 2015, 2009> {};
51 class RouteMissingLanelet : public TestRoute<2003, 2015> {};
52 class RouteInCircle : public TestRoute<2029, 2068> {};
53 class RouteCircular : public TestRoute<2037, 2037, 2065> {};
54 class RouteCircularNoLc : public TestRoute<2037, 2037, 2065> {
55  public:
56  RouteCircularNoLc() : TestRoute(0, false) {}
57 };
58 
59 template <typename T>
60 class AllRoutesTest : public T {};
61 
62 using AllRoutes =
67 
69 
70 TYPED_TEST(AllRoutesTest, CheckValidity) { EXPECT_NO_THROW(this->route.checkValidity()); } // NOLINT
71 
72 TYPED_TEST(AllRoutesTest, ShortestMapInDebugMap) {
73  const auto map{this->route.getDebugLaneletMap()};
74  for (const auto& el : this->route.shortestPath()) {
75  ASSERT_NE(map->pointLayer.find(el.id()), map->pointLayer.end());
76  const Point3d point{*map->pointLayer.find(el.id())};
77  EXPECT_TRUE(*point.attribute("shortest_path").asBool());
78  }
79 }
80 
81 TYPED_TEST(AllRoutesTest, DebugMapCompleteness) {
82  const LaneletMapPtr debugMap{this->route.getDebugLaneletMap()};
83  const LaneletSubmapConstPtr laneletMap{this->route.laneletSubmap()};
84 
85  for (const auto& it : laneletMap->laneletLayer) {
86  ASSERT_NE(debugMap->pointLayer.find(it.id()), debugMap->pointLayer.end());
87  Point3d point{*debugMap->pointLayer.find(it.id())};
88  EXPECT_NO_THROW(point.attribute("id")); // NOLINT
89  EXPECT_NO_THROW(point.attribute("lane_id")); // NOLINT
90  }
91 
92  for (const auto& it : debugMap->lineStringLayer) {
93  EXPECT_NO_THROW(it.attribute("relation_1")); // NOLINT
94  }
95 }
96 
97 TEST_F(Route1, CreateRoute1) { // NOLINT
98  EXPECT_EQ(route.size(), 15ul); // NOLINT
99  EXPECT_GT(route.length2d(), 10.);
100  EXPECT_EQ(route.shortestPath(), *graph->shortestPath(start, end, 0)); // NOLINT
101  EXPECT_EQ(route.remainingShortestPath(start), route.shortestPath()); // NOLINT
102  EXPECT_TRUE(route.remainingShortestPath(lanelets.at(2003)).empty()); // NOLINT
103  EXPECT_NE(route.getDebugLaneletMap(), nullptr);
104  EXPECT_EQ(route.getDebugLaneletMap()->pointLayer.size(), route.size()); // NOLINT
105  EXPECT_NE(route.laneletSubmap(), nullptr);
106  EXPECT_EQ(route.laneletSubmap()->laneletLayer.size(), route.size()); // NOLINT
107 }
108 
109 bool hasRelation(const LaneletRelations& relations, const ConstLanelet& llt, RelationType relationType) {
110  LaneletRelation rel{llt, relationType};
111  return utils::anyOf(relations, [&rel](auto& relation) { return rel == relation; });
112 }
113 
114 template <typename ContainerT>
115 bool hasLanelet(const ContainerT& llts, const ConstLanelet& llt) {
116  return utils::anyOf(llts, [&llt](auto& curr) { return curr == llt; });
117 }
118 
119 TEST_F(Route1, Relations) { // NOLINT
120  LaneletRelations previous{route.previousRelations(lanelets.at(2007))};
121  EXPECT_EQ(previous.size(), 2ul); // NOLINT
122  EXPECT_TRUE(hasRelation(previous, ConstLanelet(lanelets.at(2005)), RelationType::Successor));
123  EXPECT_TRUE(hasRelation(previous, ConstLanelet(lanelets.at(2006)), RelationType::Successor));
124 
125  LaneletRelations following{route.followingRelations(lanelets.at(2007))};
126  EXPECT_EQ(following.size(), 2ul); // NOLINT
127  EXPECT_TRUE(hasRelation(following, ConstLanelet(lanelets.at(2008)), RelationType::Successor));
128  EXPECT_TRUE(hasRelation(following, ConstLanelet(lanelets.at(2009)), RelationType::Successor));
129 }
130 
131 TEST_F(Route1, Conflicting) { // NOLINT
132  auto conflictingInMap{route.conflictingInMap(lanelets.at(2009))};
133  EXPECT_EQ(conflictingInMap.size(), 1ul); // NOLINT
134  EXPECT_TRUE(hasLanelet(conflictingInMap, lanelets.at(2008)));
135 
136  ConstLanelets conflictingInRoute{route.conflictingInRoute(lanelets.at(2009))};
137  EXPECT_EQ(conflictingInRoute.size(), 1ul); // NOLINT
138  EXPECT_TRUE(hasLanelet(conflictingInRoute, lanelets.at(2008)));
139 
140  EXPECT_TRUE(route.conflictingInRoute(lanelets.at(2007)).empty());
141  EXPECT_TRUE(route.conflictingInMap(lanelets.at(2007)).empty());
142 }
143 
144 TEST_F(Route1, forEachSuccessor) { // NOLINT
145  double cLast = 0.;
146  route.forEachSuccessor(lanelets.at(2001), [&](const LaneletVisitInformation& i) {
147  EXPECT_TRUE(route.contains(i.lanelet));
148  EXPECT_LE(cLast, i.cost);
149  cLast = i.cost;
150  return true;
151  });
152 }
153 
154 TEST_F(Route1, Lanes) { // NOLINT
155  auto remainingLane{route.remainingLane(lanelets.at(2002))};
156  EXPECT_EQ(remainingLane.size(), 2ul); // NOLINT
157  EXPECT_TRUE(hasLanelet(remainingLane, lanelets.at(2002)));
158 
159  auto fullLane{route.fullLane(lanelets.at(2001))};
160  EXPECT_EQ(fullLane.size(), 3ul); // NOLINT
161  EXPECT_TRUE(hasLanelet(fullLane, lanelets.at(2002)));
162  EXPECT_EQ(route.numLanes(), 7ul);
163 }
164 
165 TEST_F(Route1NoLc, CreateRoute) { // NOLINT
166  EXPECT_EQ(route.size(), 7ul); // NOLINT
167  EXPECT_EQ(route.shortestPath(), *graph->shortestPath(start, end, 0, false)); // NOLINT
168  EXPECT_NE(route.getDebugLaneletMap(), nullptr);
169  EXPECT_EQ(route.getDebugLaneletMap()->pointLayer.size(), route.size()); // NOLINT
170  EXPECT_NE(route.laneletSubmap(), nullptr);
171  EXPECT_EQ(route.laneletSubmap()->laneletLayer.size(), route.size()); // NOLINT
172 }
173 TEST_F(Route1NoLc, Lanes) { // NOLINT
174  auto remainingLane{route.remainingLane(lanelets.at(2002))};
175  EXPECT_EQ(remainingLane.size(), 6ul); // NOLINT
176  EXPECT_TRUE(hasLanelet(remainingLane, lanelets.at(2002)));
177 
178  auto fullLane{route.fullLane(lanelets.at(2002))};
179  EXPECT_EQ(fullLane.size(), 7ul); // NOLINT
180 
181  EXPECT_TRUE(route.remainingLane(lanelets.at(2010)).empty());
182  EXPECT_EQ(route.numLanes(), 1ul);
183 }
184 
185 TEST_F(Route1NoLc, forEachPredecessor) { // NOLINT
186  route.forEachPredecessor(lanelets.at(2001), [&](const LaneletVisitInformation& i) {
187  EXPECT_EQ(i.lanelet, lanelets.at(2001));
188  return true;
189  });
190 }
191 
192 TEST_F(Route2, CreateRoute2) { // NOLINT
193  EXPECT_EQ(route.size(), 3ul); // NOLINT
194  EXPECT_EQ(route.shortestPath(), *graph->shortestPath(start, end, 0)); // NOLINT
195  EXPECT_NE(route.getDebugLaneletMap(), nullptr);
196  EXPECT_EQ(route.getDebugLaneletMap()->pointLayer.size(), route.size()); // NOLINT
197  EXPECT_NE(route.laneletSubmap(), nullptr);
198  EXPECT_EQ(route.laneletSubmap()->laneletLayer.size(), route.size()); // NOLINT
199 }
200 
201 TEST_F(Route3, CreateRoute3) { // NOLINT
202  EXPECT_EQ(route.size(), 3ul); // NOLINT
203  EXPECT_EQ(route.shortestPath(), *graph->shortestPath(start, end, 0)); // NOLINT
204  EXPECT_NE(route.getDebugLaneletMap(), nullptr);
205  EXPECT_EQ(route.getDebugLaneletMap()->pointLayer.size(), route.size()); // NOLINT
206  EXPECT_NE(route.laneletSubmap(), nullptr);
207  EXPECT_EQ(route.laneletSubmap()->laneletLayer.size(), route.size()); // NOLINT
208 }
209 
210 TEST_F(Route4, CreateRoute4) { // NOLINT
211  EXPECT_EQ(route.size(), 15ul); // NOLINT
212  EXPECT_EQ(route.shortestPath(), *graph->shortestPath(start, end, 0)); // NOLINT
213  EXPECT_NE(route.getDebugLaneletMap(), nullptr);
214  EXPECT_EQ(route.getDebugLaneletMap()->pointLayer.size(), route.size()); // NOLINT
215  EXPECT_NE(route.laneletSubmap(), nullptr);
216  EXPECT_EQ(route.laneletSubmap()->laneletLayer.size(), route.size()); // NOLINT
217 }
218 
219 TEST_F(Route5, NoCircle) {
220  EXPECT_EQ(route.size(), 9);
221  EXPECT_FALSE(hasLanelet(route.laneletSubmap()->laneletLayer, lanelets.at(2065)));
222 }
223 
224 TEST_F(RouteMaxHoseLeftRight, CreateRouteMaxHose1) { // NOLINT
225  EXPECT_EQ(route.size(), 5ul); // NOLINT
226  EXPECT_EQ(route.shortestPath(), *graph->shortestPath(start, end, 0)); // NOLINT
227  EXPECT_NE(route.getDebugLaneletMap(), nullptr);
228  EXPECT_EQ(route.getDebugLaneletMap()->pointLayer.size(), route.size()); // NOLINT
229  EXPECT_NE(route.laneletSubmap(), nullptr);
230  EXPECT_EQ(route.laneletSubmap()->laneletLayer.size(), route.size()); // NOLINT
231 }
232 
233 TEST_F(RouteMaxHoseLeftRight, Lanes) { // NOLINT
234  auto remainingLane{route.remainingLane(lanelets.at(2020))};
235  EXPECT_EQ(remainingLane.size(), 3ul); // NOLINT
236  EXPECT_TRUE(std::find(std::begin(remainingLane), std::end(remainingLane), ConstLanelet(lanelets.at(2022))) !=
237  std::end(remainingLane));
238 
239  auto fullLane{route.fullLane(lanelets.at(2020))};
240  EXPECT_EQ(fullLane.size(), 5ul); // NOLINT
241  EXPECT_TRUE(std::find(std::begin(fullLane), std::end(fullLane), ConstLanelet(lanelets.at(2024))) !=
242  std::end(fullLane));
243  EXPECT_EQ(route.numLanes(), 1ul);
244 }
245 
246 TEST_F(RouteMaxHoseLeftRight, InvalidLane) { // NOLINT
247  auto remainingLane{route.remainingLane(lanelets.at(2020).invert())};
248  EXPECT_TRUE(remainingLane.empty());
249 }
250 
251 TEST_F(RouteMaxHoseRightLeft, CreateRouteMaxHose2) { // NOLINT
252  EXPECT_EQ(route.size(), 5ul); // NOLINT
253  EXPECT_EQ(route.shortestPath(), *graph->shortestPath(start, end, 0)); // NOLINT
254  EXPECT_NE(route.getDebugLaneletMap(), nullptr);
255  EXPECT_EQ(route.getDebugLaneletMap()->pointLayer.size(), route.size()); // NOLINT
256  EXPECT_NE(route.laneletSubmap(), nullptr);
257  EXPECT_EQ(route.laneletSubmap()->laneletLayer.size(), route.size()); // NOLINT
258 }
259 
260 TEST_F(RouteMaxHoseRightLeft, Lanes) { // NOLINT
261  auto remainingLane{route.remainingLane(lanelets.at(2020).invert())};
262  EXPECT_EQ(remainingLane.size(), 3ul); // NOLINT
263  EXPECT_TRUE(std::find(std::begin(remainingLane), std::end(remainingLane), ConstLanelet(lanelets.at(2018))) !=
264  std::end(remainingLane));
265 
266  auto fullLane{route.fullLane(lanelets.at(2020).invert())};
267  EXPECT_EQ(fullLane.size(), 5ul); // NOLINT
268  EXPECT_TRUE(std::find(std::begin(fullLane), std::end(fullLane), ConstLanelet(lanelets.at(2021))) !=
269  std::end(fullLane));
270  EXPECT_EQ(route.numLanes(), 1ul); // NOLINT
271 }
272 
274  auto remainingLane{route.remainingLane(lanelets.at(2020))};
275  EXPECT_EQ(remainingLane.size(), 4ul); // NOLINT
276  EXPECT_FALSE(std::find(std::begin(remainingLane), std::end(remainingLane), ConstLanelet(lanelets.at(2018))) !=
277  std::end(remainingLane));
278 
279  auto fullLane{route.fullLane(lanelets.at(2020))};
280  EXPECT_EQ(fullLane.size(), 6ul); // NOLINT
281  EXPECT_TRUE(std::find(std::begin(fullLane), std::end(fullLane), ConstLanelet(lanelets.at(2021))) ==
282  std::end(fullLane));
283  EXPECT_EQ(route.numLanes(), 1ul); // NOLINT
284 }
285 
286 TEST_F(RouteMaxHoseLeftRightDashedSolid, DashedSolidLineRegarded) { // NOLINT
287  EXPECT_FALSE(!!route.rightRelation(lanelets.at(2025)));
288 }
289 
291  EXPECT_EQ(route.numLanes(), 1ul); // NOLINT
292  EXPECT_TRUE(route.remainingLane(lanelets.at(2026)).empty());
293 }
294 
296  EXPECT_EQ(route.size(), 7ul); // NOLINT
297 }
298 
299 TEST_F(RouteMaxHoseLeftRightDashedSolidFurther, DashedSolidLineRegarded) { // NOLINT
300  EXPECT_FALSE(!!route.rightRelation(lanelets.at(2025)));
301 }
302 
303 TEST_F(RouteSolidDashed, Lanes) { // NOLINT
304  EXPECT_EQ(route.numLanes(), 2ul); // NOLINT
305 }
306 
308  EXPECT_EQ(route.numLanes(), 2ul); // NOLINT
309 }
310 
311 TEST_F(RouteSolidDashedWithAdjacent, AdjacentLaneletInRoute) { // NOLINT
312  ASSERT_TRUE(!!route.rightRelation(lanelets.at(2025)));
313  EXPECT_EQ(*route.rightRelation(lanelets.at(2025)), // NOLINT
314  (LaneletRelation{lanelets.at(2026), RelationType::Right}));
315  ASSERT_TRUE(!!route.leftRelation(lanelets.at(2026)));
316  EXPECT_EQ(*route.leftRelation(lanelets.at(2026)), // NOLINT
317  (LaneletRelation{lanelets.at(2025), RelationType::AdjacentLeft}));
318  ASSERT_TRUE(!!route.rightRelation(lanelets.at(2027)));
319  EXPECT_EQ(*route.rightRelation(lanelets.at(2027)), // NOLINT
320  (LaneletRelation{lanelets.at(2028), RelationType::AdjacentRight}));
321  ASSERT_TRUE(!!route.leftRelation(lanelets.at(2028)));
322  EXPECT_EQ(*route.leftRelation(lanelets.at(2028)), // NOLINT
323  (LaneletRelation{lanelets.at(2027), RelationType::AdjacentLeft}));
324  ASSERT_TRUE(!!route.rightRelation(lanelets.at(2029)));
325  EXPECT_EQ(*route.rightRelation(lanelets.at(2029)), // NOLINT
326  (LaneletRelation{lanelets.at(2030), RelationType::AdjacentRight}));
327  ASSERT_TRUE(!!route.leftRelation(lanelets.at(2030)));
328  EXPECT_EQ(*route.leftRelation(lanelets.at(2030)), // NOLINT
329  (LaneletRelation{lanelets.at(2029), RelationType::Left}));
330 }
331 
332 TEST_F(RouteViaSimple, create) { // NOLINT
333  EXPECT_EQ(route.size(), 15ul);
334  EXPECT_EQ(route.shortestPath(), *graph->shortestPath(start, end, 0));
335 }
336 
337 TEST_F(RouteMissingLanelet, create) { // NOLINT
338  EXPECT_EQ(route.size(), 15ul); // NOLINT
339  EXPECT_EQ(route.shortestPath(), *graph->shortestPath(start, end, 0)); // NOLINT
340 }
341 
342 TEST_F(GermanVehicleGraph, CannotCreateRoute) { // NOLINT
343  Optional<Route> route{graph->getRoute(lanelets.at(2014), lanelets.at(2007), 0)};
344  EXPECT_FALSE(!!route);
345  // NOLINTNEXTLINE
346  EXPECT_THROW(graph->getRoute(lanelets.at(2001), lanelets.at(2004), numCostModules), lanelet::InvalidInputError);
347 }
348 
349 TEST_F(RouteSplittedDiverging, Completeness) { // NOLINT
350  EXPECT_EQ(route.laneletSubmap()->laneletLayer.size(), 7ul); // NOLINT
351  EXPECT_EQ(route.numLanes(), 3ul); // NOLINT
352 }
353 
354 TEST_F(RouteSplittedDivergingAndMerging, Completeness) { // NOLINT
355  EXPECT_EQ(route.laneletSubmap()->laneletLayer.size(), 11ul); // NOLINT
356  EXPECT_EQ(route.numLanes(), 5ul); // NOLINT
357 }
358 
359 TEST_F(RouteInCircle, create) { // NOLINT
360  EXPECT_EQ(route.laneletSubmap()->laneletLayer.size(), 11ul); // NOLINT
361  EXPECT_EQ(route.numLanes(), 3ul); // NOLINT
362  EXPECT_EQ(route.remainingLane(lanelets.at(2067)).size(), 0ul); // NOLINT
363 }
364 
365 TEST_F(RouteCircular, Circularity) { // NOLINT
366  EXPECT_EQ(route.size(), 10ul);
367  // at any point of the circular route, the remaining lane should cross the circle
368  EXPECT_EQ(route.remainingLane(start).size(), 6ul);
369  EXPECT_EQ(*route.remainingLane(start).begin(), start);
370  EXPECT_EQ(route.remainingLane(lanelets.at(2036)).size(), 7ul);
371  EXPECT_EQ(route.remainingShortestPath(lanelets.at(2067)).size(), 7ul);
372  EXPECT_EQ(route.remainingLane(lanelets.at(2067)).size(), 1ul);
373  EXPECT_EQ(route.remainingShortestPath(lanelets.at(2067)).front(), lanelets.at(2067));
374  EXPECT_EQ(route.remainingLane(lanelets.at(2033)).size(), 3ul);
375 }
376 
377 TEST_F(RouteCircularNoLc, Circularity) { // NOLINT
378  EXPECT_EQ(route.size(), 7ul);
379  EXPECT_EQ(route.numLanes(), 1ul);
380  EXPECT_EQ(route.remainingLane(start).size(), 7ul);
381  EXPECT_EQ(route.remainingShortestPath(lanelets.at(2036)).size(), 7ul);
382  EXPECT_EQ(route.remainingLane(lanelets.at(2067)).size(), 7ul);
383 }
TEST_F
TEST_F(Route1, CreateRoute1)
Definition: test_route.cpp:97
RouteSolidDashed
Definition: test_route.cpp:46
Route1NoLc
Definition: test_route.cpp:34
Route1
Definition: test_route.cpp:33
RoutingGraph.h
LaneletMapPtr
std::shared_ptr< LaneletMap > LaneletMapPtr
lanelet
TestRoute
Definition: test_route.cpp:12
TestRoute::start
ConstLanelet start
Definition: test_route.cpp:24
hasRelation
bool hasRelation(const LaneletRelations &relations, const ConstLanelet &llt, RelationType relationType)
Definition: test_route.cpp:109
Id
int64_t Id
lanelet::routing::RelationType
RelationType
Definition: Forward.h:56
Ids
std::vector< Id > Ids
Route2
Definition: test_route.cpp:38
RouteMaxHoseLeftRightDashedSolid
Definition: test_route.cpp:44
lanelet::routing::tests
Definition: test_routing_map.h:17
lanelet::routing
Definition: Forward.h:11
TestRoute::TestRoute
TestRoute(uint16_t routingCostId=0, bool withLaneChanges=true)
Definition: test_route.cpp:14
RouteCircularNoLc
Definition: test_route.cpp:54
lanelet::routing::RelationType::Successor
@ Successor
A (the only) direct, reachable successor. Not merging and not diverging.
lanelet::routing::LaneletVisitInformation
This object carries the required information for the graph neighbourhood search.
Definition: Types.h:22
TestRoute::via
ConstLanelets via
Definition: test_route.cpp:26
lanelet::routing::tests::GermanVehicleGraph
Definition: test_routing_map.h:493
RouteCircularNoLc::RouteCircularNoLc
RouteCircularNoLc()
Definition: test_route.cpp:56
lanelet::utils::transform
auto transform(Container &&c, Func f)
Optional
boost::optional< T > Optional
RouteSplittedDivergingAndMerging
Definition: test_route.cpp:49
Route.h
Route3
Definition: test_route.cpp:39
RouteMaxHoseLeftRight
Definition: test_route.cpp:42
RouteMissingLanelet
Definition: test_route.cpp:51
lanelet::routing::LaneletRelations
std::vector< LaneletRelation > LaneletRelations
Definition: Forward.h:34
RouteMaxHoseRightLeft
Definition: test_route.cpp:43
AllRoutes
testing::Types< Route1, Route1NoLc, Route2, Route3, Route4, Route5, RouteMaxHoseLeftRight, RouteMaxHoseRightLeft, RouteMaxHoseLeftRightDashedSolid, RouteMaxHoseLeftRightDashedSolidFurther, RouteSolidDashed, RouteSolidDashedWithAdjacent, RouteSplittedDiverging, RouteSplittedDivergingAndMerging, RouteViaSimple, RouteMissingLanelet, RouteInCircle, RouteCircular, RouteCircularNoLc > AllRoutes
Definition: test_route.cpp:66
lanelet::routing::LaneletRelation
Represents the relation of a lanelet to another lanelet.
Definition: Types.h:34
RouteCircular
Definition: test_route.cpp:53
lanelet::routing::tests::TYPED_TEST_SUITE
TYPED_TEST_SUITE(AllGraphsTest, AllGraphs)
lanelet::Point3d
Route4
Definition: test_route.cpp:40
Route1NoLc::Route1NoLc
Route1NoLc()
Definition: test_route.cpp:36
RouteSolidDashedWithAdjacent
Definition: test_route.cpp:47
lanelet::utils::anyOf
bool anyOf(const Container &c, Predicate &&p)
TestRoute::end
ConstLanelet end
Definition: test_route.cpp:25
RouteInCircle
Definition: test_route.cpp:52
lanelet::routing::Route
The famous route object that marks a route from A to B.
Definition: Route.h:36
RouteViaSimple
Definition: test_route.cpp:50
TestRoute::route
Route route
Definition: test_route.cpp:27
RouteMaxHoseLeftRightDashedSolidFurther
Definition: test_route.cpp:45
LaneletSubmapConstPtr
std::shared_ptr< const LaneletSubmap > LaneletSubmapConstPtr
lanelet::ConstLanelet
AllRoutesTest
Definition: test_route.cpp:60
RouteSplittedDiverging
Definition: test_route.cpp:48
TYPED_TEST
TYPED_TEST(AllRoutesTest, CheckValidity)
Definition: test_route.cpp:70
Route5
Definition: test_route.cpp:41
test_routing_map.h
hasLanelet
bool hasLanelet(const ContainerT &llts, const ConstLanelet &llt)
Definition: test_route.cpp:115
ConstLanelets
std::vector< ConstLanelet > ConstLanelets
lanelet::InvalidInputError


lanelet2_routing
Author(s): Matthias Mayr
autogenerated on Sun Oct 27 2024 02:27:49