Files
PythonRobotics/_modules/Mapping/rectangle_fitting/rectangle_fitting.html
2023-06-30 23:30:35 +00:00

424 lines
55 KiB
HTML

<!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>Mapping.rectangle_fitting.rectangle_fitting &mdash; PythonRobotics documentation</title>
<link rel="stylesheet" href="../../../_static/pygments.css" type="text/css" />
<link rel="stylesheet" href="../../../_static/css/theme.css" type="text/css" />
<link rel="stylesheet" href="../../../_static/plot_directive.css" type="text/css" />
<link rel="stylesheet" href="../../../_static/copybutton.css" type="text/css" />
<link rel="stylesheet" href="../../../_static/custom.css" type="text/css" />
<link rel="stylesheet" href="../../../_static/dark_mode_css/general.css" type="text/css" />
<link rel="stylesheet" href="../../../_static/dark_mode_css/dark.css" type="text/css" />
<!--[if lt IE 9]>
<script src="../../../_static/js/html5shiv.min.js"></script>
<![endif]-->
<script data-url_root="../../../" id="documentation_options" 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 src="../../../_static/clipboard.min.js"></script>
<script src="../../../_static/copybutton.js"></script>
<script src="../../../_static/dark_mode_js/default_dark.js"></script>
<script src="../../../_static/dark_mode_js/theme_switcher.js"></script>
<script src="../../../_static/js/theme.js"></script>
<link rel="index" title="Index" href="../../../genindex.html" />
<link rel="search" title="Search" href="../../../search.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"> PythonRobotics
<img src="../../../_static/icon.png" class="logo" alt="Logo"/>
</a>
<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>
<script async src="https://pagead2.googlesyndication.com/pagead/js/adsbygoogle.js?client=ca-pub-9612347954373886"
crossorigin="anonymous"></script>
<!-- PythonRoboticsDoc -->
<ins class="adsbygoogle"
style="display:block"
data-ad-client="ca-pub-9612347954373886"
data-ad-slot="1579532132"
data-ad-format="auto"
data-full-width-responsive="true"></ins>
<script>
(adsbygoogle = window.adsbygoogle || []).push({});
</script>
</div><div class="wy-menu wy-menu-vertical" data-spy="affix" role="navigation" aria-label="Navigation menu">
<p class="caption" role="heading"><span class="caption-text">Contents</span></p>
<ul>
<li class="toctree-l1"><a class="reference internal" href="../../../getting_started.html">Getting Started</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../../modules/introduction.html">Introduction</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../../modules/localization/localization.html">Localization</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../../modules/mapping/mapping.html">Mapping</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../../modules/slam/slam.html">SLAM</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../../modules/path_planning/path_planning.html">Path Planning</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../../modules/path_tracking/path_tracking.html">Path Tracking</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../../modules/arm_navigation/arm_navigation.html">Arm Navigation</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../../modules/aerial_navigation/aerial_navigation.html">Aerial Navigation</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../../modules/bipedal/bipedal.html">Bipedal</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../../modules/control/control.html">Control</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../../modules/utils/utils.html">Utilities</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../../modules/appendix/appendix.html">Appendix</a></li>
<li class="toctree-l1"><a class="reference internal" href="../../../how_to_contribute.html">How To Contribute</a></li>
</ul>
</div>
</div>
</nav>
<section data-toggle="wy-nav-shift" class="wy-nav-content-wrap"><nav class="wy-nav-top" aria-label="Mobile navigation menu" >
<i data-toggle="wy-nav-top" class="fa fa-bars"></i>
<a href="../../../index.html">PythonRobotics</a>
</nav>
<div class="wy-nav-content">
<div class="rst-content">
<div role="navigation" aria-label="Page navigation">
<ul class="wy-breadcrumbs">
<li><a href="../../../index.html" class="icon icon-home"></a> &raquo;</li>
<li><a href="../../index.html">Module code</a> &raquo;</li>
<li>Mapping.rectangle_fitting.rectangle_fitting</li>
<li class="wy-breadcrumbs-aside">
</li>
</ul>
<hr/>
</div>
<div role="main" class="document" itemscope="itemscope" itemtype="http://schema.org/Article">
<div itemprop="articleBody">
<h1>Source code for Mapping.rectangle_fitting.rectangle_fitting</h1><div class="highlight"><pre>
<span></span><span class="sd">&quot;&quot;&quot;</span>
<span class="sd">Object shape recognition with L-shape fitting</span>
<span class="sd">author: Atsushi Sakai (@Atsushi_twi)</span>
<span class="sd">Ref:</span>
<span class="sd">- Efficient L-Shape Fitting for Vehicle Detection Using Laser Scanners -</span>
<span class="sd">The Robotics Institute Carnegie Mellon University</span>
<span class="sd">https://www.ri.cmu.edu/publications/</span>
<span class="sd">efficient-l-shape-fitting-for-vehicle-detection-using-laser-scanners/</span>
<span class="sd">&quot;&quot;&quot;</span>
<span class="kn">import</span> <span class="nn">sys</span>
<span class="kn">import</span> <span class="nn">pathlib</span>
<span class="n">sys</span><span class="o">.</span><span class="n">path</span><span class="o">.</span><span class="n">append</span><span class="p">(</span><span class="nb">str</span><span class="p">(</span><span class="n">pathlib</span><span class="o">.</span><span class="n">Path</span><span class="p">(</span><span class="vm">__file__</span><span class="p">)</span><span class="o">.</span><span class="n">parent</span><span class="o">.</span><span class="n">parent</span><span class="o">.</span><span class="n">parent</span><span class="p">))</span>
<span class="kn">import</span> <span class="nn">matplotlib.pyplot</span> <span class="k">as</span> <span class="nn">plt</span>
<span class="kn">import</span> <span class="nn">numpy</span> <span class="k">as</span> <span class="nn">np</span>
<span class="kn">import</span> <span class="nn">itertools</span>
<span class="kn">from</span> <span class="nn">enum</span> <span class="kn">import</span> <span class="n">Enum</span>
<span class="kn">from</span> <span class="nn">utils.angle</span> <span class="kn">import</span> <span class="n">rot_mat_2d</span>
<span class="kn">from</span> <span class="nn">Mapping.rectangle_fitting.simulator</span> \
<span class="kn">import</span> <span class="nn">VehicleSimulator</span><span class="o">,</span> <span class="nn">LidarSimulator</span>
<span class="n">show_animation</span> <span class="o">=</span> <span class="kc">True</span>
<div class="viewcode-block" id="LShapeFitting"><a class="viewcode-back" href="../../../modules/mapping/rectangle_fitting/rectangle_fitting.html#Mapping.rectangle_fitting.rectangle_fitting.LShapeFitting">[docs]</a><span class="k">class</span> <span class="nc">LShapeFitting</span><span class="p">:</span>
<span class="w"> </span><span class="sd">&quot;&quot;&quot;</span>
<span class="sd"> LShapeFitting class. You can use this class by initializing the class and</span>
<span class="sd"> changing the parameters, and then calling the fitting method.</span>
<span class="sd"> &quot;&quot;&quot;</span>
<div class="viewcode-block" id="LShapeFitting.Criteria"><a class="viewcode-back" href="../../../modules/mapping/rectangle_fitting/rectangle_fitting.html#Mapping.rectangle_fitting.rectangle_fitting.LShapeFitting.Criteria">[docs]</a> <span class="k">class</span> <span class="nc">Criteria</span><span class="p">(</span><span class="n">Enum</span><span class="p">):</span>
<span class="n">AREA</span> <span class="o">=</span> <span class="mi">1</span>
<span class="n">CLOSENESS</span> <span class="o">=</span> <span class="mi">2</span>
<span class="n">VARIANCE</span> <span class="o">=</span> <span class="mi">3</span></div>
<span class="k">def</span> <span class="fm">__init__</span><span class="p">(</span><span class="bp">self</span><span class="p">):</span>
<span class="w"> </span><span class="sd">&quot;&quot;&quot;</span>
<span class="sd"> Default parameter settings</span>
<span class="sd"> &quot;&quot;&quot;</span>
<span class="c1">#: Fitting criteria parameter</span>
<span class="bp">self</span><span class="o">.</span><span class="n">criteria</span> <span class="o">=</span> <span class="bp">self</span><span class="o">.</span><span class="n">Criteria</span><span class="o">.</span><span class="n">VARIANCE</span>
<span class="c1">#: Minimum distance for closeness criteria parameter [m]</span>
<span class="bp">self</span><span class="o">.</span><span class="n">min_dist_of_closeness_criteria</span> <span class="o">=</span> <span class="mf">0.01</span>
<span class="c1">#: Angle difference parameter [deg]</span>
<span class="bp">self</span><span class="o">.</span><span class="n">d_theta_deg_for_search</span> <span class="o">=</span> <span class="mf">1.0</span>
<span class="c1">#: Range segmentation parameter [m]</span>
<span class="bp">self</span><span class="o">.</span><span class="n">R0</span> <span class="o">=</span> <span class="mf">3.0</span>
<span class="c1">#: Range segmentation parameter [m]</span>
<span class="bp">self</span><span class="o">.</span><span class="n">Rd</span> <span class="o">=</span> <span class="mf">0.001</span>
<div class="viewcode-block" id="LShapeFitting.fitting"><a class="viewcode-back" href="../../../modules/mapping/rectangle_fitting/rectangle_fitting.html#Mapping.rectangle_fitting.rectangle_fitting.LShapeFitting.fitting">[docs]</a> <span class="k">def</span> <span class="nf">fitting</span><span class="p">(</span><span class="bp">self</span><span class="p">,</span> <span class="n">ox</span><span class="p">,</span> <span class="n">oy</span><span class="p">):</span>
<span class="w"> </span><span class="sd">&quot;&quot;&quot;</span>
<span class="sd"> Fitting L-shape model to object points</span>
<span class="sd"> Parameters</span>
<span class="sd"> ----------</span>
<span class="sd"> ox : x positions of range points from an object</span>
<span class="sd"> oy : y positions of range points from an object</span>
<span class="sd"> Returns</span>
<span class="sd"> -------</span>
<span class="sd"> rects: Fitting rectangles</span>
<span class="sd"> id_sets: id sets of each cluster</span>
<span class="sd"> &quot;&quot;&quot;</span>
<span class="c1"># step1: Adaptive Range Segmentation</span>
<span class="n">id_sets</span> <span class="o">=</span> <span class="bp">self</span><span class="o">.</span><span class="n">_adoptive_range_segmentation</span><span class="p">(</span><span class="n">ox</span><span class="p">,</span> <span class="n">oy</span><span class="p">)</span>
<span class="c1"># step2 Rectangle search</span>
<span class="n">rects</span> <span class="o">=</span> <span class="p">[]</span>
<span class="k">for</span> <span class="n">ids</span> <span class="ow">in</span> <span class="n">id_sets</span><span class="p">:</span> <span class="c1"># for each cluster</span>
<span class="n">cx</span> <span class="o">=</span> <span class="p">[</span><span class="n">ox</span><span class="p">[</span><span class="n">i</span><span class="p">]</span> <span class="k">for</span> <span class="n">i</span> <span class="ow">in</span> <span class="nb">range</span><span class="p">(</span><span class="nb">len</span><span class="p">(</span><span class="n">ox</span><span class="p">))</span> <span class="k">if</span> <span class="n">i</span> <span class="ow">in</span> <span class="n">ids</span><span class="p">]</span>
<span class="n">cy</span> <span class="o">=</span> <span class="p">[</span><span class="n">oy</span><span class="p">[</span><span class="n">i</span><span class="p">]</span> <span class="k">for</span> <span class="n">i</span> <span class="ow">in</span> <span class="nb">range</span><span class="p">(</span><span class="nb">len</span><span class="p">(</span><span class="n">oy</span><span class="p">))</span> <span class="k">if</span> <span class="n">i</span> <span class="ow">in</span> <span class="n">ids</span><span class="p">]</span>
<span class="n">rects</span><span class="o">.</span><span class="n">append</span><span class="p">(</span><span class="bp">self</span><span class="o">.</span><span class="n">_rectangle_search</span><span class="p">(</span><span class="n">cx</span><span class="p">,</span> <span class="n">cy</span><span class="p">))</span>
<span class="k">return</span> <span class="n">rects</span><span class="p">,</span> <span class="n">id_sets</span></div>
<span class="nd">@staticmethod</span>
<span class="k">def</span> <span class="nf">_calc_area_criterion</span><span class="p">(</span><span class="n">c1</span><span class="p">,</span> <span class="n">c2</span><span class="p">):</span>
<span class="n">c1_max</span><span class="p">,</span> <span class="n">c1_min</span><span class="p">,</span> <span class="n">c2_max</span><span class="p">,</span> <span class="n">c2_min</span> <span class="o">=</span> <span class="n">LShapeFitting</span><span class="o">.</span><span class="n">_find_min_max</span><span class="p">(</span><span class="n">c1</span><span class="p">,</span> <span class="n">c2</span><span class="p">)</span>
<span class="n">alpha</span> <span class="o">=</span> <span class="o">-</span><span class="p">(</span><span class="n">c1_max</span> <span class="o">-</span> <span class="n">c1_min</span><span class="p">)</span> <span class="o">*</span> <span class="p">(</span><span class="n">c2_max</span> <span class="o">-</span> <span class="n">c2_min</span><span class="p">)</span>
<span class="k">return</span> <span class="n">alpha</span>
<span class="k">def</span> <span class="nf">_calc_closeness_criterion</span><span class="p">(</span><span class="bp">self</span><span class="p">,</span> <span class="n">c1</span><span class="p">,</span> <span class="n">c2</span><span class="p">):</span>
<span class="n">c1_max</span><span class="p">,</span> <span class="n">c1_min</span><span class="p">,</span> <span class="n">c2_max</span><span class="p">,</span> <span class="n">c2_min</span> <span class="o">=</span> <span class="n">LShapeFitting</span><span class="o">.</span><span class="n">_find_min_max</span><span class="p">(</span><span class="n">c1</span><span class="p">,</span> <span class="n">c2</span><span class="p">)</span>
<span class="c1"># Vectorization</span>
<span class="n">d1</span> <span class="o">=</span> <span class="n">np</span><span class="o">.</span><span class="n">minimum</span><span class="p">(</span><span class="n">c1_max</span> <span class="o">-</span> <span class="n">c1</span><span class="p">,</span> <span class="n">c1</span> <span class="o">-</span> <span class="n">c1_min</span><span class="p">)</span>
<span class="n">d2</span> <span class="o">=</span> <span class="n">np</span><span class="o">.</span><span class="n">minimum</span><span class="p">(</span><span class="n">c2_max</span> <span class="o">-</span> <span class="n">c2</span><span class="p">,</span> <span class="n">c2</span> <span class="o">-</span> <span class="n">c2_min</span><span class="p">)</span>
<span class="n">d</span> <span class="o">=</span> <span class="n">np</span><span class="o">.</span><span class="n">maximum</span><span class="p">(</span><span class="n">np</span><span class="o">.</span><span class="n">minimum</span><span class="p">(</span><span class="n">d1</span><span class="p">,</span> <span class="n">d2</span><span class="p">),</span> <span class="bp">self</span><span class="o">.</span><span class="n">min_dist_of_closeness_criteria</span><span class="p">)</span>
<span class="n">beta</span> <span class="o">=</span> <span class="p">(</span><span class="mf">1.0</span> <span class="o">/</span> <span class="n">d</span><span class="p">)</span><span class="o">.</span><span class="n">sum</span><span class="p">()</span>
<span class="k">return</span> <span class="n">beta</span>
<span class="nd">@staticmethod</span>
<span class="k">def</span> <span class="nf">_calc_variance_criterion</span><span class="p">(</span><span class="n">c1</span><span class="p">,</span> <span class="n">c2</span><span class="p">):</span>
<span class="n">c1_max</span><span class="p">,</span> <span class="n">c1_min</span><span class="p">,</span> <span class="n">c2_max</span><span class="p">,</span> <span class="n">c2_min</span> <span class="o">=</span> <span class="n">LShapeFitting</span><span class="o">.</span><span class="n">_find_min_max</span><span class="p">(</span><span class="n">c1</span><span class="p">,</span> <span class="n">c2</span><span class="p">)</span>
<span class="c1"># Vectorization</span>
<span class="n">d1</span> <span class="o">=</span> <span class="n">np</span><span class="o">.</span><span class="n">minimum</span><span class="p">(</span><span class="n">c1_max</span> <span class="o">-</span> <span class="n">c1</span><span class="p">,</span> <span class="n">c1</span> <span class="o">-</span> <span class="n">c1_min</span><span class="p">)</span>
<span class="n">d2</span> <span class="o">=</span> <span class="n">np</span><span class="o">.</span><span class="n">minimum</span><span class="p">(</span><span class="n">c2_max</span> <span class="o">-</span> <span class="n">c2</span><span class="p">,</span> <span class="n">c2</span> <span class="o">-</span> <span class="n">c2_min</span><span class="p">)</span>
<span class="n">e1</span> <span class="o">=</span> <span class="n">d1</span><span class="p">[</span><span class="n">d1</span> <span class="o">&lt;</span> <span class="n">d2</span><span class="p">]</span>
<span class="n">e2</span> <span class="o">=</span> <span class="n">d2</span><span class="p">[</span><span class="n">d1</span> <span class="o">&gt;=</span> <span class="n">d2</span><span class="p">]</span>
<span class="n">v1</span> <span class="o">=</span> <span class="o">-</span> <span class="n">np</span><span class="o">.</span><span class="n">var</span><span class="p">(</span><span class="n">e1</span><span class="p">)</span> <span class="k">if</span> <span class="nb">len</span><span class="p">(</span><span class="n">e1</span><span class="p">)</span> <span class="o">&gt;</span> <span class="mi">0</span> <span class="k">else</span> <span class="mf">0.</span>
<span class="n">v2</span> <span class="o">=</span> <span class="o">-</span> <span class="n">np</span><span class="o">.</span><span class="n">var</span><span class="p">(</span><span class="n">e2</span><span class="p">)</span> <span class="k">if</span> <span class="nb">len</span><span class="p">(</span><span class="n">e2</span><span class="p">)</span> <span class="o">&gt;</span> <span class="mi">0</span> <span class="k">else</span> <span class="mf">0.</span>
<span class="n">gamma</span> <span class="o">=</span> <span class="n">v1</span> <span class="o">+</span> <span class="n">v2</span>
<span class="k">return</span> <span class="n">gamma</span>
<span class="nd">@staticmethod</span>
<span class="k">def</span> <span class="nf">_find_min_max</span><span class="p">(</span><span class="n">c1</span><span class="p">,</span> <span class="n">c2</span><span class="p">):</span>
<span class="n">c1_max</span> <span class="o">=</span> <span class="nb">max</span><span class="p">(</span><span class="n">c1</span><span class="p">)</span>
<span class="n">c2_max</span> <span class="o">=</span> <span class="nb">max</span><span class="p">(</span><span class="n">c2</span><span class="p">)</span>
<span class="n">c1_min</span> <span class="o">=</span> <span class="nb">min</span><span class="p">(</span><span class="n">c1</span><span class="p">)</span>
<span class="n">c2_min</span> <span class="o">=</span> <span class="nb">min</span><span class="p">(</span><span class="n">c2</span><span class="p">)</span>
<span class="k">return</span> <span class="n">c1_max</span><span class="p">,</span> <span class="n">c1_min</span><span class="p">,</span> <span class="n">c2_max</span><span class="p">,</span> <span class="n">c2_min</span>
<span class="k">def</span> <span class="nf">_rectangle_search</span><span class="p">(</span><span class="bp">self</span><span class="p">,</span> <span class="n">x</span><span class="p">,</span> <span class="n">y</span><span class="p">):</span>
<span class="n">xy</span> <span class="o">=</span> <span class="n">np</span><span class="o">.</span><span class="n">array</span><span class="p">([</span><span class="n">x</span><span class="p">,</span> <span class="n">y</span><span class="p">])</span><span class="o">.</span><span class="n">T</span>
<span class="n">d_theta</span> <span class="o">=</span> <span class="n">np</span><span class="o">.</span><span class="n">deg2rad</span><span class="p">(</span><span class="bp">self</span><span class="o">.</span><span class="n">d_theta_deg_for_search</span><span class="p">)</span>
<span class="n">min_cost</span> <span class="o">=</span> <span class="p">(</span><span class="o">-</span><span class="nb">float</span><span class="p">(</span><span class="s1">&#39;inf&#39;</span><span class="p">),</span> <span class="kc">None</span><span class="p">)</span>
<span class="k">for</span> <span class="n">theta</span> <span class="ow">in</span> <span class="n">np</span><span class="o">.</span><span class="n">arange</span><span class="p">(</span><span class="mf">0.0</span><span class="p">,</span> <span class="n">np</span><span class="o">.</span><span class="n">pi</span> <span class="o">/</span> <span class="mf">2.0</span> <span class="o">-</span> <span class="n">d_theta</span><span class="p">,</span> <span class="n">d_theta</span><span class="p">):</span>
<span class="n">c</span> <span class="o">=</span> <span class="n">xy</span> <span class="o">@</span> <span class="n">rot_mat_2d</span><span class="p">(</span><span class="n">theta</span><span class="p">)</span>
<span class="n">c1</span> <span class="o">=</span> <span class="n">c</span><span class="p">[:,</span> <span class="mi">0</span><span class="p">]</span>
<span class="n">c2</span> <span class="o">=</span> <span class="n">c</span><span class="p">[:,</span> <span class="mi">1</span><span class="p">]</span>
<span class="c1"># Select criteria</span>
<span class="n">cost</span> <span class="o">=</span> <span class="mf">0.0</span>
<span class="k">if</span> <span class="bp">self</span><span class="o">.</span><span class="n">criteria</span> <span class="o">==</span> <span class="bp">self</span><span class="o">.</span><span class="n">Criteria</span><span class="o">.</span><span class="n">AREA</span><span class="p">:</span>
<span class="n">cost</span> <span class="o">=</span> <span class="bp">self</span><span class="o">.</span><span class="n">_calc_area_criterion</span><span class="p">(</span><span class="n">c1</span><span class="p">,</span> <span class="n">c2</span><span class="p">)</span>
<span class="k">elif</span> <span class="bp">self</span><span class="o">.</span><span class="n">criteria</span> <span class="o">==</span> <span class="bp">self</span><span class="o">.</span><span class="n">Criteria</span><span class="o">.</span><span class="n">CLOSENESS</span><span class="p">:</span>
<span class="n">cost</span> <span class="o">=</span> <span class="bp">self</span><span class="o">.</span><span class="n">_calc_closeness_criterion</span><span class="p">(</span><span class="n">c1</span><span class="p">,</span> <span class="n">c2</span><span class="p">)</span>
<span class="k">elif</span> <span class="bp">self</span><span class="o">.</span><span class="n">criteria</span> <span class="o">==</span> <span class="bp">self</span><span class="o">.</span><span class="n">Criteria</span><span class="o">.</span><span class="n">VARIANCE</span><span class="p">:</span>
<span class="n">cost</span> <span class="o">=</span> <span class="bp">self</span><span class="o">.</span><span class="n">_calc_variance_criterion</span><span class="p">(</span><span class="n">c1</span><span class="p">,</span> <span class="n">c2</span><span class="p">)</span>
<span class="k">if</span> <span class="n">min_cost</span><span class="p">[</span><span class="mi">0</span><span class="p">]</span> <span class="o">&lt;</span> <span class="n">cost</span><span class="p">:</span>
<span class="n">min_cost</span> <span class="o">=</span> <span class="p">(</span><span class="n">cost</span><span class="p">,</span> <span class="n">theta</span><span class="p">)</span>
<span class="c1"># calc best rectangle</span>
<span class="n">sin_s</span> <span class="o">=</span> <span class="n">np</span><span class="o">.</span><span class="n">sin</span><span class="p">(</span><span class="n">min_cost</span><span class="p">[</span><span class="mi">1</span><span class="p">])</span>
<span class="n">cos_s</span> <span class="o">=</span> <span class="n">np</span><span class="o">.</span><span class="n">cos</span><span class="p">(</span><span class="n">min_cost</span><span class="p">[</span><span class="mi">1</span><span class="p">])</span>
<span class="n">c1_s</span> <span class="o">=</span> <span class="n">xy</span> <span class="o">@</span> <span class="n">np</span><span class="o">.</span><span class="n">array</span><span class="p">([</span><span class="n">cos_s</span><span class="p">,</span> <span class="n">sin_s</span><span class="p">])</span><span class="o">.</span><span class="n">T</span>
<span class="n">c2_s</span> <span class="o">=</span> <span class="n">xy</span> <span class="o">@</span> <span class="n">np</span><span class="o">.</span><span class="n">array</span><span class="p">([</span><span class="o">-</span><span class="n">sin_s</span><span class="p">,</span> <span class="n">cos_s</span><span class="p">])</span><span class="o">.</span><span class="n">T</span>
<span class="n">rect</span> <span class="o">=</span> <span class="n">RectangleData</span><span class="p">()</span>
<span class="n">rect</span><span class="o">.</span><span class="n">a</span><span class="p">[</span><span class="mi">0</span><span class="p">]</span> <span class="o">=</span> <span class="n">cos_s</span>
<span class="n">rect</span><span class="o">.</span><span class="n">b</span><span class="p">[</span><span class="mi">0</span><span class="p">]</span> <span class="o">=</span> <span class="n">sin_s</span>
<span class="n">rect</span><span class="o">.</span><span class="n">c</span><span class="p">[</span><span class="mi">0</span><span class="p">]</span> <span class="o">=</span> <span class="nb">min</span><span class="p">(</span><span class="n">c1_s</span><span class="p">)</span>
<span class="n">rect</span><span class="o">.</span><span class="n">a</span><span class="p">[</span><span class="mi">1</span><span class="p">]</span> <span class="o">=</span> <span class="o">-</span><span class="n">sin_s</span>
<span class="n">rect</span><span class="o">.</span><span class="n">b</span><span class="p">[</span><span class="mi">1</span><span class="p">]</span> <span class="o">=</span> <span class="n">cos_s</span>
<span class="n">rect</span><span class="o">.</span><span class="n">c</span><span class="p">[</span><span class="mi">1</span><span class="p">]</span> <span class="o">=</span> <span class="nb">min</span><span class="p">(</span><span class="n">c2_s</span><span class="p">)</span>
<span class="n">rect</span><span class="o">.</span><span class="n">a</span><span class="p">[</span><span class="mi">2</span><span class="p">]</span> <span class="o">=</span> <span class="n">cos_s</span>
<span class="n">rect</span><span class="o">.</span><span class="n">b</span><span class="p">[</span><span class="mi">2</span><span class="p">]</span> <span class="o">=</span> <span class="n">sin_s</span>
<span class="n">rect</span><span class="o">.</span><span class="n">c</span><span class="p">[</span><span class="mi">2</span><span class="p">]</span> <span class="o">=</span> <span class="nb">max</span><span class="p">(</span><span class="n">c1_s</span><span class="p">)</span>
<span class="n">rect</span><span class="o">.</span><span class="n">a</span><span class="p">[</span><span class="mi">3</span><span class="p">]</span> <span class="o">=</span> <span class="o">-</span><span class="n">sin_s</span>
<span class="n">rect</span><span class="o">.</span><span class="n">b</span><span class="p">[</span><span class="mi">3</span><span class="p">]</span> <span class="o">=</span> <span class="n">cos_s</span>
<span class="n">rect</span><span class="o">.</span><span class="n">c</span><span class="p">[</span><span class="mi">3</span><span class="p">]</span> <span class="o">=</span> <span class="nb">max</span><span class="p">(</span><span class="n">c2_s</span><span class="p">)</span>
<span class="k">return</span> <span class="n">rect</span>
<span class="k">def</span> <span class="nf">_adoptive_range_segmentation</span><span class="p">(</span><span class="bp">self</span><span class="p">,</span> <span class="n">ox</span><span class="p">,</span> <span class="n">oy</span><span class="p">):</span>
<span class="c1"># Setup initial cluster</span>
<span class="n">segment_list</span> <span class="o">=</span> <span class="p">[]</span>
<span class="k">for</span> <span class="n">i</span><span class="p">,</span> <span class="n">_</span> <span class="ow">in</span> <span class="nb">enumerate</span><span class="p">(</span><span class="n">ox</span><span class="p">):</span>
<span class="n">c</span> <span class="o">=</span> <span class="nb">set</span><span class="p">()</span>
<span class="n">r</span> <span class="o">=</span> <span class="bp">self</span><span class="o">.</span><span class="n">R0</span> <span class="o">+</span> <span class="bp">self</span><span class="o">.</span><span class="n">Rd</span> <span class="o">*</span> <span class="n">np</span><span class="o">.</span><span class="n">linalg</span><span class="o">.</span><span class="n">norm</span><span class="p">([</span><span class="n">ox</span><span class="p">[</span><span class="n">i</span><span class="p">],</span> <span class="n">oy</span><span class="p">[</span><span class="n">i</span><span class="p">]])</span>
<span class="k">for</span> <span class="n">j</span><span class="p">,</span> <span class="n">_</span> <span class="ow">in</span> <span class="nb">enumerate</span><span class="p">(</span><span class="n">ox</span><span class="p">):</span>
<span class="n">d</span> <span class="o">=</span> <span class="n">np</span><span class="o">.</span><span class="n">hypot</span><span class="p">(</span><span class="n">ox</span><span class="p">[</span><span class="n">i</span><span class="p">]</span> <span class="o">-</span> <span class="n">ox</span><span class="p">[</span><span class="n">j</span><span class="p">],</span> <span class="n">oy</span><span class="p">[</span><span class="n">i</span><span class="p">]</span> <span class="o">-</span> <span class="n">oy</span><span class="p">[</span><span class="n">j</span><span class="p">])</span>
<span class="k">if</span> <span class="n">d</span> <span class="o">&lt;=</span> <span class="n">r</span><span class="p">:</span>
<span class="n">c</span><span class="o">.</span><span class="n">add</span><span class="p">(</span><span class="n">j</span><span class="p">)</span>
<span class="n">segment_list</span><span class="o">.</span><span class="n">append</span><span class="p">(</span><span class="n">c</span><span class="p">)</span>
<span class="c1"># Merge cluster</span>
<span class="k">while</span> <span class="kc">True</span><span class="p">:</span>
<span class="n">no_change</span> <span class="o">=</span> <span class="kc">True</span>
<span class="k">for</span> <span class="p">(</span><span class="n">c1</span><span class="p">,</span> <span class="n">c2</span><span class="p">)</span> <span class="ow">in</span> <span class="nb">list</span><span class="p">(</span><span class="n">itertools</span><span class="o">.</span><span class="n">permutations</span><span class="p">(</span><span class="nb">range</span><span class="p">(</span><span class="nb">len</span><span class="p">(</span><span class="n">segment_list</span><span class="p">)),</span> <span class="mi">2</span><span class="p">)):</span>
<span class="k">if</span> <span class="n">segment_list</span><span class="p">[</span><span class="n">c1</span><span class="p">]</span> <span class="o">&amp;</span> <span class="n">segment_list</span><span class="p">[</span><span class="n">c2</span><span class="p">]:</span>
<span class="n">segment_list</span><span class="p">[</span><span class="n">c1</span><span class="p">]</span> <span class="o">=</span> <span class="p">(</span><span class="n">segment_list</span><span class="p">[</span><span class="n">c1</span><span class="p">]</span> <span class="o">|</span> <span class="n">segment_list</span><span class="o">.</span><span class="n">pop</span><span class="p">(</span><span class="n">c2</span><span class="p">))</span>
<span class="n">no_change</span> <span class="o">=</span> <span class="kc">False</span>
<span class="k">break</span>
<span class="k">if</span> <span class="n">no_change</span><span class="p">:</span>
<span class="k">break</span>
<span class="k">return</span> <span class="n">segment_list</span></div>
<span class="k">class</span> <span class="nc">RectangleData</span><span class="p">:</span>
<span class="k">def</span> <span class="fm">__init__</span><span class="p">(</span><span class="bp">self</span><span class="p">):</span>
<span class="bp">self</span><span class="o">.</span><span class="n">a</span> <span class="o">=</span> <span class="p">[</span><span class="kc">None</span><span class="p">]</span> <span class="o">*</span> <span class="mi">4</span>
<span class="bp">self</span><span class="o">.</span><span class="n">b</span> <span class="o">=</span> <span class="p">[</span><span class="kc">None</span><span class="p">]</span> <span class="o">*</span> <span class="mi">4</span>
<span class="bp">self</span><span class="o">.</span><span class="n">c</span> <span class="o">=</span> <span class="p">[</span><span class="kc">None</span><span class="p">]</span> <span class="o">*</span> <span class="mi">4</span>
<span class="bp">self</span><span class="o">.</span><span class="n">rect_c_x</span> <span class="o">=</span> <span class="p">[</span><span class="kc">None</span><span class="p">]</span> <span class="o">*</span> <span class="mi">5</span>
<span class="bp">self</span><span class="o">.</span><span class="n">rect_c_y</span> <span class="o">=</span> <span class="p">[</span><span class="kc">None</span><span class="p">]</span> <span class="o">*</span> <span class="mi">5</span>
<span class="k">def</span> <span class="nf">plot</span><span class="p">(</span><span class="bp">self</span><span class="p">):</span>
<span class="bp">self</span><span class="o">.</span><span class="n">calc_rect_contour</span><span class="p">()</span>
<span class="n">plt</span><span class="o">.</span><span class="n">plot</span><span class="p">(</span><span class="bp">self</span><span class="o">.</span><span class="n">rect_c_x</span><span class="p">,</span> <span class="bp">self</span><span class="o">.</span><span class="n">rect_c_y</span><span class="p">,</span> <span class="s2">&quot;-r&quot;</span><span class="p">)</span>
<span class="k">def</span> <span class="nf">calc_rect_contour</span><span class="p">(</span><span class="bp">self</span><span class="p">):</span>
<span class="bp">self</span><span class="o">.</span><span class="n">rect_c_x</span><span class="p">[</span><span class="mi">0</span><span class="p">],</span> <span class="bp">self</span><span class="o">.</span><span class="n">rect_c_y</span><span class="p">[</span><span class="mi">0</span><span class="p">]</span> <span class="o">=</span> <span class="bp">self</span><span class="o">.</span><span class="n">calc_cross_point</span><span class="p">(</span>
<span class="bp">self</span><span class="o">.</span><span class="n">a</span><span class="p">[</span><span class="mi">0</span><span class="p">:</span><span class="mi">2</span><span class="p">],</span> <span class="bp">self</span><span class="o">.</span><span class="n">b</span><span class="p">[</span><span class="mi">0</span><span class="p">:</span><span class="mi">2</span><span class="p">],</span> <span class="bp">self</span><span class="o">.</span><span class="n">c</span><span class="p">[</span><span class="mi">0</span><span class="p">:</span><span class="mi">2</span><span class="p">])</span>
<span class="bp">self</span><span class="o">.</span><span class="n">rect_c_x</span><span class="p">[</span><span class="mi">1</span><span class="p">],</span> <span class="bp">self</span><span class="o">.</span><span class="n">rect_c_y</span><span class="p">[</span><span class="mi">1</span><span class="p">]</span> <span class="o">=</span> <span class="bp">self</span><span class="o">.</span><span class="n">calc_cross_point</span><span class="p">(</span>
<span class="bp">self</span><span class="o">.</span><span class="n">a</span><span class="p">[</span><span class="mi">1</span><span class="p">:</span><span class="mi">3</span><span class="p">],</span> <span class="bp">self</span><span class="o">.</span><span class="n">b</span><span class="p">[</span><span class="mi">1</span><span class="p">:</span><span class="mi">3</span><span class="p">],</span> <span class="bp">self</span><span class="o">.</span><span class="n">c</span><span class="p">[</span><span class="mi">1</span><span class="p">:</span><span class="mi">3</span><span class="p">])</span>
<span class="bp">self</span><span class="o">.</span><span class="n">rect_c_x</span><span class="p">[</span><span class="mi">2</span><span class="p">],</span> <span class="bp">self</span><span class="o">.</span><span class="n">rect_c_y</span><span class="p">[</span><span class="mi">2</span><span class="p">]</span> <span class="o">=</span> <span class="bp">self</span><span class="o">.</span><span class="n">calc_cross_point</span><span class="p">(</span>
<span class="bp">self</span><span class="o">.</span><span class="n">a</span><span class="p">[</span><span class="mi">2</span><span class="p">:</span><span class="mi">4</span><span class="p">],</span> <span class="bp">self</span><span class="o">.</span><span class="n">b</span><span class="p">[</span><span class="mi">2</span><span class="p">:</span><span class="mi">4</span><span class="p">],</span> <span class="bp">self</span><span class="o">.</span><span class="n">c</span><span class="p">[</span><span class="mi">2</span><span class="p">:</span><span class="mi">4</span><span class="p">])</span>
<span class="bp">self</span><span class="o">.</span><span class="n">rect_c_x</span><span class="p">[</span><span class="mi">3</span><span class="p">],</span> <span class="bp">self</span><span class="o">.</span><span class="n">rect_c_y</span><span class="p">[</span><span class="mi">3</span><span class="p">]</span> <span class="o">=</span> <span class="bp">self</span><span class="o">.</span><span class="n">calc_cross_point</span><span class="p">(</span>
<span class="p">[</span><span class="bp">self</span><span class="o">.</span><span class="n">a</span><span class="p">[</span><span class="mi">3</span><span class="p">],</span> <span class="bp">self</span><span class="o">.</span><span class="n">a</span><span class="p">[</span><span class="mi">0</span><span class="p">]],</span> <span class="p">[</span><span class="bp">self</span><span class="o">.</span><span class="n">b</span><span class="p">[</span><span class="mi">3</span><span class="p">],</span> <span class="bp">self</span><span class="o">.</span><span class="n">b</span><span class="p">[</span><span class="mi">0</span><span class="p">]],</span> <span class="p">[</span><span class="bp">self</span><span class="o">.</span><span class="n">c</span><span class="p">[</span><span class="mi">3</span><span class="p">],</span> <span class="bp">self</span><span class="o">.</span><span class="n">c</span><span class="p">[</span><span class="mi">0</span><span class="p">]])</span>
<span class="bp">self</span><span class="o">.</span><span class="n">rect_c_x</span><span class="p">[</span><span class="mi">4</span><span class="p">],</span> <span class="bp">self</span><span class="o">.</span><span class="n">rect_c_y</span><span class="p">[</span><span class="mi">4</span><span class="p">]</span> <span class="o">=</span> <span class="bp">self</span><span class="o">.</span><span class="n">rect_c_x</span><span class="p">[</span><span class="mi">0</span><span class="p">],</span> <span class="bp">self</span><span class="o">.</span><span class="n">rect_c_y</span><span class="p">[</span><span class="mi">0</span><span class="p">]</span>
<span class="nd">@staticmethod</span>
<span class="k">def</span> <span class="nf">calc_cross_point</span><span class="p">(</span><span class="n">a</span><span class="p">,</span> <span class="n">b</span><span class="p">,</span> <span class="n">c</span><span class="p">):</span>
<span class="n">x</span> <span class="o">=</span> <span class="p">(</span><span class="n">b</span><span class="p">[</span><span class="mi">0</span><span class="p">]</span> <span class="o">*</span> <span class="o">-</span><span class="n">c</span><span class="p">[</span><span class="mi">1</span><span class="p">]</span> <span class="o">-</span> <span class="n">b</span><span class="p">[</span><span class="mi">1</span><span class="p">]</span> <span class="o">*</span> <span class="o">-</span><span class="n">c</span><span class="p">[</span><span class="mi">0</span><span class="p">])</span> <span class="o">/</span> <span class="p">(</span><span class="n">a</span><span class="p">[</span><span class="mi">0</span><span class="p">]</span> <span class="o">*</span> <span class="n">b</span><span class="p">[</span><span class="mi">1</span><span class="p">]</span> <span class="o">-</span> <span class="n">a</span><span class="p">[</span><span class="mi">1</span><span class="p">]</span> <span class="o">*</span> <span class="n">b</span><span class="p">[</span><span class="mi">0</span><span class="p">])</span>
<span class="n">y</span> <span class="o">=</span> <span class="p">(</span><span class="n">a</span><span class="p">[</span><span class="mi">1</span><span class="p">]</span> <span class="o">*</span> <span class="o">-</span><span class="n">c</span><span class="p">[</span><span class="mi">0</span><span class="p">]</span> <span class="o">-</span> <span class="n">a</span><span class="p">[</span><span class="mi">0</span><span class="p">]</span> <span class="o">*</span> <span class="o">-</span><span class="n">c</span><span class="p">[</span><span class="mi">1</span><span class="p">])</span> <span class="o">/</span> <span class="p">(</span><span class="n">a</span><span class="p">[</span><span class="mi">0</span><span class="p">]</span> <span class="o">*</span> <span class="n">b</span><span class="p">[</span><span class="mi">1</span><span class="p">]</span> <span class="o">-</span> <span class="n">a</span><span class="p">[</span><span class="mi">1</span><span class="p">]</span> <span class="o">*</span> <span class="n">b</span><span class="p">[</span><span class="mi">0</span><span class="p">])</span>
<span class="k">return</span> <span class="n">x</span><span class="p">,</span> <span class="n">y</span>
<span class="k">def</span> <span class="nf">main</span><span class="p">():</span>
<span class="c1"># simulation parameters</span>
<span class="n">sim_time</span> <span class="o">=</span> <span class="mf">30.0</span> <span class="c1"># simulation time</span>
<span class="n">dt</span> <span class="o">=</span> <span class="mf">0.2</span> <span class="c1"># time tick</span>
<span class="n">angle_resolution</span> <span class="o">=</span> <span class="n">np</span><span class="o">.</span><span class="n">deg2rad</span><span class="p">(</span><span class="mf">3.0</span><span class="p">)</span> <span class="c1"># sensor angle resolution</span>
<span class="n">v1</span> <span class="o">=</span> <span class="n">VehicleSimulator</span><span class="p">(</span><span class="o">-</span><span class="mf">10.0</span><span class="p">,</span> <span class="mf">0.0</span><span class="p">,</span> <span class="n">np</span><span class="o">.</span><span class="n">deg2rad</span><span class="p">(</span><span class="mf">90.0</span><span class="p">),</span>
<span class="mf">0.0</span><span class="p">,</span> <span class="mf">50.0</span> <span class="o">/</span> <span class="mf">3.6</span><span class="p">,</span> <span class="mf">3.0</span><span class="p">,</span> <span class="mf">5.0</span><span class="p">)</span>
<span class="n">v2</span> <span class="o">=</span> <span class="n">VehicleSimulator</span><span class="p">(</span><span class="mf">20.0</span><span class="p">,</span> <span class="mf">10.0</span><span class="p">,</span> <span class="n">np</span><span class="o">.</span><span class="n">deg2rad</span><span class="p">(</span><span class="mf">180.0</span><span class="p">),</span>
<span class="mf">0.0</span><span class="p">,</span> <span class="mf">50.0</span> <span class="o">/</span> <span class="mf">3.6</span><span class="p">,</span> <span class="mf">4.0</span><span class="p">,</span> <span class="mf">10.0</span><span class="p">)</span>
<span class="n">l_shape_fitting</span> <span class="o">=</span> <span class="n">LShapeFitting</span><span class="p">()</span>
<span class="n">lidar_sim</span> <span class="o">=</span> <span class="n">LidarSimulator</span><span class="p">()</span>
<span class="n">time</span> <span class="o">=</span> <span class="mf">0.0</span>
<span class="k">while</span> <span class="n">time</span> <span class="o">&lt;=</span> <span class="n">sim_time</span><span class="p">:</span>
<span class="n">time</span> <span class="o">+=</span> <span class="n">dt</span>
<span class="n">v1</span><span class="o">.</span><span class="n">update</span><span class="p">(</span><span class="n">dt</span><span class="p">,</span> <span class="mf">0.1</span><span class="p">,</span> <span class="mf">0.0</span><span class="p">)</span>
<span class="n">v2</span><span class="o">.</span><span class="n">update</span><span class="p">(</span><span class="n">dt</span><span class="p">,</span> <span class="mf">0.1</span><span class="p">,</span> <span class="o">-</span><span class="mf">0.05</span><span class="p">)</span>
<span class="n">ox</span><span class="p">,</span> <span class="n">oy</span> <span class="o">=</span> <span class="n">lidar_sim</span><span class="o">.</span><span class="n">get_observation_points</span><span class="p">([</span><span class="n">v1</span><span class="p">,</span> <span class="n">v2</span><span class="p">],</span> <span class="n">angle_resolution</span><span class="p">)</span>
<span class="n">rects</span><span class="p">,</span> <span class="n">id_sets</span> <span class="o">=</span> <span class="n">l_shape_fitting</span><span class="o">.</span><span class="n">fitting</span><span class="p">(</span><span class="n">ox</span><span class="p">,</span> <span class="n">oy</span><span class="p">)</span>
<span class="k">if</span> <span class="n">show_animation</span><span class="p">:</span> <span class="c1"># pragma: no cover</span>
<span class="n">plt</span><span class="o">.</span><span class="n">cla</span><span class="p">()</span>
<span class="c1"># for stopping simulation with the esc key.</span>
<span class="n">plt</span><span class="o">.</span><span class="n">gcf</span><span class="p">()</span><span class="o">.</span><span class="n">canvas</span><span class="o">.</span><span class="n">mpl_connect</span><span class="p">(</span>
<span class="s1">&#39;key_release_event&#39;</span><span class="p">,</span>
<span class="k">lambda</span> <span class="n">event</span><span class="p">:</span> <span class="p">[</span><span class="n">exit</span><span class="p">(</span><span class="mi">0</span><span class="p">)</span> <span class="k">if</span> <span class="n">event</span><span class="o">.</span><span class="n">key</span> <span class="o">==</span> <span class="s1">&#39;escape&#39;</span> <span class="k">else</span> <span class="kc">None</span><span class="p">])</span>
<span class="n">plt</span><span class="o">.</span><span class="n">axis</span><span class="p">(</span><span class="s2">&quot;equal&quot;</span><span class="p">)</span>
<span class="n">plt</span><span class="o">.</span><span class="n">plot</span><span class="p">(</span><span class="mf">0.0</span><span class="p">,</span> <span class="mf">0.0</span><span class="p">,</span> <span class="s2">&quot;*r&quot;</span><span class="p">)</span>
<span class="n">v1</span><span class="o">.</span><span class="n">plot</span><span class="p">()</span>
<span class="n">v2</span><span class="o">.</span><span class="n">plot</span><span class="p">()</span>
<span class="c1"># Plot range observation</span>
<span class="k">for</span> <span class="n">ids</span> <span class="ow">in</span> <span class="n">id_sets</span><span class="p">:</span>
<span class="n">x</span> <span class="o">=</span> <span class="p">[</span><span class="n">ox</span><span class="p">[</span><span class="n">i</span><span class="p">]</span> <span class="k">for</span> <span class="n">i</span> <span class="ow">in</span> <span class="nb">range</span><span class="p">(</span><span class="nb">len</span><span class="p">(</span><span class="n">ox</span><span class="p">))</span> <span class="k">if</span> <span class="n">i</span> <span class="ow">in</span> <span class="n">ids</span><span class="p">]</span>
<span class="n">y</span> <span class="o">=</span> <span class="p">[</span><span class="n">oy</span><span class="p">[</span><span class="n">i</span><span class="p">]</span> <span class="k">for</span> <span class="n">i</span> <span class="ow">in</span> <span class="nb">range</span><span class="p">(</span><span class="nb">len</span><span class="p">(</span><span class="n">ox</span><span class="p">))</span> <span class="k">if</span> <span class="n">i</span> <span class="ow">in</span> <span class="n">ids</span><span class="p">]</span>
<span class="k">for</span> <span class="p">(</span><span class="n">ix</span><span class="p">,</span> <span class="n">iy</span><span class="p">)</span> <span class="ow">in</span> <span class="nb">zip</span><span class="p">(</span><span class="n">x</span><span class="p">,</span> <span class="n">y</span><span class="p">):</span>
<span class="n">plt</span><span class="o">.</span><span class="n">plot</span><span class="p">([</span><span class="mf">0.0</span><span class="p">,</span> <span class="n">ix</span><span class="p">],</span> <span class="p">[</span><span class="mf">0.0</span><span class="p">,</span> <span class="n">iy</span><span class="p">],</span> <span class="s2">&quot;-og&quot;</span><span class="p">)</span>
<span class="n">plt</span><span class="o">.</span><span class="n">plot</span><span class="p">([</span><span class="n">ox</span><span class="p">[</span><span class="n">i</span><span class="p">]</span> <span class="k">for</span> <span class="n">i</span> <span class="ow">in</span> <span class="nb">range</span><span class="p">(</span><span class="nb">len</span><span class="p">(</span><span class="n">ox</span><span class="p">))</span> <span class="k">if</span> <span class="n">i</span> <span class="ow">in</span> <span class="n">ids</span><span class="p">],</span>
<span class="p">[</span><span class="n">oy</span><span class="p">[</span><span class="n">i</span><span class="p">]</span> <span class="k">for</span> <span class="n">i</span> <span class="ow">in</span> <span class="nb">range</span><span class="p">(</span><span class="nb">len</span><span class="p">(</span><span class="n">ox</span><span class="p">))</span> <span class="k">if</span> <span class="n">i</span> <span class="ow">in</span> <span class="n">ids</span><span class="p">],</span>
<span class="s2">&quot;o&quot;</span><span class="p">)</span>
<span class="k">for</span> <span class="n">rect</span> <span class="ow">in</span> <span class="n">rects</span><span class="p">:</span>
<span class="n">rect</span><span class="o">.</span><span class="n">plot</span><span class="p">()</span>
<span class="n">plt</span><span class="o">.</span><span class="n">pause</span><span class="p">(</span><span class="mf">0.1</span><span class="p">)</span>
<span class="nb">print</span><span class="p">(</span><span class="s2">&quot;Done&quot;</span><span class="p">)</span>
<span class="k">if</span> <span class="vm">__name__</span> <span class="o">==</span> <span class="s1">&#39;__main__&#39;</span><span class="p">:</span>
<span class="n">main</span><span class="p">()</span>
</pre></div>
</div>
</div>
<footer>
<hr/>
<div role="contentinfo">
<p>&#169; Copyright 2018-2021, Atsushi Sakai.</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>
jQuery(function () {
SphinxRtdTheme.Navigation.enable(true);
});
</script>
</body>
</html>