Mapping and The Road Network

lanelet

We use Lanelets to represent the scenario Road Network. It contains all topological information about the roads and their semantics, including lanes, road markings, traffic signs, traffic lights, crosswalks, intersections, and all relevant details that could affect the traffic. We decided to use Lanelets because of their compact and lightweight structure; the Geoscenario format follows a similar spirit itself. The Road Network is stored in a separate XML file to make replacements easy. However, a scenario can only be interpreted within the context of the Road Network. Thus, a Geoscenario must always be distributed with its associated Road Network file. The Lanelet file is defined inside the Global Config element.

By definition, lanelets are “atomic, interconnected, drivable road segments geometrically represented by their left and right bounds” (Bender, et al. 2014). The bounds are encoded by an array of OSM nodes forming a polyline. Together, they compose the lanelet map. With lanes represented by road-segments with precise boundaries, Lanelets can be used to compose the Road Network of a scenario.

We recommend reading the Lanelet paper and checking the liblanelet2 repository: https://ieeexplore.ieee.org/document/6856487
https://github.com/fzi-forschungszentrum-informatik/Lanelet2

Intersections

If the scenario uses the SDV Model for dynamic driving, the structure of the map and regulatory elements must be compatible with Lanelet 2 format. Otherwise, vehicle won't be able to "understand" the traffic and drive as expected.

AllWayStop

All approaching vehicles have to stop before entering the intersection. The right of way is based is based on the order of arrival. The following roles are used in an all way stop:

  • yield: References the lanelets that might have to yield
  • ref_line: The stop line where yielding vehicles have to stop at. This is either empty or has the same order and size as the number of lanelets.
  • refers: The traffic sign(s) that constitute this rule

Important:

  • All lanelets referenced in this regelem also have to reference this regelem (circular reference). Note how this rule is different from Traffic Lights.
  • The order of lanelets and stop lines must be the same.
  • All lanelets must have the yield role.

Example: A 4-Way Stop intersection

<relation id='-773887'>
    <tag k='type' v='regulatory_element' />
    <tag k='subtype' v='all_way_stop' />
    <!-- Lanelets participating in the 4-way stop -->
    <member type='relation' ref='-773854' role='yield' />
    <member type='relation' ref='-773862' role='yield' />
    <member type='relation' ref='-773860' role='yield' />
    <member type='relation' ref='-773857' role='yield' />
    <!-- Traffic signs (Stop Signs)--> 
    <member type='node' ref='-2650758' role='refers' />
    <member type='node' ref='-2650710' role='refers' />
    <member type='node' ref='-2650711' role='refers' />
    <member type='node' ref='-2650712' role='refers' />
    <!-- stop lines for the lanelets (same order as lanelets) -->
    <member type='way' ref='-1948830' role='ref_line' />
    <member type='way' ref='-1948831' role='ref_line' />
    <member type='way' ref='-1948832' role='ref_line' />
    <member type='way' ref='-1948833' role='ref_line' />
</relation>

file: maps/ll2_firetower_4waystop.osm

Right of Way

Defines what lanes must yield and what lanes have the right of way over intersecting lanelets. The following attributes are used:

  • yield: References the lanelets that have to yield. Only one lanelet of a chain of lanelets that belong to the same lane have to be referenced (generally the last lanelet before the intersection).
  • right_of_way: the lanelets that have the right of way over the yielding ones
  • ref_line: The stop line where yielding vehicles have to stop at. This is either empty or has the same order and size as the number of yielding lanelets.

Important:

  • All yileding lanelets referenced in this regelem also have to reference this regelem (circular reference). Note how this rule is different from Traffic Lights.
  • The order of yielding lanelets and yielding stop lines must be the same.
  • At least one lanelet must have the right of way.

Example 1: A T-shape (one way stop) intersection

In this example, one lanelet is approaching the intersection and has to yield. The other two lanes (south and north) have the right of way.

 <relation id='-5000379'>
    <member type='relation' ref='-5000373' role='right_of_way' />
    <member type='relation' ref='-5000372' role='right_of_way' />
    <member type='relation' ref='-5000359' role='yield' />
    <member type='way' ref='-1949870' role='ref_line' />
    <member type='node' ref='-2763686' role='refers' />
    <tag k='name' v='t_intersection' />
    <tag k='subtype' v='right_of_way' />
    <tag k='type' v='regulatory_element' />
 </relation>

file: maps/ll2_firetower_4waystop.osm

Example 2: A 2-way stop intersection

In this example, two lanes are approaching the intersection and both have to yield (efrom ast and west). The other two lanes (from south and north) have the right of way.

  <relation id='-5000336'>
    <!-- Lanelets with right of way -->
    <member type='relation' ref='-5000327' role='right_of_way' />
    <member type='relation' ref='-5000326' role='right_of_way' />
    <!-- Yielding lanelets -->
    <member type='relation' ref='-5000308' role='yield' />
    <member type='relation' ref='-5000305' role='yield' />
    <!-- Stop lines for the lanelets (same order as yielding lanelets) -->
    <member type='way' ref='-1949787' role='ref_line' />
    <member type='way' ref='-1949790' role='ref_line' />
    <!-- Traffic signs (stop signs) for the lanelets (same order as yielding lanelets) -->
    <member type='node' ref='-2761496' role='refers' />
    <member type='node' ref='-2761450' role='refers' />
    <tag k='name' v='2way_intersection' />
    <tag k='subtype' v='right_of_way' />
    <tag k='type' v='regulatory_element' />
 </relation>

file: maps/ll2_firetower_2waystop.png

Pedestrian Crossing

The pedestrian crosswalk is also an intersection where the vehicles have to yield.

<!-- Pedestrian lanelet -->

<!-- Righ of Way Regulatory Element-->
  <relation id='-5000336'>
    <!-- Pedestrian lanelets with right of way -->
    <member type='relation' ref='-5000327' role='right_of_way' />
    <member type='relation' ref='-5000326' role='right_of_way' />
    <!-- Yielding lanelets -->
    <member type='relation' ref='-5000308' role='yield' />
    <member type='relation' ref='-5000305' role='yield' />
    <!-- Stop lines for the lanelets (same order as yielding lanelets) -->
    <member type='way' ref='-1949787' role='ref_line' />
    <member type='way' ref='-1949790' role='ref_line' />
    <!-- Traffic signs (stop signs) for the lanelets (same order as yielding lanelets) -->
    <member type='node' ref='-2761496' role='refers' />
    <member type='node' ref='-2761450' role='refers' />
    <tag k='name' v='pedestrian_crosssing_intersection' />
    <tag k='subtype' v='right_of_way' />
    <tag k='type' v='regulatory_element' />
 </relation>

<h1> Locations </h1>

Locations are named points (or areas) of the road network that can be used to dynamic place other elements. This is specially useful when a scenario is built with mutation and automatic generation, which requires a base scenario with a certain degree of flexibility (boundaries or alternative points instead of pre-defined locations). Location elements can also be used to provide a more human-readable design, with key points of the road mapped to areas with meaningful names (for example, the approaching zone of an intersection). Locations are designed as an extra layer on top of the road network, and can be shared between scenarios.
For example, location nodes can be placed as a collection of alternative starting points for a given vehicle and a scenario generation approach can search for the optimal point. Alternatively, this starting point can be designed as an area, and the optimization is bounded by this area.

```xml
<node id='-166757'>
    <tag k='gs' v='location' />
    <tag k='name' v='vehiclespawning_1' />
    <tag k='continuous' v='no' />
</node>

Location attributes:

k v description
gs* 'location' GS role key
name* string A name for the location
continuous bool When a location is defined as a polyline (way), this attribute tells if the boundaries should be interpreted as continuous bounded area, or as a collection of discrete alternative points (nodes).