![]() |
Classes | |
class | lanelet::ConstLanelet |
An immutable lanelet. More... | |
class | lanelet::Lanelet |
The famous (mutable) lanelet class. More... | |
Lanelets represent an atomic section of a lane.
A lanelet consists of two bounds, attributes and regulatory elements. The orientation of the bounds is important and must be consistent as it indicates the driving direction. The attributes can define simple constaints for a lanelet and regulatory elements impose traffic regulations (right of way, speed limits).
You can get the centerline of a Lanelet. This computation is a bit costly but this is necessary to guarantee that the centerline never violates the bounds of its polygon. To speed up subsequend calls, the result is cached. However, if points are modified, the Lanelet does not get notified and the cached centerline will be wrong. To solve that, manually reset the cache of the affected lanelets when changing point coordinates.
You can override the centerline by setting your own. If you do that, you take resposability of the validity of the centerline. If the bounds of lanelet with such a centerline is updated, the centerline will stay unchanged.
Lanelets can directly be used in some geometry calculations. see lanelet::geometry. If this does not satisfy your needs, you can try the Lanelet::polygon2d or Lanelet::polygon3d instead.
Regulatory Elements represent traffic rules that affect a lanelet. Instead of trying to interpret the traffic rules by hand, use the lanelet2_traffic_rules package. It is designed to yield senseful results for all commmon traffic rules. If they do not fit your needs, you can extend them easily.
A lanelet implicitly stands for a certain driving direction. To get the opposite direction, Lanelets can be inverted in O(0). An inverted Lanelet shares its data with all normal lanelets, it just returns its bounds with left and right flipped.