Algorithm_SituationAssessment

The situation assessment module represents the first module of cognitive performance along the information flow within the Modular Driver. The task of the module is to assess the current and also the evolving traffic situation. The output signal of the module consists of the description of a situation pattern, e.g. “new lead vehicle”, “new desired speed”, “time-headway wish” or “new speed limit”.

Within this process it enables the possibility to manipulate the reaction process on new surrounding agents with a reaction time.

If the Sensor_Junction is used and there is an oncoming junction, the intersection and the relevant agents are analysed. At first, it is checked, if the junction is traffic light controlled or if there are relevant traffic signs, because this influences the relevance of surrounding agents. Then the surrounding agents are analyzed due to their incoming road, their distance to the junction, their connecting road and its rank and the possible time-to-collision. Therefore it is analyzed, if intersecting connecting roads come from the right and geometrically intersects, where the conflict zone between both routes is and if there is an OpenDRIVE rank parameterized. For the parameterization of a traffic-light controlled junction, an example is shown below. With the interpolation of the agents it is also detected, if there is a relevant time-to-collision (under 3s). It is possible, that agents get spawned on a lane, which isn’t connected with the connecting road along the stochastically sampled route. This happens, because currently there is only checked, if a road is connected with another to calculate the possible roadstream. Therefore a target lane on the current section is calculated, which is transmitted to the lane-change-model for strategic lane changes.

The module can be parameterised with the following parameters through the Static system Configuration with the corresponding Ids.

Parameter

Type

Unit

Id

Description

Defaults to (range)

ReactionTimeMean

Integer

ms

2

Mean reaction time when reacting to a new traffic situation (currently new “leader”, “follower” each on adjacent lanes).

0

ReactionTimeDeviation

Integer

ms

3

Standard deviation of the reaction time

0

VelocityWish

Double

km/h

7

Mean velocity wish on a free road in the simulated scenario (e.g. motorway)

140

VelocityWishDeviation

Double

km/h

8

Standard deviation of the velocity wish

20

TGapWish

Double

s

9

Mean wish time-gap to a leading vehicle

1.5

TGapWishDeviation

Double

s

10

Standard deviation of the wish time-gap

0.3

MeanSpeedLimitViolation

Double

km/h

11

Mean increment on the speed desire when the speed limit is in place

3

MeanSpeedLimitViolationDeviation

Double

km/h

12

Standard deviation of the speed limit violation

0

MinDistance

Double

m

13

Minimum distance to another agent

2

TtcThreshold_mean

Double

s

21

Mean limit below which the agent changes from the comfort deceleration potential to the emergency braking potential.

3

TtcThreshold_std

Double

s

22

Standard deviation of the ttc-threshold

0

Traffic-Light-Controlled Junction

A junction with traffic-signs or traffic-lights should be parameterized a little bit differently. Because of the possible wrong interpretation of the right of way rule after reacting on the stop sign (stop for some seconds then react on relevant agents with the reaction pattern in the module Action_Deduction). If there is a traffic-light-controlled junction no relevant agents are added to the output container, because of the assumption, that if it is green, then the agent can go. If, despite the reaction on the traffic-lights, the relevant agents depending on their intersecting connecting road and the right of way rule where added to the output container, then also agents who wait on a red light would be added to the output. Currently it is not detected, if there is also a relevant traffic light for an agent and if he probably waits on it. Therefore the connecting roads which interact within a light phase need a priority. Then the agent is relevant and added to the output.

For each connecting Road a traffic light has to be added to the sceneryConfiguration.xodr.

<signals>

    <signal name="TrafficLight" id="1" s="0.1" t="0.0000000000000000e+0" zOffset="0.0000000000000000e+0" hOffset="0.0000000000000000e+0" roll="0.0000000000000000e+0" pitch="0.0000000000000000e+0" orientation="+" dynamic="yes" country="OpenDRIVE" type="1.000.011" subtype="20" text="" />

</signals>

Then each intersecting connecting road within one green light-phase need to be added to the end of a “junction” node.

<junction id="1" name="junction1">

   ...
   <priority high="8" low="5" />

   <priority high="7" low="5" />

</junction>

After that the traffic phases can be added manually to the “Scenario.xosc”

<RoadNetwork>
   <LogicFile filepath="SceneryConfiguration.xodr"/>
   <SceneGraphFile filepath=""/>
      <TrafficSignals>
         <TrafficSignalController name="">
            <Phase duration="20" name="Phase1">
               <TrafficSignalState state="green" trafficSignalId="1" />
               <TrafficSignalState state="green" trafficSignalId="14" />
               <TrafficSignalState state="red" trafficSignalId="10" />
               <TrafficSignalState state="red" trafficSignalId="19" />
               <TrafficSignalState state="red" trafficSignalId="1" />
               <TrafficSignalState state="red" trafficSignalId="15" />
            </Phase>
            <Phase duration="3" name="Phase2">
               <TrafficSignalState state="yellow" trafficSignalId="1" />
               <TrafficSignalState state="yellow" trafficSignalId="14" />
               <TrafficSignalState state="red" trafficSignalId="10" />
               <TrafficSignalState state="red" trafficSignalId="19" />
               <TrafficSignalState state="red" trafficSignalId="1" />
               <TrafficSignalState state="red" trafficSignalId="15" />
            </Phase>
            ...
         ...
      ...
   ...
</RoadNetwork>