routing.cpp
Go to the documentation of this file.
3 
4 #include <boost/make_shared.hpp>
5 
8 
9 using namespace boost::python;
10 using namespace lanelet;
11 
13  const ConstLanelet& from, const ConstLanelet& to,
15  bool withLaneChange) {
16  auto route = self.getRoute(from, to, costId, withLaneChange);
17  if (!route) {
18  return {};
19  }
20  return std::make_shared<lanelet::routing::Route>(std::move(*route));
21 }
22 
24  const ConstLanelet& from,
25  const ConstLanelets& via, const ConstLanelet& to,
27  bool withLaneChange) {
28  auto route = self.getRouteVia(from, via, to, costId, withLaneChange);
29  if (!route) {
30  return {};
31  }
32  return std::make_shared<lanelet::routing::Route>(std::move(*route));
33 }
34 
36  const routing::RoutingCostPtrs& routingCosts) {
37  return routing::RoutingGraph::build(laneletMap, trafficRules, routingCosts);
38 }
39 
41  const traffic_rules::TrafficRules& trafficRules,
42  const routing::RoutingCostPtrs& routingCosts) {
43  return routing::RoutingGraph::build(laneletMap, trafficRules, routingCosts);
44 }
45 
46 template <typename T>
47 object optionalToObject(const Optional<T>& v) {
48  return v ? object(*v) : object();
49 }
50 
51 template <typename T>
52 Optional<T> objectToOptional(const object& o) {
53  return o == object() ? Optional<T>{} : Optional<T>{extract<T>(o)()};
54 }
55 
56 class RoutingCostBaseWrapper : public lanelet::routing::RoutingCost, public wrapper<lanelet::routing::RoutingCost> {
57  public:
58  double getCostSucceeding(const traffic_rules::TrafficRules& trafficRules, const ConstLaneletOrArea& from,
59  const ConstLaneletOrArea& to) const noexcept override {
60  return this->get_override("getCostSucceeding")(boost::ref(trafficRules), from, to);
61  }
62 
63  double getCostLaneChange(const traffic_rules::TrafficRules& trafficRules, const ConstLanelets& from,
64  const ConstLanelets& to) const noexcept override {
65  return this->get_override("getCostLaneChange")(boost::ref(trafficRules), from, to);
66  }
67 };
68 
69 template <typename BaseT>
70 class RoutingCostWrapper : public BaseT, public wrapper<BaseT> {
71  public:
72  RoutingCostWrapper(const BaseT& base) : BaseT(base) {}
73  RoutingCostWrapper(double laneChangeCost, double minLaneChange) : BaseT(laneChangeCost, minLaneChange) {}
74 
75  double getCostSucceeding(const traffic_rules::TrafficRules& trafficRules, const ConstLaneletOrArea& from,
76  const ConstLaneletOrArea& to) const noexcept override {
77  const auto o = this->get_override("getCostSucceeding");
78  if (o) {
79  return o(boost::ref(trafficRules), from, to);
80  }
81  return BaseT::getCostSucceeding(trafficRules, from, to);
82  }
83 
85  const ConstLaneletOrArea& to) const {
86  return BaseT::getCostSucceeding(trafficRules, from, to);
87  }
88 
89  double getCostLaneChange(const traffic_rules::TrafficRules& trafficRules, const ConstLanelets& from,
90  const ConstLanelets& to) const noexcept override {
91  const auto o = this->get_override("getCostLaneChange");
92  if (o) {
93  return o(boost::ref(trafficRules), from, to);
94  }
95  return BaseT::getCostLaneChange(trafficRules, from, to);
96  }
97 
98  double defaultGetCostLaneChange(const traffic_rules::TrafficRules& trafficRules, const ConstLanelets& from,
99  const ConstLanelets& to) const {
100  return BaseT::getCostLaneChange(trafficRules, from, to);
101  }
102 };
103 
104 BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT
105  auto trafficRules = import("lanelet2.traffic_rules");
106  using namespace lanelet::routing;
107  using namespace lanelet::python;
108 
112  OptionalConverter<Route>();
113  OptionalConverter<std::shared_ptr<Route>>();
114  OptionalConverter<RelationType>();
115  OptionalConverter<LaneletRelation>();
116  OptionalConverter<LaneletPath>();
117 
118  VectorToListConverter<LaneletRelations>();
119  VectorToListConverter<RoutingCostPtrs>();
120  VectorToListConverter<LaneletPaths>();
121 
122  // Register interable conversions.
123  IterableConverter().fromPython<RoutingCostPtrs>();
124 
125  implicitly_convertible<std::shared_ptr<RoutingCostDistance>, RoutingCostPtr>();
126  implicitly_convertible<std::shared_ptr<RoutingCostTravelTime>, RoutingCostPtr>();
127  implicitly_convertible<LaneletMapPtr, LaneletMapConstPtr>();
128 
129  // Routing costs
130  class_<RoutingCostBaseWrapper, boost::noncopyable>( // NOLINT
131  "RoutingCost", "Object for calculating routing costs between lanelets")
132  .def("getCostSucceeding", pure_virtual(&RoutingCost::getCostSucceeding),
133  "Get the cost of the transition from one to another lanelet", (arg("trafficRules"), arg("from"), arg("to")))
134  .def("getCostLaneChange", pure_virtual(&RoutingCost::getCostLaneChange),
135  "Get the cost of the lane change between two adjacent lanelets",
136  (arg("trafficRules"), arg("from"), arg("to")));
137  register_ptr_to_python<std::shared_ptr<RoutingCost>>();
138 
139  class_<RoutingCostWrapper<RoutingCostDistance>, bases<RoutingCost>>( // NOLINT
140  "RoutingCostDistance", "Distance based routing cost calculation object",
141  init<double, double>((arg("laneChangeCost"), arg("minLaneChangeDistance") = 0)))
142  .def("getCostSucceeding", &RoutingCostDistance::getCostSucceeding,
144  "Get the cost of the transition from one to another lanelet", (arg("trafficRules"), arg("from"), arg("to")))
145  .def("getCostLaneChange", &RoutingCostDistance::getCostLaneChange,
147  "Get the cost of the lane change between two adjacent lanelets",
148  (arg("trafficRules"), arg("from"), arg("to")));
149  register_ptr_to_python<std::shared_ptr<RoutingCostDistance>>();
150 
151  class_<RoutingCostWrapper<RoutingCostTravelTime>, bases<RoutingCost>>( // NOLINT
152  "RoutingCostTravelTime", "Travel time based routing cost calculation object",
153  init<double, double>((arg("laneChangeCost"), arg("minLaneChangeTime") = 0)))
154  .def("getCostSucceeding", &RoutingCostTravelTime::getCostSucceeding,
156  "Get the cost of the transition from one to another lanelet", (arg("trafficRules"), arg("from"), arg("to")))
157  .def("getCostLaneChange", &RoutingCostTravelTime::getCostLaneChange,
159  "Get the cost of the lane change between two adjacent lanelets",
160  (arg("trafficRules"), arg("from"), arg("to")));
161  register_ptr_to_python<std::shared_ptr<RoutingCostTravelTime>>();
162 
163  auto possPCost = static_cast<LaneletPaths (RoutingGraph::*)(const ConstLanelet&, double, RoutingCostId, bool) const>(
164  &RoutingGraph::possiblePaths);
165  auto possPLen = static_cast<LaneletPaths (RoutingGraph::*)(const ConstLanelet&, uint32_t, bool, RoutingCostId) const>(
166  &RoutingGraph::possiblePaths);
167  auto possPParam = static_cast<LaneletPaths (RoutingGraph::*)(const ConstLanelet&, const PossiblePathsParams&) const>(
168  &RoutingGraph::possiblePaths);
169  auto possPToCost =
170  static_cast<LaneletPaths (RoutingGraph::*)(const ConstLanelet&, double, RoutingCostId, bool) const>(
171  &RoutingGraph::possiblePathsTowards);
172  auto possPToLen =
173  static_cast<LaneletPaths (RoutingGraph::*)(const ConstLanelet&, uint32_t, bool, RoutingCostId) const>(
174  &RoutingGraph::possiblePathsTowards);
175  auto possPToParam =
176  static_cast<LaneletPaths (RoutingGraph::*)(const ConstLanelet&, const PossiblePathsParams&) const>(
177  &RoutingGraph::possiblePathsTowards);
178 
179  class_<LaneletPath>("LaneletPath",
180  "A set of consecutive lanelets connected in straight "
181  "directon or by lane changes",
182  init<ConstLanelets>(arg("lanelets")))
183  .def("__iter__", iterator<LaneletPath>())
184  .def("__len__", &LaneletPath::size)
185  .def("__getitem__", wrappers::getItem<LaneletPath>, return_internal_reference<>())
186  .def(
187  "getRemainingLane",
188  +[](const LaneletPath& self, const ConstLanelet& llt) { return self.getRemainingLane(llt); },
189  "get the sequence of remaining lanelets without a lane change")
190  .def(
191  "__repr__",
192  +[](const LaneletPath& self) {
193  return makeRepr("LaneletPath", repr(list(ConstLanelets{self.begin(), self.end()})));
194  })
195  .def(self == self) // NOLINT
196  .def(self != self); // NOLINT
197 
198  class_<LaneletVisitInformation>("LaneletVisitInformation",
199  "Object passed as input for the forEachSuccessor function of the routing graph")
200  .def_readwrite("lanelet", &LaneletVisitInformation::lanelet, "the currently visited lanelet")
201  .def_readwrite("predecessor", &LaneletVisitInformation::predecessor, "the predecessor within the shortest path")
202  .def_readwrite("length", &LaneletVisitInformation::length,
203  "The length of the shortest path to this lanelet (including lanelet")
204  .def_readwrite("cost", &LaneletVisitInformation::cost, "The cost along the shortest path")
205  .def_readwrite("numLaneChanges", &LaneletVisitInformation::numLaneChanges,
206  "The number of lane changes necessary along the shortest path");
207 
208  class_<LaneletOrAreaVisitInformation>(
209  "LaneletOrAreaVisitInformation",
210  "Object passed as input for the forEachSuccessorIncludingAreas function of the routing graph")
211  .def_readwrite("laneletOrArea", &LaneletOrAreaVisitInformation::laneletOrArea,
212  "the currently visited lanelet/area")
213  .def_readwrite("predecessor", &LaneletOrAreaVisitInformation::predecessor,
214  "the predecessor within the shortest path")
215  .def_readwrite("length", &LaneletOrAreaVisitInformation::length,
216  "The length of the shortest path to this lanelet (including lanelet")
217  .def_readwrite("cost", &LaneletOrAreaVisitInformation::cost, "The cost along the shortest path")
218  .def_readwrite("numLaneChanges", &LaneletOrAreaVisitInformation::numLaneChanges,
219  "The number of lane changes necessary along the shortest path");
220 
221  class_<PossiblePathsParams>(
222  "PossiblePathsParams", "Parameters for configuring the behaviour of the possible path algorithms of RoutingGraph")
223  .def("__init__",
224  make_constructor(
225  +[](const object& costLimit, const object& elemLimit, RoutingCostId costId, bool includeLc,
226  bool includeShorter) {
227  return boost::make_shared<PossiblePathsParams>(PossiblePathsParams{
228  objectToOptional<double>(costLimit), objectToOptional<std::uint32_t>(elemLimit), costId, includeLc,
229  includeShorter});
230  },
231  default_call_policies{},
232  (arg("routingCostLimit") = object(), arg("elementLimit") = object(), arg("routingCostId") = 0,
233  arg("includeLaneChanges") = false, arg("includeShorterPaths") = false)))
234  .add_property(
235  "routingCostLimit", +[](const PossiblePathsParams& self) { return optionalToObject(self.routingCostLimit); },
236  +[](PossiblePathsParams& self, const object& value) {
237  self.routingCostLimit = objectToOptional<double>(value);
238  })
239  .add_property(
240  "elementLimit", +[](const PossiblePathsParams& self) { return optionalToObject(self.elementLimit); },
241  +[](PossiblePathsParams& self, const object& value) {
242  self.elementLimit = objectToOptional<std::uint32_t>(value);
243  })
244  .def_readwrite("routingCostId", &PossiblePathsParams::routingCostId)
245  .def_readwrite("includeLaneChanges", &PossiblePathsParams::includeLaneChanges)
246  .def_readwrite("includeShorterPaths", &PossiblePathsParams::includeShorterPaths);
247 
248  auto lltAndLc = (arg("lanelet"), arg("withLaneChanges") = false);
249  auto lltAndRoutingCost = (arg("lanelet"), arg("routingCostId") = 0);
250  class_<RoutingGraph, boost::noncopyable, RoutingGraphPtr>(
251  "RoutingGraph",
252  "Main class of the routing module that holds routing information and can "
253  "be queried",
254  no_init)
255  .def("__init__",
256  make_constructor(makeRoutingGraph, default_call_policies(),
257  (arg("laneletMap"), arg("trafficRules"), arg("routingCost") = defaultRoutingCosts())),
258  "Initialization with default routing costs")
259  .def("__init__",
260  make_constructor(makeRoutingGraphSubmap, default_call_policies(),
261  (arg("laneletSubmap"), arg("trafficRules"), arg("routingCost") = defaultRoutingCosts())),
262  "Initialization from a submap")
263  .def("getRoute", getRouteWrapper, "driving route from 'start' to 'end' lanelet",
264  (arg("from"), arg("to"), arg("routingCostId") = 0, arg("withLaneChanges") = true))
265  .def("getRouteVia", getRouteViaWrapper, "driving route from 'start' to 'end' lanelet using the 'via' lanelets",
266  (arg("from"), arg("via"), arg("to"), arg("routingCostId") = 0, arg("withLaneChanges") = true))
267  .def("shortestPath", &RoutingGraph::shortestPath, "shortest path between 'start' and 'end'",
268  (arg("from"), arg("to"), arg("routingCostId") = 0, arg("withLaneChanges") = true))
269  .def("shortestPathWithVia", &RoutingGraph::shortestPathVia,
270  "shortest path between 'start' and 'end' using intermediate points",
271  (arg("start"), arg("via"), arg("end"), arg("routingCostId") = 0, arg("withLaneChanges") = true))
272  .def("routingRelation", &RoutingGraph::routingRelation, "relation between two lanelets excluding 'conflicting'",
273  (arg("from"), arg("to"), arg("includeConflicting") = false))
274  .def("following", &RoutingGraph::following, "lanelets that can be reached from this lanelet", lltAndLc)
275  .def("followingRelations", &RoutingGraph::followingRelations, "relations to following lanelets", lltAndLc)
276  .def("previous", &RoutingGraph::previous, "previous lanelets of this lanelet", lltAndLc)
277  .def("previousRelations", &RoutingGraph::previousRelations, "relations to preceding lanelets", lltAndLc)
278  .def("besides", &RoutingGraph::besides,
279  "all reachable left and right lanelets, including lanelet, from "
280  "left to right",
281  lltAndRoutingCost)
282  .def("left", &RoutingGraph::left, "left (routable)lanelet, if exists", lltAndRoutingCost)
283  .def("right", &RoutingGraph::right, "right (routable)lanelet, if it exists", lltAndRoutingCost)
284  .def("adjacentLeft", &RoutingGraph::adjacentLeft, "left non-routable lanelet", lltAndRoutingCost)
285  .def("adjacentRight", &RoutingGraph::adjacentRight, "right non-routable lanelet", lltAndRoutingCost)
286  .def("lefts", &RoutingGraph::lefts, "all left (routable) lanelets", lltAndRoutingCost)
287  .def("rights", &RoutingGraph::rights, "all right (routable) lanelets", lltAndRoutingCost)
288  .def("adjacentLefts", &RoutingGraph::adjacentLefts, "all left (non-routable) lanelets", lltAndRoutingCost)
289  .def("adjacentRights", &RoutingGraph::adjacentRights, "all right (non-routable) lanelets", lltAndRoutingCost)
290  .def("leftRelations", &RoutingGraph::leftRelations, "relations to left lanelets", lltAndRoutingCost)
291  .def("rightRelations", &RoutingGraph::rightRelations, "relations to right lanelets", lltAndRoutingCost)
292  .def("conflicting", &RoutingGraph::conflicting, "Conflicting lanelets", arg("lanelet"))
293  .def("reachableSet", &RoutingGraph::reachableSet, "set of lanelets that can be reached from a given lanelet",
294  (arg("lanelet"), arg("maxRoutingCost"), arg("RoutingCostId") = 0, arg("allowLaneChanges") = true))
295  .def("reachableSetTowards", &RoutingGraph::reachableSetTowards, "set of lanelets that can reach a given lanelet",
296  (arg("lanelet"), arg("maxRoutingCost"), arg("RoutingCostId") = 0, arg("allowLaneChanges") = true))
297  .def("possiblePaths", possPCost, "possible paths from a given start lanelet that are 'minRoutingCost'-long",
298  (arg("lanelet"), arg("minRoutingCost"), arg("RoutingCostId") = 0, arg("allowLaneChanges") = false,
299  arg("routingCostId") = 0))
300  .def("possiblePaths", possPParam, "possible paths from a given start lanelet as configured in parameters",
301  (arg("lanelet"), arg("parameters")))
302  .def("possiblePathsTowards", possPToCost,
303  "possible paths to a given start lanelet that are 'minRoutingCost'-long",
304  (arg("lanelet"), arg("minRoutingCost"), arg("RoutingCostId") = 0, arg("allowLaneChanges") = false,
305  arg("routingCostId") = 0))
306  .def("possiblePathsTowards", possPToParam, "possible paths to a given lanelet as configured in parameters",
307  (arg("lanelet"), arg("parameters")))
308  .def("possiblePathsMinLen", possPLen, "possible routes from a given start lanelet that are 'minLanelets'-long",
309  (arg("lanelet"), arg("minLanelets"), arg("allowLaneChanges") = false, arg("routingCostId") = 0))
310  .def("possiblePathsTowardsMinLen", possPToLen,
311  "possible routes from a given start lanelet that are 'minLanelets'-long",
312  (arg("lanelet"), arg("minLanelets"), arg("allowLaneChanges") = false, arg("routingCostId") = 0))
313  .def(
314  "forEachSuccessor",
315  +[](RoutingGraph& self, const ConstLanelet& from, object func, bool lc, RoutingCostId costId) {
316  self.forEachSuccessor(from, std::move(func), lc, costId);
317  },
318  "calls a function on each successor of lanelet with increasing cost. The function must receives a "
319  "LaneletVisitInformation object as input and must return a bool whether followers of the current lanelet "
320  "should be visited as well. The function can raise an exception if an early exit is desired",
321  (arg("lanelet"), arg("func"), arg("allowLaneChanges") = true, arg("routingCostId") = 0))
322  .def(
323  "forEachSuccessorIncludingAreas",
324  +[](RoutingGraph& self, const ConstLaneletOrArea& from, object func, bool lc, RoutingCostId costId) {
325  self.forEachSuccessorIncludingAreas(from, std::move(func), lc, costId);
326  },
327  "similar to forEachSuccessor but also includes areas into the search",
328  (arg("lanelet"), arg("func"), arg("allowLaneChanges") = true, arg("routingCostId") = 0))
329  .def(
330  "forEachPredecessor",
331  +[](RoutingGraph& self, const ConstLanelet& from, object func, bool lc, RoutingCostId costId) {
332  self.forEachPredecessor(from, std::move(func), lc, costId);
333  },
334  "similar to forEachSuccessor but instead goes backwards along the routing graph",
335  (arg("lanelet"), arg("func"), arg("allowLaneChanges") = true, arg("routingCostId") = 0))
336  .def(
337  "forEachPredecessorIncludingAreas",
338  +[](RoutingGraph& self, const ConstLaneletOrArea& from, object func, bool lc, RoutingCostId costId) {
339  self.forEachPredecessorIncludingAreas(from, std::move(func), lc, costId);
340  },
341  "calls a function on each successor of lanelet. The function must receives a LaneletVisitInformation object "
342  "as input and must return a bool whether followers of the current lanelet should be visited as well. The "
343  "function can throw an exception if an early exit is desired",
344  (arg("lanelet"), arg("func"), arg("allowLaneChanges") = true, arg("routingCostId") = 0))
345  .def(
346  "exportGraphML", +[](RoutingGraph& self, const std::string& path) { self.exportGraphML(path); },
347  "Export the internal graph to graphML (xml-based) file format")
348  .def(
349  "exportGraphViz", +[](RoutingGraph& self, const std::string& path) { self.exportGraphViz(path); },
350  "Export the internal graph to graphViz (DOT) file format")
351  .def("getDebugLaneletMap", &RoutingGraph::getDebugLaneletMap,
352  "abstract lanelet map holding the information of the routing graph",
353  (arg("routingCostId") = 0, arg("includeAdjacent") = false, arg("includeConflicting") = false))
354  .def("passableLaneletSubmap", &RoutingGraph::passableSubmap, "LaneletMap that includes all passable lanelets")
355  .def("checkValidity", &RoutingGraph::checkValidity, "Performs some basic sanity checks",
356  (arg("throwOnError") = true));
357 
358  class_<LaneletRelation>("LaneletRelation")
359  .def_readwrite("lanelet", &LaneletRelation::lanelet)
360  .def_readwrite("relationType", &LaneletRelation::relationType)
361  .def(
362  "__repr__", +[](const LaneletRelation& self) {
363  return makeRepr("LaneletRelation", repr(object(self.lanelet)), repr(object(self.relationType)));
364  });
365 
366  enum_<RelationType>("RelationType")
367  .value("Successor", RelationType::Successor)
368  .value("Left", RelationType::Left)
369  .value("Right", RelationType::Right)
370  .value("Conflicting", RelationType::Conflicting)
371  .value("AdjacentLeft", RelationType::AdjacentLeft)
372  .value("AdjacentRight", RelationType::AdjacentRight)
373  .export_values();
374 
375  class_<Route, boost::noncopyable, std::shared_ptr<Route>>("Route",
376  "The famous route object that marks a route from A to B, "
377  "including all lanelets that can be used",
378  no_init)
379  .def("shortestPath", &Route::shortestPath, "Returns the shortest path along this route",
380  return_internal_reference<>())
381  .def("fullLane", &Route::fullLane, "Returns the complete lane a Lanelet belongs to")
382  .def("remainingLane", &Route::remainingLane, "Returns that remaining lane a Lanelet belongs to")
383  .def("remainingShortestPath", &Route::remainingShortestPath,
384  "Returns all lanelets on the shortest path that follow the input lanelet")
385  .def("length2d", &Route::length2d, "2d length of shortest path")
386  .def("numLanes", &Route::numLanes, "Number of inidividual lanes")
387  .def(
388  "laneletSubmap", +[](const Route& r) { return std::const_pointer_cast<LaneletSubmap>(r.laneletSubmap()); },
389  "laneletSubmap with all lanelets that are part of the route")
390  .def("getDebugLaneletMap", &Route::getDebugLaneletMap,
391  "laneletMap that represents the Lanelets of the Route and their relationship")
392  .def("size", &Route::size, "Number of lanelets")
393  .def("followingRelations", &Route::followingRelations, "Provides the following lanelets within the Route")
394  .def("previousRelations", &Route::previousRelations, "Provides the previous lanelets within the Route")
395  .def("leftRelation", &Route::leftRelation, "Provides the lanelet left of a given lanelet within the Route")
396  .def("leftRelations", &Route::leftRelations, "*all* lanelets left of a given lanelet within the Route")
397  .def("rightRelation", &Route::rightRelation, "Provides the lanelet right of a given lanelet within the Route")
398  .def("rightRelations", &Route::rightRelations, "*all* lanelets right of a given lanelet within the Route")
399  .def("conflictingInRoute", &Route::conflictingInRoute, "conflicting lanelets of a lanelet within the route")
400  .def("conflictingInMap", &Route::conflictingInMap,
401  "conflicting lanelets of a lanelet within all passable lanelets in the laneletMap")
402  .def("allConflictingInMap", &Route::allConflictingInMap,
403  "all lanelets in the map that conflict with any lanelet in the route")
404  .def(
405  "forEachSuccessor",
406  +[](Route& self, const ConstLanelet& from, object func) { self.forEachSuccessor(from, std::move(func)); },
407  "calls a function on each successor of lanelet with increasing cost. The function must receives a "
408  "LaneletVisitInformation object as input and must return a bool whether followers of the current lanelet "
409  "should be visited as well. The function can raise an exception if an early exit is desired",
410  (arg("lanelet"), arg("func")))
411  .def(
412  "forEachPredecessor",
413  +[](Route& self, const ConstLanelet& from, object func) { self.forEachPredecessor(from, std::move(func)); },
414  "similar to forEachSuccessor but instead goes backwards along the routing graph",
415  (arg("lanelet"), arg("func")))
416  .def("__contains__", &Route::contains, "Checks if a specific lanelet is part of the route", (arg("lanelet")))
417  .def("checkValidity", &Route::checkValidity, "perform sanity check on the route");
418 }
RoutingCostWrapper::RoutingCostWrapper
RoutingCostWrapper(const BaseT &base)
Definition: routing.cpp:72
RoutingCostWrapper::RoutingCostWrapper
RoutingCostWrapper(double laneChangeCost, double minLaneChange)
Definition: routing.cpp:73
lanelet
getRouteWrapper
Optional< std::shared_ptr< lanelet::routing::Route > > getRouteWrapper(const lanelet::routing::RoutingGraph &self, const ConstLanelet &from, const ConstLanelet &to, lanelet::routing::RoutingCostId costId, bool withLaneChange)
Definition: routing.cpp:12
lanelet::traffic_rules::TrafficRules
lanelet::routing::RoutingCostPtrs
std::vector< RoutingCostPtr > RoutingCostPtrs
lanelet::routing::RoutingCost
lanelet::routing::Route::laneletSubmap
LaneletSubmapConstPtr laneletSubmap() const noexcept
optionalToObject
object optionalToObject(const Optional< T > &v)
Definition: routing.cpp:47
BOOST_PYTHON_MODULE
BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME)
Definition: routing.cpp:104
lanelet::ConstLaneletOrArea
makeRoutingGraphSubmap
routing::RoutingGraphPtr makeRoutingGraphSubmap(LaneletSubmap &laneletMap, const traffic_rules::TrafficRules &trafficRules, const routing::RoutingCostPtrs &routingCosts)
Definition: routing.cpp:40
RoutingCostWrapper::getCostSucceeding
double getCostSucceeding(const traffic_rules::TrafficRules &trafficRules, const ConstLaneletOrArea &from, const ConstLaneletOrArea &to) const noexcept override
Definition: routing.cpp:75
objectToOptional
Optional< T > objectToOptional(const object &o)
Definition: routing.cpp:52
RoutingCostBaseWrapper::getCostSucceeding
double getCostSucceeding(const traffic_rules::TrafficRules &trafficRules, const ConstLaneletOrArea &from, const ConstLaneletOrArea &to) const noexcept override
Definition: routing.cpp:58
repr.h
lanelet::routing
RoutingCostPtr
std::shared_ptr< RoutingCost > RoutingCostPtr
LaneletPaths
std::vector< LaneletPath > LaneletPaths
converter.h
lanelet::LaneletMap
Optional
boost::optional< T > Optional
defaultRoutingCosts
RoutingCostPtrs defaultRoutingCosts()
lanelet::routing::PossiblePathsParams
RoutingCostWrapper::defaultGetCostSucceeding
double defaultGetCostSucceeding(const traffic_rules::TrafficRules &trafficRules, const ConstLaneletOrArea &from, const ConstLaneletOrArea &to) const
Definition: routing.cpp:84
lanelet::routing::RoutingGraphPtr
std::shared_ptr< RoutingGraph > RoutingGraphPtr
lanelet::python::repr
std::string repr(const boost::python::object &o)
Definition: repr.h:45
Route.h
lanelet::routing::LaneletRelation
getRouteViaWrapper
Optional< std::shared_ptr< lanelet::routing::Route > > getRouteViaWrapper(const lanelet::routing::RoutingGraph &self, const ConstLanelet &from, const ConstLanelets &via, const ConstLanelet &to, lanelet::routing::RoutingCostId costId, bool withLaneChange)
Definition: routing.cpp:23
RoutingCostWrapper::defaultGetCostLaneChange
double defaultGetCostLaneChange(const traffic_rules::TrafficRules &trafficRules, const ConstLanelets &from, const ConstLanelets &to) const
Definition: routing.cpp:98
lanelet::routing::RoutingCostId
uint16_t RoutingCostId
converters::VectorToListConverter
py::to_python_converter< T, VectorToList< T > > VectorToListConverter
Definition: converter.h:219
lanelet::LaneletSubmap
lanelet::routing::RoutingGraph
lanelet::routing::Route
lanelet::python
Definition: repr.h:7
lanelet::ConstLanelet
RoutingCostWrapper
Definition: routing.cpp:70
RoutingGraph.h
RoutingCostWrapper::getCostLaneChange
double getCostLaneChange(const traffic_rules::TrafficRules &trafficRules, const ConstLanelets &from, const ConstLanelets &to) const noexcept override
Definition: routing.cpp:89
RoutingCostBaseWrapper::getCostLaneChange
double getCostLaneChange(const traffic_rules::TrafficRules &trafficRules, const ConstLanelets &from, const ConstLanelets &to) const noexcept override
Definition: routing.cpp:63
RoutingCostBaseWrapper
Definition: routing.cpp:56
makeRoutingGraph
routing::RoutingGraphPtr makeRoutingGraph(LaneletMap &laneletMap, const traffic_rules::TrafficRules &trafficRules, const routing::RoutingCostPtrs &routingCosts)
Definition: routing.cpp:35
ConstLanelets
std::vector< ConstLanelet > ConstLanelets
lanelet::routing::LaneletPath
converters::IterableConverter
Definition: converter.h:53
lanelet::python::makeRepr
std::string makeRepr(const char *name, const Args &... Args_)
Definition: repr.h:37
converters::OptionalConverter
py::to_python_converter< lanelet::Optional< T >, OptionalToObject< T > > OptionalConverter
Definition: converter.h:222


lanelet2_python
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:26:14