blob: f4b9082fccfc5939562114d1dcc667c1c01db6e4 [file] [log] [blame]
<!DOCTYPE html>
<html class="writer-html5" lang="en" >
<head>
<meta charset="utf-8" />
<meta name="viewport" content="width=device-width, initial-scale=1.0" />
<title>Agent Components &mdash; OpenPASS Documentation</title>
<link rel="stylesheet" href="../../_static/css/theme.css" type="text/css" />
<link rel="stylesheet" href="../../_static/pygments.css" type="text/css" />
<link rel="stylesheet" href="../../_static/tabs.css" type="text/css" />
<link rel="stylesheet" href="../../_static/css/custom.css" type="text/css" />
<link rel="shortcut icon" href="../../_static/openPASS.ico"/>
<!--[if lt IE 9]>
<script src="../../_static/js/html5shiv.min.js"></script>
<![endif]-->
<script type="text/javascript" id="documentation_options" data-url_root="../../" src="../../_static/documentation_options.js"></script>
<script src="../../_static/jquery.js"></script>
<script src="../../_static/underscore.js"></script>
<script src="../../_static/doctools.js"></script>
<script type="text/javascript" src="../../_static/js/theme.js"></script>
<link rel="index" title="Index" href="../../genindex.html" />
<link rel="search" title="Search" href="../../search.html" />
<link rel="next" title="EventDetector" href="event_detector.html" />
<link rel="prev" title="Simulator" href="../20_simulator_advanced.html" />
</head>
<body class="wy-body-for-nav">
<div class="wy-grid-for-nav">
<nav data-toggle="wy-nav-shift" class="wy-nav-side">
<div class="wy-side-scroll">
<div class="wy-side-nav-search" >
<a href="../../index.html" class="icon icon-home"> openPASS
<img src="../../_static/openPASS.png" class="logo" alt="Logo"/>
</a>
<div class="version">
0.8.0
</div>
<div role="search">
<form id="rtd-search-form" class="wy-form" action="../../search.html" method="get">
<input type="text" name="q" placeholder="Search docs" />
<input type="hidden" name="check_keywords" value="yes" />
<input type="hidden" name="area" value="default" />
</form>
</div>
</div>
<div class="wy-menu wy-menu-vertical" data-spy="affix" role="navigation" aria-label="main navigation">
<p class="caption"><span class="caption-text">Installation Guide</span></p>
<ul>
<li class="toctree-l1"><a class="reference internal" href="../../installation_guide/10_getting_started.html">Getting Started</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../installation_guide/20_install_prerequisites.html">Installing Prerequisites</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../installation_guide/30_install_openpass.html">Installing OpenPASS</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../installation_guide/50_further_guidance.html">Further Guidance</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../installation_guide/60_conan.html">Building with Conan</a></li>
</ul>
<p class="caption"><span class="caption-text">User Guides</span></p>
<ul>
<li class="toctree-l1"><a class="reference internal" href="../../user_guide/10_overview.html">Overview</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../user_guide/20_tutorials.html">Tutorials</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../user_guide/30_gui_plugins.html">GUI Plugins</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../user_guide/40_configs_in_depth.html">Configs in Depth</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../user_guide/50_outputs_in_depth.html">Outputs in Depth</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../user_guide/60_scenario_simulation.html">Simulator</a></li>
</ul>
<p class="caption"><span class="caption-text">Advanced topics</span></p>
<ul class="current">
<li class="toctree-l1 current"><a class="reference internal" href="../20_simulator_advanced.html">Simulator</a><ul class="current">
<li class="toctree-l2 current"><a class="current reference internal" href="#">Agent Components</a><ul>
<li class="toctree-l3"><a class="reference internal" href="#action-longitudinaldriver">Action_LongitudinalDriver</a></li>
<li class="toctree-l3"><a class="reference internal" href="#action-secondarydriver">Action_SecondaryDriver</a></li>
<li class="toctree-l3"><a class="reference internal" href="#agentupdater">AgentUpdater</a></li>
<li class="toctree-l3"><a class="reference internal" href="#algorithm-lateral">Algorithm_Lateral</a></li>
<li class="toctree-l3"><a class="reference internal" href="#algorithm-longitudinal">Algorithm_Longitudinal</a></li>
<li class="toctree-l3"><a class="reference internal" href="#dynamics-collision">Dynamics_Collision</a></li>
<li class="toctree-l3"><a class="reference internal" href="#dynamics-regulardriving">Dynamics_RegularDriving</a></li>
<li class="toctree-l3"><a class="reference internal" href="#limiteraccelerationvehiclecomponents">LimiterAccelerationVehicleComponents</a></li>
<li class="toctree-l3"><a class="reference internal" href="#openscenarioactions">OpenScenarioActions</a></li>
<li class="toctree-l3"><a class="reference internal" href="#parameters-vehicle">Parameters_Vehicle</a></li>
<li class="toctree-l3"><a class="reference internal" href="#sensor-driver">Sensor_Driver</a></li>
<li class="toctree-l3"><a class="reference internal" href="#sensor-osi">Sensor_OSI</a><ul>
<li class="toctree-l4"><a class="reference internal" href="#function">Function</a></li>
<li class="toctree-l4"><a class="reference internal" href="#cases">Cases</a></li>
<li class="toctree-l4"><a class="reference internal" href="#visual-obstruction">Visual Obstruction</a></li>
</ul>
</li>
<li class="toctree-l3"><a class="reference internal" href="#sensorfusionosi">SensorFusionOSI</a></li>
<li class="toctree-l3"><a class="reference internal" href="#signalprioritizer">SignalPrioritizer</a></li>
<li class="toctree-l3"><a class="reference internal" href="#componentcontroller">ComponentController</a><ul>
<li class="toctree-l4"><a class="reference internal" href="#overview">Overview</a></li>
<li class="toctree-l4"><a class="reference internal" href="#state-handling-inside-vehicle-component">State handling inside Vehicle Component</a></li>
<li class="toctree-l4"><a class="reference internal" href="#used-signals">Used signals</a></li>
</ul>
</li>
</ul>
</li>
<li class="toctree-l2"><a class="reference internal" href="event_detector.html">EventDetector</a></li>
<li class="toctree-l2"><a class="reference internal" href="simulation.html">Simulation</a></li>
<li class="toctree-l2"><a class="reference internal" href="world_osi.html">World_OSI</a></li>
</ul>
</li>
<li class="toctree-l1"><a class="reference internal" href="../30_testing.html">EndToEnd Test Framework</a></li>
</ul>
<p class="caption"><span class="caption-text">Developer Information</span></p>
<ul>
<li class="toctree-l1"><a class="reference internal" href="../../developer_information/10_ide_support.html">IDE Support</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../developer_information/20_documentation.html">Documentation Concept</a></li>
</ul>
<p class="caption"><span class="caption-text">Other Information</span></p>
<ul>
<li class="toctree-l1"><a class="reference internal" href="../../other_information/10_external_dependencies.html">External Dependencies</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../other_information/20_glossary.html">Glossary</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../other_information/30_license.html">License</a></li>
</ul>
</div>
</div>
</nav>
<section data-toggle="wy-nav-shift" class="wy-nav-content-wrap">
<nav class="wy-nav-top" aria-label="top navigation">
<i data-toggle="wy-nav-top" class="fa fa-bars"></i>
<a href="../../index.html">openPASS</a>
</nav>
<div class="wy-nav-content">
<div class="rst-content">
<div role="navigation" aria-label="breadcrumbs navigation">
<ul class="wy-breadcrumbs">
<li><a href="../../index.html" class="icon icon-home"></a> &raquo;</li>
<li><a href="../20_simulator_advanced.html">Simulator</a> &raquo;</li>
<li>Agent Components</li>
<li class="wy-breadcrumbs-aside">
<a href="../../_sources/advanced_topics/simulator/agent_components.rst.txt" rel="nofollow"> View page source</a>
</li>
</ul>
<hr/>
</div>
<div role="main" class="document" itemscope="itemscope" itemtype="http://schema.org/Article">
<div itemprop="articleBody">
<div class="section" id="agent-components">
<span id="agentcomponents"></span><h1>Agent Components<a class="headerlink" href="#agent-components" title="Permalink to this headline"></a></h1>
<p>An agent in openPASS is composed of multiple modules, which are connected by corresponding signals.
As shown in the next figure, the modules can be roughly divided into the groups drivers, vehicle components, algorithms, dynamic modules, and prioritizers.
Thereby, modules can consist of several submodules, such as sensor (reading from an interface) and action (writing to an interface).</p>
<div class="figure align-default" id="id1">
<img alt="../../_images/DynamicsModules.png" src="../../_images/DynamicsModules.png" />
<p class="caption"><span class="caption-text">Modules for longitudinal and lateral dynamics</span><a class="headerlink" href="#id1" title="Permalink to this image"></a></p>
</div>
<p>By statistic means, based on corresponding probabilities defined in the <a class="reference internal" href="../../user_guide/configs/profilescatalog.html#profilescatalog"><span class="std std-ref">ProfilesCatalog</span></a>, each individual agent is composed from a superset of all possible (valid) combinations, which is defined by the <a class="reference internal" href="../../user_guide/configs/systemconfigblueprint.html#systemconfigblueprint"><span class="std std-ref">SystemConfigBlueprint</span></a>.
This config defines all available framework modules and agent modules and connects them by corresponding channels, which in turn have a specific signal type.</p>
<p>The next figure gives an exhaustive overview over the current superset:</p>
<div class="figure align-default" id="id2">
<span id="component-channel-communication"></span><img alt="../../_images/ComponentsChannelCommunicationDiagram.svg" src="../../_images/ComponentsChannelCommunicationDiagram.svg" /><p class="caption"><span class="caption-text">Components and channel communication</span><a class="headerlink" href="#id2" title="Permalink to this image"></a></p>
</div>
<p><a class="reference download internal" download="" href="../../_downloads/9aabdb34246c59e548d181762c2e97b2/ComponentsChannelCommunicationDiagram.svg"><code class="xref download docutils literal notranslate"><span class="pre">./images/ComponentsChannelCommunicationDiagram.svg</span></code></a></p>
<p>Modules that can be parametrized by the user are explained in the <a class="reference internal" href="../../user_guide/sim_user_guide/20_components.html#simuserguide-components"><span class="std std-ref">Simulation User Guide</span></a>.
Therefor the following section only contains the components not listed in the user guide.</p>
<div class="section" id="action-longitudinaldriver">
<h2>Action_LongitudinalDriver<a class="headerlink" href="#action-longitudinaldriver" title="Permalink to this headline"></a></h2>
<p>Updates the agents pedal positions and gear.
The input for this module is prepared by the AlgorithmLongitudinal Module.</p>
</div>
<div class="section" id="action-secondarydriver">
<h2>Action_SecondaryDriver<a class="headerlink" href="#action-secondarydriver" title="Permalink to this headline"></a></h2>
<p>Updates the agents braking light, indicator, horn and all light switches (headlight, high beam, flasher).
The input for this module is prepared by the driver module.</p>
</div>
<div class="section" id="agentupdater">
<h2>AgentUpdater<a class="headerlink" href="#agentupdater" title="Permalink to this headline"></a></h2>
<p>The AgentUpdater executes all Set-Methods of the agent dynamics after the DynamicsPrioritizer. This includes position, velocity, acceleration and rotation.</p>
</div>
<div class="section" id="algorithm-lateral">
<h2>Algorithm_Lateral<a class="headerlink" href="#algorithm-lateral" title="Permalink to this headline"></a></h2>
<p>This module converts the lateral input of the driver module into a steering wheel angle.</p>
</div>
<div class="section" id="algorithm-longitudinal">
<h2>Algorithm_Longitudinal<a class="headerlink" href="#algorithm-longitudinal" title="Permalink to this headline"></a></h2>
<p>This module converts the acceleration input of the driver module into pedal positions and gear.</p>
</div>
<div class="section" id="dynamics-collision">
<h2>Dynamics_Collision<a class="headerlink" href="#dynamics-collision" title="Permalink to this headline"></a></h2>
<p>If the number of collision partners of the agent is bigger than in the previous time step, the DynamicsCollision module calculates the collision.
Currently the collision is implemented fully inelastic, i.e. all agents will have the same velocity after the collision, while the momentum is conserved.
After the collision the agents slow down with a fixed deceleration until fully stopped.</p>
</div>
<div class="section" id="dynamics-regulardriving">
<h2>Dynamics_RegularDriving<a class="headerlink" href="#dynamics-regulardriving" title="Permalink to this headline"></a></h2>
<p>The module takes care that the motion of the agent fit to the physical limitations, such as friction or maximum possible acceleration based on the current gear.
This module uses both the world friction and the vehicle model parameter friction.
Thereby it calculates the dynamics of the agents in every time step.
The currently covered dynamics are <em>Acceleration</em>, <em>Velocity</em>, and consequently <em>Position</em>, <em>Yaw angle</em> and <em>Yaw rate</em>.
The input for this module is the steering wheel angle and the new acceleration of the vehicle.</p>
</div>
<div class="section" id="limiteraccelerationvehiclecomponents">
<h2>LimiterAccelerationVehicleComponents<a class="headerlink" href="#limiteraccelerationvehiclecomponents" title="Permalink to this headline"></a></h2>
<p>This module limits the AccelerationSignal from the PrioritizerAccelerationVehicleComponents to the constraints given by the vehicle. The DynamicsTrajectoryFollower can then use this signal to calculate a trajectory.</p>
<p>The limit is calculated by <span class="math">a_{\text{lim}} = \frac {F_{\text{wheel}} - F_{\text{roll}} - F_{\text{air}}} {m_{\text{veh}}}</span>, where the symbols meanings are:</p>
<table class="docutils align-default">
<colgroup>
<col style="width: 33%" />
<col style="width: 67%" />
</colgroup>
<thead>
<tr class="row-odd"><th class="head"><p>Symbol</p></th>
<th class="head"><p>Description</p></th>
</tr>
</thead>
<tbody>
<tr class="row-even"><td><p><span class="math">a_{\text{lim}}</span></p></td>
<td><p>Resulting acceleration limit [m/s²]</p></td>
</tr>
<tr class="row-odd"><td><p><span class="math">F_{\text{wheel}}</span></p></td>
<td><p>Force at wheel (provided by drivetrain) [N]</p></td>
</tr>
<tr class="row-even"><td><p><span class="math">F_{\text{roll}}</span></p></td>
<td><p>Force resulting from rolling resistance [N]</p></td>
</tr>
<tr class="row-odd"><td><p><span class="math">F_{\text{air}}</span></p></td>
<td><p>Force resulting from air drag [N]</p></td>
</tr>
<tr class="row-even"><td><p><span class="math">m_{\text{veh}}</span></p></td>
<td><p>Mass of the vehicle [kg]</p></td>
</tr>
</tbody>
</table>
<p>The components are calculated as follows:</p>
<p><strong>Driving force</strong></p>
<p><span class="math">F_{\text{wheel}} = \frac {T_{\text{engine}} \cdot r_{\text{axle}}} {r_{\text{wheel}}}</span></p>
<table class="docutils align-default">
<colgroup>
<col style="width: 21%" />
<col style="width: 79%" />
</colgroup>
<thead>
<tr class="row-odd"><th class="head"><p>Symbol</p></th>
<th class="head"><p>Description</p></th>
</tr>
</thead>
<tbody>
<tr class="row-even"><td><p><span class="math">T_{\text{engine}}</span></p></td>
<td><p>Resulting torque from drivetrain at current velocity (assuming best gearing selected) [Nm]</p></td>
</tr>
<tr class="row-odd"><td><p><span class="math">r_{\text{axle}}</span></p></td>
<td><p>Axle transmission ratio [1]</p></td>
</tr>
<tr class="row-even"><td><p><span class="math">r_{\text{wheel}}</span></p></td>
<td><p>Static radius of the wheels [m]</p></td>
</tr>
</tbody>
</table>
<p>The engine torque <span class="math">T_{\text{engine}}</span> is calculated by a simple model, where the torque scales proportional with the current engine speed between 1350 and 5000 rpm, up to maximum engine torque.
From minimum engine speed up to 1350 rpm the torque scales proportional with the engine speed up to half the maximum torque.
From 5000 rpm up to maximum engine speed, the torque scales with 5000 / maxEngineSpeed, up to maximum torque.</p>
<p><strong>Rolling resistance</strong></p>
<p><span class="math">F_{\text{roll}} = m_{\text{veh}} \cdot c_{\text{fric}} \cdot g</span></p>
<table class="docutils align-default">
<colgroup>
<col style="width: 21%" />
<col style="width: 79%" />
</colgroup>
<thead>
<tr class="row-odd"><th class="head"><p>Symbol</p></th>
<th class="head"><p>Description</p></th>
</tr>
</thead>
<tbody>
<tr class="row-even"><td><p><span class="math">m_{\text{veh}}</span></p></td>
<td><p>Mass of the vehicle [kg]</p></td>
</tr>
<tr class="row-odd"><td><p><span class="math">c_{\text{fric}}</span></p></td>
<td><p>Rolling friction coefficient (constant 0.015) [1]</p></td>
</tr>
</tbody>
</table>
<p><strong>Air drag</strong></p>
<p><span class="math">F_{\text{air}} = \frac {\rho_{\text{air}}} {2} \cdot A_{\text{front}} \cdot c_w \cdot v^2</span></p>
<table class="docutils align-default">
<colgroup>
<col style="width: 21%" />
<col style="width: 79%" />
</colgroup>
<thead>
<tr class="row-odd"><th class="head"><p>Symbol</p></th>
<th class="head"><p>Description</p></th>
</tr>
</thead>
<tbody>
<tr class="row-even"><td><p><span class="math">\rho_{\text{air}}</span></p></td>
<td><p>Density of air [kg/m³]</p></td>
</tr>
<tr class="row-odd"><td><p><span class="math">A_{\text{front}}</span></p></td>
<td><p>Vehicle front surface area [m²]</p></td>
</tr>
<tr class="row-even"><td><p><span class="math">c_w</span></p></td>
<td><p>Drag coefficient [1]</p></td>
</tr>
<tr class="row-odd"><td><p><span class="math">v</span></p></td>
<td><p>Vehicle’s current velocity [m/s]</p></td>
</tr>
</tbody>
</table>
</div>
<div class="section" id="openscenarioactions">
<h2>OpenScenarioActions<a class="headerlink" href="#openscenarioactions" title="Permalink to this headline"></a></h2>
<p>As defined by openSCENARIO, OpenScenarioActions is the relaying module for:</p>
<ul class="simple">
<li><p>Trajectory-actions</p></li>
<li><p>LaneChange-actions</p></li>
<li><p>UserDefined-actions.</p></li>
</ul>
<p>If a</p>
<ul class="simple">
<li><p>TrajectoryManipulator</p></li>
<li><p>LaneChangeManipulator</p></li>
</ul>
<p>or a user defined manipulator</p>
<p>raises such an event for the specified agent, the module forwards it as signal to all interested module of the corresponding agent. The modules can than react on the signals content without time delay.</p>
</div>
<div class="section" id="parameters-vehicle">
<h2>Parameters_Vehicle<a class="headerlink" href="#parameters-vehicle" title="Permalink to this headline"></a></h2>
<p>The ParametersVehicle module forwards the VehicleModelParameters to all other modules that need them via the ParametersVehicleSignal</p>
</div>
<div class="section" id="sensor-driver">
<h2>Sensor_Driver<a class="headerlink" href="#sensor-driver" title="Permalink to this headline"></a></h2>
<p>The SensorDriver performs queries on the AgentInterface to gather information about the own agent and its surroundings. These are forwarded to the driver modules and the Algorithm modules, which use them for their calculations.</p>
</div>
<div class="section" id="sensor-osi">
<h2>Sensor_OSI<a class="headerlink" href="#sensor-osi" title="Permalink to this headline"></a></h2>
<p>This module is a representation of various sensors and uses OSI for its input and output.
Currently it only has one type of sensor (SensorGeometric2D) which detects all objects in sector with specified range and opening angle.
The input of the sensor is a OSI SensorView generated by the OSI World and its output is a OSI SensorData structure.</p>
<p>For generation of the SensorView, a SensorViewConfiguration has to be provided by the sensor to the OSI World. See image for a visualization of the
dataflow.</p>
<div class="figure align-default" id="id3">
<img alt="../../_images/SensorView_Dataflow.svg" src="../../_images/SensorView_Dataflow.svg" /><p class="caption"><span class="caption-text">OSI SensorView dataflow</span><a class="headerlink" href="#id3" title="Permalink to this image"></a></p>
</div>
<p>From OSI development perspective, the OSI World would have to send back a SensorViewConfiguration to the sensor, with the contents describing the
actual configuration of the SensorView (since the World is maybe notable to provide the requested information).
As we have full control over the simulation environment, this back-channel is skipped and SensorView according to the sensor’S SensorView configuration
will always be provided.</p>
<p>To test whether an object is inside our sector we check
1. if it is inside the circle around the sensor with radius the detection range and
2. if it intersects a suitable polygon</p>
<p>Depending on the opening-angle the polygon in 2) has either four (angle &lt; 180°) or five corners (angle &gt;= 180°).</p>
<div class="figure align-default" id="id4">
<img alt="../../_images/Sensor2D_kite_polygon.png" src="../../_images/Sensor2D_kite_polygon.png" />
<p class="caption"><span class="caption-text">four-corner kite polygon for angle lower than 180°</span><a class="headerlink" href="#id4" title="Permalink to this image"></a></p>
</div>
<table class="docutils align-default">
<colgroup>
<col style="width: 14%" />
<col style="width: 33%" />
<col style="width: 35%" />
<col style="width: 18%" />
</colgroup>
<thead>
<tr class="row-odd"><th class="head"><p>Object</p></th>
<th class="head"><p>intersects circle</p></th>
<th class="head"><p>intersects polygon</p></th>
<th class="head"><p>detected</p></th>
</tr>
</thead>
<tbody>
<tr class="row-even"><td><p>A</p></td>
<td><p>true</p></td>
<td><p>false</p></td>
<td><p>false</p></td>
</tr>
<tr class="row-odd"><td><p>B</p></td>
<td><p>true</p></td>
<td><p>true</p></td>
<td><p>true</p></td>
</tr>
<tr class="row-even"><td><p>C</p></td>
<td><p>false</p></td>
<td><p>true</p></td>
<td><p>false</p></td>
</tr>
<tr class="row-odd"><td><p>D</p></td>
<td><p>false</p></td>
<td><p>false</p></td>
<td><p>false</p></td>
</tr>
<tr class="row-even"><td><p>E</p></td>
<td><p>true</p></td>
<td><p>true</p></td>
<td><p>true</p></td>
</tr>
</tbody>
</table>
<div class="figure align-default" id="id5">
<img alt="../../_images/Sensor2D_five_corner_polygon.png" src="../../_images/Sensor2D_five_corner_polygon.png" />
<p class="caption"><span class="caption-text">five-corner polygon for angle greater or equal 180° and greater 360°</span><a class="headerlink" href="#id5" title="Permalink to this image"></a></p>
</div>
<table class="docutils align-default">
<colgroup>
<col style="width: 14%" />
<col style="width: 33%" />
<col style="width: 35%" />
<col style="width: 18%" />
</colgroup>
<thead>
<tr class="row-odd"><th class="head"><p>Object</p></th>
<th class="head"><p>intersects circle</p></th>
<th class="head"><p>intersects polygon</p></th>
<th class="head"><p>detected</p></th>
</tr>
</thead>
<tbody>
<tr class="row-even"><td><p>A</p></td>
<td><p>false</p></td>
<td><p>true</p></td>
<td><p>false</p></td>
</tr>
<tr class="row-odd"><td><p>B</p></td>
<td><p>true</p></td>
<td><p>true</p></td>
<td><p>true</p></td>
</tr>
<tr class="row-even"><td><p>C</p></td>
<td><p>true</p></td>
<td><p>true</p></td>
<td><p>true</p></td>
</tr>
<tr class="row-odd"><td><p>D</p></td>
<td><p>true</p></td>
<td><p>false</p></td>
<td><p>false</p></td>
</tr>
<tr class="row-even"><td><p>E</p></td>
<td><p>false</p></td>
<td><p>false</p></td>
<td><p>false</p></td>
</tr>
</tbody>
</table>
<p>For convex BBoxes the above will give correct detection results.</p>
<p>Both polygons are constructed from corner-points consisting out of the intersection between the opening-angle boundaries at maximum detection range and their corresponding tangents.</p>
<div class="section" id="function">
<h3>Function<a class="headerlink" href="#function" title="Permalink to this headline"></a></h3>
<ol class="arabic simple">
<li><p>Construct the polygon based on the opening-angle</p></li>
<li><p>Check if detection-field (polygon) intersects with any BBox (object-detection)</p></li>
<li><p>Calculate the distance between sensor and object</p></li>
<li><p>if (dist &lt;= range &amp;&amp; isIntersecting) -&gt; object is in circular sector (object validation)</p></li>
</ol>
</div>
<div class="section" id="cases">
<h3>Cases<a class="headerlink" href="#cases" title="Permalink to this headline"></a></h3>
<ul class="simple">
<li><p>For angles &lt; 1.0 * pi a four-corner (kite) polygon can be constructed out of two radiuses and two tangents.</p></li>
<li><p>For angles &gt; = 1.0 * pi and &lt; 2.0 * pi a five-corner polygon can be constructed of two radiuses an three tangents.</p></li>
<li><p>For opening-angle of exactly 2.0 * pi the distance information suffices. No polygon is needed.</p></li>
</ul>
</div>
<div class="section" id="visual-obstruction">
<h3>Visual Obstruction<a class="headerlink" href="#visual-obstruction" title="Permalink to this headline"></a></h3>
<p>Objects in front of others block the sensors line of sight. If an object is large enough it might visually obstruct others.
To check if one or multiple objects in combination “shadow” other objects the EnableVisualObstruction - flag can be set.
Also the minimum required percentage of the visible area of an object to be detected can be specified.
The implemented algorithm uses the concept of shadow-casting.</p>
<p><strong>Basic</strong></p>
<div class="figure align-default" id="id6">
<img alt="../../_images/ShadowCasting.svg" src="../../_images/ShadowCasting.svg" /><p class="caption"><span class="caption-text">Example of shadow-casting</span><a class="headerlink" href="#id6" title="Permalink to this image"></a></p>
</div>
<p>The sensor can be pictured as a light source.
Every object in the detection field of the sensor will therefore cast a shadow and reduce the overall detection area behind it.
If an object is shadowed too much, it is removed from the list of detected objects.
After all shadows are removed, only the “real” detection field polygon (yellow area) remains.
Objects in green and blue are detected.
The red object is completely covered by shadows and therefore not detected.</p>
<p><strong>Step by Step</strong></p>
<p>Shadow casting is calculated as follows (see figure below):
1. Approximate detection field as circular sector (bright area).
2. Calculate the casted shadow of each object inside the detection field.
3. Remove the casted shadow from the detection field.
4. Check for each object if the remaining area is inside the remaining polygon.
5. Removed objects if the relation <cite>covered object area/total object area</cite> is smaller than a parameterizable threshold.</p>
<p><strong>Details</strong></p>
<p>The approximation of the detection range is deliberately calculated along its edge and not by means of a tangential approximation.
The areal error along the edge is regarded as negligible w.r.t to the sizes of objects and commonly used detection ranges.</p>
<div class="figure align-default" id="id7">
<img alt="../../_images/shadowing1.png" src="../../_images/shadowing1.png" />
<p class="caption"><span class="caption-text">Shadow casting detail 1</span><a class="headerlink" href="#id7" title="Permalink to this image"></a></p>
</div>
<p>For the calculation of the shadowing polygon, the confining vectors for the object of interest are calculated (see detail 1).</p>
<div class="figure align-default" id="id8">
<img alt="../../_images/shadowing2.png" src="../../_images/shadowing2.png" />
<p class="caption"><span class="caption-text">Shadow casting detail 2</span><a class="headerlink" href="#id8" title="Permalink to this image"></a></p>
</div>
<p>Scaling the length of the vectors w.r.t. the detection range would only to reach the boundary and not suffice, as the resulting polygon is too small (red area in detail 2 not covered).</p>
<div class="figure align-default" id="id9">
<img alt="../../_images/shadowing3.png" src="../../_images/shadowing3.png" />
<p class="caption"><span class="caption-text">Shadow casting detail 3</span><a class="headerlink" href="#id9" title="Permalink to this image"></a></p>
</div>
<p>A larger scale factor is necessary, but needs to be calculated dynamically, as a too small factor might not suffice for very close objects and a very large factor could lead to numerical issues.
Hence, the scale is calculated dynamically as depicted in detail 3, by comparing two isosceles triangles, laying in between the two vectors.
This is only an approximation of the true triangles, but an upper bound, which allows faster processing.
The final scale resolves to <cite>detection_radius / projected_height</cite>, where the projected height is taken from shorter vector.</p>
<div class="figure align-default" id="id10">
<img alt="../../_images/shadowing4.png" src="../../_images/shadowing4.png" />
<p class="caption"><span class="caption-text">Shadow casting detail 4</span><a class="headerlink" href="#id10" title="Permalink to this image"></a></p>
</div>
<p>As shown in detail 4, the scale is just large enough to include the whole detection range, preventing potential numerical issues.
This only holds as long as the detection range is approximated as described above.</p>
</div>
</div>
<div class="section" id="sensorfusionosi">
<h2>SensorFusionOSI<a class="headerlink" href="#sensorfusionosi" title="Permalink to this headline"></a></h2>
<p>The SensorFusionOSI module allows unsorted aggregation of any data provided by sensors. All sampled detected objects can then be broadcasted to connected ADAS.</p>
<p>It collects all SensorDataSignals and merges them into a single SensorDataSignal.</p>
</div>
<div class="section" id="signalprioritizer">
<span id="agentcomponents-signalprioritizer"></span><h2>SignalPrioritizer<a class="headerlink" href="#signalprioritizer" title="Permalink to this headline"></a></h2>
<p>All channels can only have one source.
If one module can have the same input type from multiple sources a prioritizer module is needed in between.
All sources then get an output channel to the prioritizer module and the prioritizer gets an output to the module, which uses this signal.
If more than an component sends an active signal during the same timestep, the prioritizer forwards only the signal from the input channel with the highest priority.
These priorities are set as parameters in the systemconfigblueprint.xml, where the key corresponds the the id of the input channel and the value is the priority (higher value is prioritized).
In the following example the channel with id 102 has the highest priority (3) and the channel with id 100 has the lowest priority (1).</p>
<div class="highlight-xml notranslate"><div class="highlight"><pre><span></span><span class="nt">&lt;component&gt;</span>
<span class="nt">&lt;id&gt;</span>PrioritizerName<span class="nt">&lt;/id&gt;</span>
<span class="nt">&lt;schedule&gt;</span>
<span class="nt">&lt;priority&gt;</span>150<span class="nt">&lt;/priority&gt;</span>
<span class="nt">&lt;offset&gt;</span>0<span class="nt">&lt;/offset&gt;</span>
<span class="nt">&lt;cycle&gt;</span>100<span class="nt">&lt;/cycle&gt;</span>
<span class="nt">&lt;response&gt;</span>0<span class="nt">&lt;/response&gt;</span>
<span class="nt">&lt;/schedule&gt;</span>
<span class="nt">&lt;library&gt;</span>SignalPrioritizer<span class="nt">&lt;/library&gt;</span>
<span class="nt">&lt;parameters&gt;</span>
<span class="nt">&lt;parameter&gt;</span>
<span class="nt">&lt;id&gt;</span>100<span class="nt">&lt;/id&gt;</span>
<span class="nt">&lt;type&gt;</span>int<span class="nt">&lt;/type&gt;</span>
<span class="nt">&lt;unit/&gt;</span>
<span class="nt">&lt;value&gt;</span>1<span class="nt">&lt;/value&gt;</span>
<span class="nt">&lt;/parameter&gt;</span>
<span class="nt">&lt;parameter&gt;</span>
<span class="nt">&lt;id&gt;</span>101<span class="nt">&lt;/id&gt;</span>
<span class="nt">&lt;type&gt;</span>int<span class="nt">&lt;/type&gt;</span>
<span class="nt">&lt;unit/&gt;</span>
<span class="nt">&lt;value&gt;</span>2<span class="nt">&lt;/value&gt;</span>
<span class="nt">&lt;/parameter&gt;</span>
<span class="nt">&lt;parameter&gt;</span>
<span class="nt">&lt;id&gt;</span>102<span class="nt">&lt;/id&gt;</span>
<span class="nt">&lt;type&gt;</span>int<span class="nt">&lt;/type&gt;</span>
<span class="nt">&lt;unit/&gt;</span>
<span class="nt">&lt;value&gt;</span>3<span class="nt">&lt;/value&gt;</span>
<span class="nt">&lt;/parameter&gt;</span>
<span class="nt">&lt;/parameters&gt;</span>
<span class="nt">&lt;/component&gt;</span>
</pre></div>
</div>
<p>One prioritizer module can only handle signals of the same type and the signal class must be derived from ComponentStateSignal.
If there is no signal in one time step, then the signal of the previous time step is hold.</p>
<p><strong>Existing prioritizer modules</strong></p>
<ul class="simple">
<li><p>PrioritizerAccelerationVehicleComponents</p></li>
<li><p>PrioritizerSteeringVehicleComponents</p></li>
<li><p>PrioritizerTurningIndicator</p></li>
<li><p>PrioritizerLongitudinal</p></li>
<li><p>PrioritizerSteering</p></li>
<li><p>PrioritizerDynamics</p></li>
</ul>
</div>
<div class="section" id="componentcontroller">
<h2>ComponentController<a class="headerlink" href="#componentcontroller" title="Permalink to this headline"></a></h2>
<div class="section" id="overview">
<h3>Overview<a class="headerlink" href="#overview" title="Permalink to this headline"></a></h3>
<p>The ComponentController (CC) is used to configure and handle dependencies between other vehicle components.</p>
<p>Example use cases could be:</p>
<ul class="simple">
<li><p>Cruise control:</p>
<ul>
<li><p>driver requesting higher acceleration than cruise control overrides the latter</p></li>
<li><p>driver braking deactivates cruise control</p></li>
</ul>
</li>
<li><p>Lane keeping assistant:</p>
<ul>
<li><p>cannot be activated by driver, if emergency braking is currently active</p></li>
<li><p>stays active, when emergency braking occurs (i. e. by other ADAS)</p></li>
</ul>
</li>
</ul>
<p>The responsibilies of the CC are:</p>
<ul class="simple">
<li><p>Handling of all dependencies between <em>VehicleComponents</em> in case a component wants to activate</p></li>
<li><p>Make information about driver, <em>TrajectoryFollower</em> and other <em>VehicleComponents</em> available to each other</p></li>
<li><p>Determine the highest allowed activation state of a component and notify the affected component about this state</p></li>
</ul>
<p>To achieve this tasks, each component is assigned a maximum allowed state in each time step. This state is of type ComponentState,
which defines <em>Disabled</em>, <em>Armed</em> or <em>Active</em> as allowed states.
Drivers can be in a state of either <em>Active</em> or <em>Passive</em>.</p>
</div>
<div class="section" id="state-handling-inside-vehicle-component">
<h3>State handling inside Vehicle Component<a class="headerlink" href="#state-handling-inside-vehicle-component" title="Permalink to this headline"></a></h3>
<p>Within a vehicle component, the information flow should be implemented as follows:</p>
<ol class="arabic simple">
<li><p>The vehicle component retrieves the information of other components and the current maximum allowed state from the CC.
Other components include drivers, trajectory followers and all other vehicle components connected to the CC.</p></li>
<li><p>Based on that information the vehicle component determines its current desired state.</p></li>
<li><p>The desired state is sent to the CC.</p></li>
</ol>
<p>The CC handles all the dependencies between different components and determines the maximum allowed state for each component based
on the configuration of the CC.</p>
</div>
<div class="section" id="used-signals">
<h3>Used signals<a class="headerlink" href="#used-signals" title="Permalink to this headline"></a></h3>
<p>The CC communicates with the controlled components via framework signals.</p>
<p>Inputs to the ComponentController:</p>
<table class="tight-table docutils align-default">
<colgroup>
<col style="width: 18%" />
<col style="width: 53%" />
<col style="width: 29%" />
</colgroup>
<thead>
<tr class="row-odd"><th class="head"><p>Source</p></th>
<th class="head"><p>Contents</p></th>
<th class="head"><p>Signal</p></th>
</tr>
</thead>
<tbody>
<tr class="row-even"><td><p>TrajectoryFollower</p></td>
<td><p>Current state</p></td>
<td><p>ComponentStateSignal</p></td>
</tr>
<tr class="row-odd"><td><p>Driver</p></td>
<td><p>Current state, pedal activity</p></td>
<td><p>DriverStateSignal</p></td>
</tr>
<tr class="row-even"><td><p>VehicleComponent</p></td>
<td><p>Current state, desired state, generic ADAS parameters</p></td>
<td><p>VehicleCompToCompCtrlSignal</p></td>
</tr>
</tbody>
</table>
<p>Output to other components:</p>
<table class="tight-table docutils align-default">
<colgroup>
<col style="width: 15%" />
<col style="width: 61%" />
<col style="width: 24%" />
</colgroup>
<thead>
<tr class="row-odd"><th class="head"><p>Destination</p></th>
<th class="head"><p>Contents</p></th>
<th class="head"><p>Signal</p></th>
</tr>
</thead>
<tbody>
<tr class="row-even"><td><p>TrajectoryFollower</p></td>
<td><p>Current max. reachable state</p></td>
<td><p>ComponentStateSignal</p></td>
</tr>
<tr class="row-odd"><td><p>Driver</p></td>
<td><p>List of all ADAS with names, stati and types</p></td>
<td><p>AdasStateSignal</p></td>
</tr>
<tr class="row-even"><td><p>VehicleComponent</p></td>
<td><p>Current max. reachable state, list of all ADAS with names, stati and types</p></td>
<td><p>CompCtrlToVehicleCompSignal</p></td>
</tr>
</tbody>
</table>
</div>
</div>
</div>
</div>
</div>
<footer>
<div class="rst-footer-buttons" role="navigation" aria-label="footer navigation">
<a href="event_detector.html" class="btn btn-neutral float-right" title="EventDetector" accesskey="n" rel="next">Next <span class="fa fa-arrow-circle-right" aria-hidden="true"></span></a>
<a href="../20_simulator_advanced.html" class="btn btn-neutral float-left" title="Simulator" accesskey="p" rel="prev"><span class="fa fa-arrow-circle-left" aria-hidden="true"></span> Previous</a>
</div>
<hr/>
<div role="contentinfo">
<p>
&#169; Copyright 2021 OpenPASS Working Group.
</p>
</div>
Built with <a href="https://www.sphinx-doc.org/">Sphinx</a> using a
<a href="https://github.com/readthedocs/sphinx_rtd_theme">theme</a>
provided by <a href="https://readthedocs.org">Read the Docs</a>.
</footer>
</div>
</div>
</section>
</div>
<script type="text/javascript">
jQuery(function () {
SphinxRtdTheme.Navigation.enable(true);
});
</script>
</body>
</html>