Full GeoScenario examples

In this section we show a few examples exploring the GeoScenario capabilities. More scenarios will be added soon.

Note: For simplicity, we omit globalconfig , origin , and nodes that only compose a path. The full XML for all scenarios is available in our repo.

Scenario 1: Left turn with occlusion

road dynamic agents paths static objects triggers metric
T-intersection 1 vehicle (3 cycles) 1 1 (wall) n/a n/a

Test:In this scenario we test the system capabilities on a T-intersection with a wall impairing visibility from the stop line point of view.

Design: Ego starts approaching the intersection with a stop sign, and must make a left turn to reach its final goal with single egogoal element placed on the north. The static object wall1 is placed on the left of Ego's point of view. Since we have premodeled objects in simulation environment, we added a few more custom attributes to give the wall its exact scale and shape in simulation. Traffic disturbance is added with a vehicle POV approaching the intersection from the left by following the path POV_path towards south. Note how we set 3 cycles for the vehicle to crossing the intersection 3 times (instead of creating 3 different vehicles). No speed profile is added, and the vehicle will follow its target speed=25 (km/h). We expect the wall to block lidar points, and the vehicle will be invisible for Ego until it reaches the intersection. Success condition: reach goal. Fail condition: collision or 1 minute timeout

Scenario designed in JOSM:

scenario1

GeoScenario XML:

<?xml version='1.0' encoding='UTF-8'?>
<osm version='0.6' generator='JOSM'>

  <node id='-774213' action='modify' visible='true' lat='43.43527867173' lon='-80.58002472388'>
    <tag k='gs' v='egostart' />
    <tag k='name' v='egostart' />
    <tag k='orientation' v='0' />
  </node>

  <node id='-774215' action='modify' visible='true' lat='43.43635448188' lon='-80.57977520114'>
    <tag k='name' v='egogoal' />
    <tag k='gs' v='egogoal' />
  </node>

  <node id='-774217' action='modify' visible='true' lat='43.43535567102' lon='-80.57986959643'>
    <tag k='gs' v='staticobject' />
    <tag k='name' v='wall1' />
    <tag k='model' v='wall' />
    <tag k='roll' v='350' external='yes'/>
    <tag k='scalex' v='20' external='yes'/>
    <tag k='scaley' v='1.0' external='yes'/>
    <tag k='scalez' v='8.25' external='yes'/>
    <tag k='shape' v='cube' external='yes'/>
  </node>

  <node id='-774236' action='modify' visible='true' lat='43.43635373633' lon='-80.57982458972'>
    <tag k='gs' v='vehicle' />
    <tag k='name' v='POV' />
    <tag k='cycles' v='3' />
    <tag k='path' v='POV_path' />
    <tag k='orientation' v='90' />
    <tag k='speed' v='25' />
    <tag k='start' v='yes' />
    <tag k='usespeedprofile' v='no' />
  </node>

  <way id='-774248' action='modify' visible='true'>
    <tag k='gs' v='vehiclepath' />
    <tag k='name' v='POV_path' />
    <nd ref='-774246' />
    <nd ref='-774247' />
    <nd ref='-774249' />
    <nd ref='-774251' />
  </way>
</osm>

We run this scenario in simulation (check video). On the left you can see our simulation environment (Unreal 4 custom tools) running the GeoScenario, and on the right RViz view showing how our ADS interpret the world through it's sensors and prediction capabilities. Note how the wall blocks the lidar points as expected, making the approaching vehicle invisible.


Scenario 2: Busy Intersection

road dynamic agents paths static objects triggers metric
T-intersection 3 vehicles 3 n/a 3 n/a

Test: In this scenario we model a right turn on a busy 3-way intersection.

Design: Ego starts on the east, following its lane to reach a single goal g1 in the north after turning right at the intersection. 3 vehicles are placed on the road v_north following north, v_south following south, and v_east starting to follow north before turning right at the intersection. All To make sure Ego will approach the intersection with the right timing, all vehicles will start moving only after Ego gets closer to the stop line. We place 3 triggers t1, t2, and t3 to make activate all vehicles following their respective paths. Ego must wait for a clear road before turning right and continuing the progress towards the goal. Success condition: reach goal. Fail condition: collision or 1 minute timeout.

Scenario designed in JOSM:

scenario1

<?xml version='1.0' encoding='UTF-8'?>
<osm version='0.6' generator='JOSM'>
  <node id='-999217' action='modify' visible='true' lat='43.50057622239' lon='-80.53799493069'>
    <tag k='gs' v='vehicle' />
    <tag k='name' v='v_north' />
    <tag k='orientation' v='230' />
    <tag k='path' v='vpath_north' />
    <tag k='speed' v='20' />
    <tag k='start' v='no' />
  </node>

  <node id='-999255' action='modify' visible='true' lat='43.5004661877' lon='-80.53788295898'>
    <tag k='gs' v='vehicle' />
    <tag k='name' v='v_right' />
    <tag k='orientation' v='230' />
    <tag k='path' v='vpath_north' />
    <tag k='speed' v='20' />
  </node>

  <node id='-999291' action='modify' visible='true' lat='43.50098337052' lon='-80.53879879131'>
    <tag k='gs' v='vehicle' />
    <tag k='name' v='v_south' />
    <tag k='orientation' v='35' />
    <tag k='path' v='vpath_south' />
    <tag k='speed' v='20' />
    <tag k='start' v='false' />
  </node>

  <node id='-999321' action='modify' visible='true' lat='43.50111052197' lon='-80.53758067157'>
    <tag k='gs' v='egostart' />
    <tag k='orientation' v='150' />
  </node>

  <node id='-999319' action='modify' visible='true' lat='43.50097552066' lon='-80.53868280425'>
    <tag k='gs' v='egogoal' />
    <tag k='name' v='g1' />
  </node>


  <node id='-999323' action='modify' visible='true' lat='43.50088239384' lon='-80.53801217805'>
    <tag k='gs' v='trigger' />
    <tag k='name' v='t1' />
    <tag k='activate' v='location' />
    <tag k='radius' v='100' />
    <tag k='owner' v='ego' />
    <tag k='target' v='v_north' />
    <tag k='astart' v='yes' />
  </node>

  <node id='-999325' action='modify' visible='true' lat='43.50085226642' lon='-80.53804399675'>
    <tag k='gs' v='trigger' />
    <tag k='name' v='t2' />
    <tag k='activate' v='location' />
    <tag k='radius' v='100' />
    <tag k='owner' v='ego' />
    <tag k='target' v='v_south' />
    <tag k='astart' v='yes' />
  </node>

  <node id='-999327' action='modify' visible='true' lat='43.50081338947' lon='-80.53808558367'>
    <tag k='gs' v='trigger' />
    <tag k='name' v='t3' />
    <tag k='activate' v='location' />
    <tag k='radius' v='100' />
    <tag k='owner' v='ego' />
    <tag k='target' v='v_right' />
    <tag k='astart' v='yes' />
  </node>

  <way id='-999328' action='modify' visible='true'>
    <nd ref='-999217' />
    <nd ref='-999219' />
    <nd ref='-999221' />
    <nd ref='-999223' />
    <nd ref='-999225' />
    <nd ref='-999227' />
    <nd ref='-999229' />
    <nd ref='-999231' />
    <nd ref='-999233' />
    <nd ref='-999235' />
    <nd ref='-999237' />
    <nd ref='-999239' />
    <nd ref='-999241' />
    <nd ref='-999243' />
    <nd ref='-999245' />
    <nd ref='-999247' />
    <nd ref='-999249' />
    <nd ref='-999251' />
    <nd ref='-999253' />
    <tag k='gs' v='path' />
    <tag k='name' v='vpath_north' />
    <tag k='oneway' v='yes' />
  </way>
  <way id='-999329' action='modify' visible='true'>
    <nd ref='-999255' />
    <nd ref='-999257' />
    <nd ref='-999259' />
    <nd ref='-999261' />
    <nd ref='-999263' />
    <nd ref='-999265' />
    <nd ref='-999267' />
    <nd ref='-999269' />
    <nd ref='-999271' />
    <nd ref='-999273' />
    <nd ref='-999275' />
    <nd ref='-999277' />
    <nd ref='-999279' />
    <nd ref='-999281' />
    <nd ref='-999283' />
    <nd ref='-999285' />
    <nd ref='-999287' />
    <nd ref='-999289' />
    <tag k='gs' v='path' />
    <tag k='name' v='vpath_turnright' />
    <tag k='oneway' v='yes' />
  </way>
  <way id='-999330' action='modify' visible='true'>
    <nd ref='-999291' />
    <nd ref='-999293' />
    <nd ref='-999295' />
    <nd ref='-999297' />
    <nd ref='-999299' />
    <nd ref='-999301' />
    <nd ref='-999303' />
    <nd ref='-999305' />
    <nd ref='-999307' />
    <nd ref='-999309' />
    <nd ref='-999311' />
    <nd ref='-999313' />
    <nd ref='-999315' />
    <nd ref='-999317' />
    <tag k='gs' v='path' />
    <tag k='name' v='vpath_south' />
    <tag k='oneway' v='yes' />
  </way>

</osm>

Scenario 3: Pedestrian crossing

road dynamic agents paths static objects triggers metric
4-way intersection 1 pedestrian 1 n/a 1 n/a

Test: In this scenario we model a pedestrian crossing the road outside of the crosswalk.

Design: Ego starts following its lane to reach a single goal g1 in the south, after turning right at the intersection. A dynamic agent pedestrian1 is placed right after the intersection, not moving, at the beginning of the crossing path pedestrian_path. When Ego reaches the trigger start_pedestrian_trigger, the pedestrian will start moving through the path with speed of 3 km/h.

Ego must react to avoid a collision. If a collision happens, the ADS failed and the scenario must end. Success condition: reach goal. Fail condition: collision or 1 minute timeout.

Scenario designed in JOSM:

scenario1

GeoScenario XML:

<?xml version='1.0' encoding='UTF-8'?>
<osm version='0.6' generator='JOSM'>

  <node id='-999332' action='modify' visible='true' lat='43.43673409293' lon='-80.58035386574'>
    <tag k='gs' v='egostart' />
    <tag k='orientation' v='15' />
  </node>
  <node id='-999334' action='modify' visible='true' lat='43.43623797361' lon='-80.57980236124'>
    <tag k='gs' v='egogoal' />
    <tag k='name' v='g1' />
  </node>

  <node id='-999336' action='modify' visible='true' lat='43.43642432523' lon='-80.579876535'>
    <tag k='gs' v='pedestrian' />
    <tag k='name' v='pedestrian1' />
    <tag k='orientation' v='0' />
    <tag k='path' v='pedestrian_path' />
    <tag k='speed' v='0' />
    <tag k='usespeedprofile' v='no' />
  </node>

  <way id='-999351' action='modify' visible='true'>
    <tag k='gs' v='path' />
    <tag k='name' v='pedestrian_path' />
    <nd ref='-999336' />
    <nd ref='-999338' />
    <nd ref='-999767' />
    <nd ref='-999705' />
    <nd ref='-999344' />
  </way>

  <node id='-999348' action='modify' visible='true' lat='43.43658337539' lon='-80.57990628814'>
    <tag k='gs' v='trigger' />
    <tag k='name' v='start_pedestrian_trigger' />
    <tag k='activate' v='location' />
    <tag k='radius' v='100' />
    <tag k='owner' v='ego' />
    <tag k='target' v='pedestrian1' />
    <tag k='aspeed' v='3' />
    <tag k='astart' v='yes' />
  </node>


</osm>

Scenario 4: Leading Vehicle Decelerates to Complete Stop

road dynamic agents paths static objects triggers metric
straight single lane 1 vehicle 2 - 1 -

Test: In this scenario we model the most frequent crash scenario according to NHTSA (lead vehicle stopped) to test how the ADS reacts to avoid an imminent collision.

Design: Ego starts following its lane to reach a single goal g1 at the east end of a straight road. A dynamic agent leading_vehicle is placed in front of Ego with a target speed=30 following the same road using east_path. When the leading vehicle reaches the trigger t1, it switches to a new path decelerate_path. This path contains a speed profile, decelerating from 30km/h to a complete stop in a short space. Triggers with different conditions can be used to explore this scenario with different ranges, and different speed profiles (e.g., an aggressive deceleration profile increasing the level of difficulty). Ego is the trailing vehicle and must react to avoid a collision. If a collision happens, the ADS failed and the scenario must end. Success condition: reach goal. Fail condition: collision or 1 minute timeout.

Scenario designed in JOSM:

scenario1

GeoScenario XML:

<?xml version='1.0' encoding='UTF-8'?>
<osm version='0.6' generator='JOSM'>

  <node id='-790360' action='modify' visible='true' lat='43.5092977414' lon='-80.5353541531'>
    <tag k='gs' v='egostart' />
  </node>

  <node id='-790362' action='modify' visible='true' lat='43.50929111872' lon='-80.53337569124'>
    <tag k='gs' v='egogoal' />
    <tag k='name' v='g1' />
  </node>

  <node id='-790278' action='modify' visible='true' lat='43.50929579893' lon='-80.53489049916'>
    <tag k='cycles' v='1' />
    <tag k='gs' v='vehicle' />
    <tag k='name' v='leading_vehicle' />
    <tag k='orientation' v='0' />
    <tag k='path' v='east_path' />
    <tag k='speed' v='30' />
    <tag k='start' v='yes' />
  </node>

  <node id='-790292' action='modify' visible='true' lat='43.50929492556' lon='-80.53403802218'>
    <tag k='gs' v='trigger' />
    <tag k='name' v='trigger1' />
    <tag k='type' v='location' />
    <tag k='target' v='leading_vehicle' />
    <tag k='apath' v='stop_path' />
    <tag k='aspeedprofile' v='yes' />
  </node>

  <way id='-790368' action='modify' visible='true'>
      <nd ref='-790280' />
      <nd ref='-790282' />
      <nd ref='-790284' />
      <nd ref='-790286' />
      <nd ref='-790288' />
      <nd ref='-790290' />
      <nd ref='-790294' />
      <nd ref='-790296' />
      <nd ref='-790298' />
      <nd ref='-790300' />
      <tag k='abstract' v='no' />
      <tag k='gs' v='path' />
      <tag k='name' v='east_path' />
    </way>

    <node id='-790260' action='modify' visible='true' lat='43.50929904003' lon='-80.53401271512'>
      <tag k='nodespeed' v='30' />
    </node>
    <node id='-790262' action='modify' visible='true' lat='43.50929832706' lon='-80.53394488431'>
      <tag k='nodespeed' v='26' />
    </node>
    <node id='-790264' action='modify' visible='true' lat='43.50929761408' lon='-80.533868206'>
      <tag k='nodespeed' v='22' />
    </node>
    <node id='-790266' action='modify' visible='true' lat='43.50929761408' lon='-80.53379840908' >
      <tag k='nodespeed' v='18' />
    </node>
    <node id='-790268' action='modify' visible='true' lat='43.50929690111' lon='-80.53372369688'>
        <tag k='nodespeed' v='14' />
    </node>
    <node id='-790270' action='modify' visible='true' lat='43.50929618814' lon='-80.53364308635'>
      <tag k='nodespeed' v='10' />
    </node>
    <node id='-790272' action='modify' visible='true' lat='43.50929547516' lon='-80.53356050971' >
        <tag k='nodespeed' v='05' />
    </node>
    <node id='-790274' action='modify' visible='true' lat='43.50929476219' lon='-80.53347203473'>
      <tag k='nodespeed' v='0' />
    </node>
    <way id='-790367' action='modify' visible='true'>
      <nd ref='-790260' />
      <nd ref='-790262' />
      <nd ref='-790264' />
      <nd ref='-790266' />
      <nd ref='-790268' />
      <nd ref='-790270' />
      <nd ref='-790272' />
      <nd ref='-790274' />
      <tag k='abstract' v='yes' />
      <tag k='gs' v='path' />
      <tag k='name' v='stop_path' />
    </way>  

</osm>