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


lanelet2_routing
Author(s): Matthias Mayr
autogenerated on Thu Mar 6 2025 03:26:10